[
  {
    "path": ".catkin_workspace",
    "content": "# This file currently only serves to mark the location of a catkin workspace for tool integration\n"
  },
  {
    "path": "README.md",
    "content": "# art_racecar  \r\n# art-racecar V1.0  2019.01.30   \r\n# art-racecar V1.1  2019.07.17 完善手柄遥控功能   \r\n\r\nROS racecar  \r\n************************安装************************  \r\ncd  ~/  \r\ngit clone https://github.com/ART-Robot-Release/racecar  \r\ncd racecar  \r\n./install.sh  \r\n配置小车串口udev：  \r\ncd  ~/racecar/src/art_racecar/udev  \r\nsudo  bash art_init.sh  \r\nsudo reboot  \r\n**********************建立地图**********************  \r\n先安装电脑用户名和主机名配置主从机  \r\na) 运行车  \r\nroslaunch art_racecar Run_car.launch  \r\nb) 3.3运行gmapping  \r\nroslaunch art_racecar Run_gmapping.launch  \r\nc) 3.4运行键盘控制  \r\nrosrun art_racecar racecar_teleop.py  \r\n或者手柄遥控  \r\nroslaunch art_racecar teleop_joy.launch  \r\nd) 3.5.本地电脑打开rviz  \r\n本地电脑打开：  \r\nsource  工作空间  \r\nsource art_racecar/art_rviz.sh  \r\nroslaunch art_racecar rviz.launch  \r\ne) 3.6 建立地图  \r\n键盘控制建立地图,按键如下：  \r\nU\tI \tO  \r\nJ\tK\tL  \r\nM\t, \t.  \r\n加减速为W，S.  \r\n手柄控制：  \r\nL侧方向键:上下为加速减速，左右为转向幅度大小调节  \r\nR侧摇杆：控制小车运动  \r\nf) 保存地图（地图直接保存在小车上）  \r\n在art_racecar文件夹下执行：bash save_map.sh  \r\n地图保存在art_racecar/map/mymap.pgm  \r\n检查无误后，修改mymap.pgm替换为test.pgm  \r\n\r\n************************导航************************  \r\na) SSH连接小车（Ubuntu系统为例）sz为小车用户名  \r\nssh sz@192.168.5.101  \r\nb) 运行车  \r\nroslaunch art_racecar Run_car.launch  \r\nc) 运行AMCL  \r\nroslaunch art_racecar amcl_nav.launch  \r\nd) .本地电脑打开rviz  \r\n本地电脑打开：  \r\nsource  工作空间  \r\nsource art_racecar/art_rviz.sh  \r\nroslaunch art_racecar rviz.launch  \r\ne) 4.5 开始导航   \r\n在RVIZ中设定初始坐标，设定目标位置，开始导航  \r\n*********************软件接口***********************  \r\n1.启动底盘  \r\n\t启动底盘需要启动rosserial_python节点。  \r\n\t设置参考art_racecar/launch/Run_car.launch  \r\n2.发布地盘控制指令：  \r\n\t通过发布Twist消息控制底盘。  \r\n\t线速度：twist.linear.x,这里的线速度范围为500～2500（对应PWM脉冲为0.5ms～2.5ms）,1500为静止，1500-2500为正向速度，500-1500为反向速度。  \r\n\t角速度：twist.angular.x，这里角度范围为0～180度,90度为中间值，90-180度左转，0-90度右转。  \r\n3.里程计数据：  \r\n\t里程计采用激光雷达和IMU数据融合的里程计。  \r\n\t需要先启动IMU节点和雷达节点，参考art_racecar/launch/Run_car.launch  \r\n\t然后启动rf2o节点，用rf2o生成激光里程计，参考art_racecar/launch/includes/rf2o.launch.xml  \r\n\t再启动robot_localization用EKF融合里程计信息，参考art_racecar/launch/Run_gmapping.launch  \r\n\t\r\n\r\n\r\n\t\t\t\t\t\t\t\t\t\t\t\r\n\t\t\t\t\t\t\t\t\t\t\t# Steven Zhang\r\n\t\t\t\t\t\t\t\t\t\t\t# 2019.01.30\r\n\t\r\n"
  },
  {
    "path": "install.sh",
    "content": "#!/bin/bash\n\n# Varibles\nrosversion=\"kinetic\"\n# Install the ros\n\nif [ `id -u` == 0 ]; then\n\techo \"Don't running this use root(sudo).\"\n\texit 0\nfi\n\necho \"Start to install the ros, http://wiki.ros.org/$rosversion/Installation/Ubuntu\"\necho \"Update the software list\"\nsudo 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'\nsudo apt-key adv --keyserver hkp://ha.pool.sks-keyservers.net:80 --recv-key C1CF6E31E6BADE8868B172B4F42ED6FBAB17C654\nsudo apt-get update\n\necho \"Install the ros from apt\" \nsudo apt-get install ros-$rosversion-desktop-full -y\nsudo rosdep init\nrosdep update\n\necho \"Setup the ROS environment variables\"\necho -e \"if [ -f /opt/ros/kinetic/setup.bash ]; then\\n\\tsource /opt/ros/kinetic/setup.bash\\nfi\" >> ~/.bashrc\necho \"source ~/racecar/devel/setup.bash\" >> ~/.bashrc\nsource ~/.bashrc\n\necho \"Install the rosinstall\"\nsudo apt-get install python-rosinstall -y\n\necho \"Install the ssh\"\nsudo apt-get install ssh -y\n\necho \"Install the ntpdate\"\nsudo apt-get install ntpdate -y\n\necho \"Install the chrony\"\nsudo apt-get install chrony -y\n\n# Install the dependecies for the project \necho \"Start to config for the project\"\n\n#echo \"Install the python dependecies\"\n#sudo apt-get install python-numpy python-scipy python-matplotlib ipython ipython-notebook python-pandas python-sympy python-nose -y\n\n#echo \"Install the eigen3\"\n#sudo apt install libeigen3-dev -y\n\n#echo \"Install the nlopt\"\n#sudo apt install libnlopt* -y\n\n\n\necho \"Install the ROS package for art_racecar\"\nsudo apt-get install ros-$rosversion-joy -y\nsudo apt-get install ros-$rosversion-move-base -y\nsudo apt-get install ros-$rosversion-mrpt* -y\nsudo apt-get install ros-$rosversion-geographic-msgs -y\nsudo apt-get install ros-$rosversion-map-server -y\nsudo apt-get install ros-$rosversion-gmapping -y\nsudo apt-get install ros-$rosversion-amcl -y\nsudo apt-get install ros-$rosversion-rviz-imu-plugin -y\nsudo apt-get install ros-$rosversion-dwa-local-planner -y\n\necho \"--Finish\"\n"
  },
  {
    "path": "src/art_driver/CMakeLists.txt",
    "content": "# Created by Steven Zhang on 18-12-29.\n# art racecar\n\ncmake_minimum_required(VERSION 2.8.3)\nproject(art_driver)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED COMPONENTS\n  roscpp\n  rospy\n  std_msgs\n)\n\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a run_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a run_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a run_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES art_driver\n#  CATKIN_DEPENDS roscpp rospy std_msgs\n#  DEPENDS system_lib\n   CATKIN_DEPENDS roscpp rospy std_msgs\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n   include\n   ${catkin_INCLUDE_DIRS}\n)\n\n\n\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n add_executable(${PROJECT_NAME}_node src/art_racecar.cpp\n         include/art_racecar_driver.h\n         )\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n\n\n#find_library(./lib libart_driver.a)\n\n\n\n\n\n#link_directories(./lib/libart_driver.a)\n target_link_libraries(${PROJECT_NAME}_node\n   ${catkin_LIBRARIES}\n   ${PROJECT_SOURCE_DIR}/lib/libart_driver.a\n   \n )\n\n#target_link_libraries(${PROJECT_NAME}_node\n#\n#        ${CMAKE_SOURCE_DIR}/lib/libart_driver.a -lm -ldl\n#\n #       )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\n# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_art_driver.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\n"
  },
  {
    "path": "src/art_driver/README",
    "content": "/*******************************************************************/\n/***************art_driverr*****************************************/\n/*******************************************************************/\n这是art racecar的底层驱动例程\n这个历程订阅/car/cmd_vel的twist的消息,发送给底层单片机\n具体可以参考art_racecar.cpp\n使用send_cmd()函数向单片机发送指令,函数参数分别为电机PWM和舵机PWM.\nPWM范围为500-2500us.\n\n\n/*********************************************北京钢铁侠科技 **********/\n/*********************************************Steven Zhang ***********/\n/*********************************************2018.12.29**************/\n"
  },
  {
    "path": "src/art_driver/include/art_racecar_driver.h",
    "content": "\n//\n// Created by Steven Zhang on 18-12-14.\n// art racecar\n//\n\n#ifndef ART_RACECAR_DRIVER\n#define ART_RACECAR_DRIVER\n#include <stdint.h>\n#include <unistd.h>\n\n#if defined(__cplusplus)\nextern \"C\" {\n#endif\n\n\n\n\nint Open_Serial_Dev(char *dev);\n\nint art_racecar_init(int speed,char *dev);//设置波特率和串口设备\n\n\nunsigned char send_cmd(uint16_t motor_pwm,uint16_t servo_pwm);//发送指令(电机PWM,舵机PWM),单位为us.\n\n\n\n\n\n\n\n#if defined(__cplusplus)\n}\n#endif\n#endif\n"
  },
  {
    "path": "src/art_driver/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>art_driver</name>\n  <version>0.1.0</version>\n  <description>The art_car package</description>\n\n  <!-- One maintainer tag required, multiple allowed, one person per tag -->\n  <!-- Example:  -->\n  <!-- <maintainer email=\"jane.doe@example.com\">Jane Doe</maintainer> -->\n  <maintainer email=\"zhangnan@artrobot.com\">zn</maintainer>\n\n\n  <!-- One license tag required, multiple allowed, one license per tag -->\n  <!-- Commonly used license strings: -->\n  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->\n  <license>TODO</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/art_driver</url> -->\n\n\n  <!-- Author tags are optional, multiple are allowed, one per tag -->\n  <!-- Authors do not have to be maintainers, but could be -->\n  <!-- Example: -->\n  <!-- <author email=\"jane.doe@example.com\">Jane Doe</author> -->\n\n\n  <!-- The *depend tags are used to specify dependencies -->\n  <!-- Dependencies can be catkin packages or system dependencies -->\n  <!-- Examples: -->\n  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->\n  <!--   <depend>roscpp</depend> -->\n  <!--   Note that this is equivalent to the following: -->\n  <!--   <build_depend>roscpp</build_depend> -->\n  <!--   <exec_depend>roscpp</exec_depend> -->\n  <!-- Use build_depend for packages you need at compile time: -->\n  <!--   <build_depend>message_generation</build_depend> -->\n  <!-- Use build_export_depend for packages you need in order to build against this package: -->\n  <!--   <build_export_depend>message_generation</build_export_depend> -->\n  <!-- Use buildtool_depend for build tool packages: -->\n  <!--   <buildtool_depend>catkin</buildtool_depend> -->\n  <!-- Use exec_depend for packages you need at runtime: -->\n  <!--   <exec_depend>message_runtime</exec_depend> -->\n  <!-- Use test_depend for packages you need only for testing: -->\n  <!--   <test_depend>gtest</test_depend> -->\n  <!-- Use doc_depend for packages you need only for building documentation: -->\n  <!--   <doc_depend>doxygen</doc_depend> -->\n  <buildtool_depend>catkin</buildtool_depend>\n  <build_depend>roscpp</build_depend>\n  <build_depend>rospy</build_depend>\n  <build_depend>std_msgs</build_depend>\n  <build_export_depend>roscpp</build_export_depend>\n  <build_export_depend>rospy</build_export_depend>\n  <build_export_depend>std_msgs</build_export_depend>\n  <exec_depend>roscpp</exec_depend>\n  <exec_depend>rospy</exec_depend>\n  <exec_depend>std_msgs</exec_depend>\n\n\n  <!-- The export tag contains other, unspecified, tags -->\n  <export>\n    <!-- Other tools can request additional information be placed here -->\n\n  </export>\n</package>\n"
  },
  {
    "path": "src/art_driver/src/art_racecar.cpp",
    "content": "//\n// Created by Steven Zhang on 18-12-14.\n// art racecar\n//\n\n#include \"../include/art_racecar_driver.h\"\n#include <ros/ros.h>\n#include <ros/package.h>\n#include <geometry_msgs/Twist.h>\n\nvoid TwistCallback(const geometry_msgs::Twist& twist)\n{\n    double angle;\n    //ROS_INFO(\"x= %f\", twist.linear.x);\n    //ROS_INFO(\"z= %f\", twist.angular.z);\n    angle = 2500.0 - twist.angular.z * 2000.0 / 180.0;\n    //ROS_INFO(\"angle= %d\",uint16_t(angle));\n    send_cmd(uint16_t(twist.linear.x),uint16_t(angle));\n}\n\nint main(int argc, char** argv)\n{\n    char data[] = \"/dev/car\";\n    art_racecar_init(38400,data);\n    ros::init(argc, argv, \"art_driver\");\n    ros::NodeHandle n;\n\n    ros::Subscriber sub = n.subscribe(\"/car/cmd_vel\",1,TwistCallback);\n\n\n\n    ros::spin();\n\n}"
  },
  {
    "path": "src/art_imu/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(art_imu)\n\n\nadd_definitions(-std=c++11)\nfind_package(catkin REQUIRED roscpp sensor_msgs tf cmake_modules)\n\nfind_package(catkin REQUIRED COMPONENTS)\n\n\ninclude_directories(${catkin_INCLUDE_DIRS})\n\nfind_package(Eigen REQUIRED)\n\ncatkin_package(\n)\n\nadd_executable(art_imu\n  src/art_imu.cc\n)\n\ntarget_link_libraries(art_imu\n  ${catkin_LIBRARIES}\n)\n"
  },
  {
    "path": "src/art_imu/launch/imu.launch",
    "content": "<?xml version=\"1.0\"?>\n<launch>\n  <node pkg=\"art_imu\"\n        name=\"imu\"\n        type=\"art_imu\"\n        output=\"screen\">\n    <param name=\"port\" value=\"/dev/imu\"/>\n    \n\n    <param name=\"model\" value=\"art_imu_02a\"/>\n    <param name=\"baud\" value=\"115200\"/>\n\n  </node>\n\n</launch>\n"
  },
  {
    "path": "src/art_imu/launch/imu_test.launch",
    "content": "<?xml version=\"1.0\"?>\n<launch>\n  <node pkg=\"art_imu\"\n        name=\"imu\"\n        type=\"art_imu\"\n        output=\"screen\">\n    <param name=\"port\" value=\"/dev/ttyUSB0\"/>\n    \n\n    <param name=\"model\" value=\"art_imu_02a\"/>\n    <param name=\"baud\" value=\"115200\"/>\n\n  </node>\n\n</launch>\n"
  },
  {
    "path": "src/art_imu/launch/rviz.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <arg name=\"use_rviz\" default=\"true\" />\n\n   \n\n    <!-- Rviz -->\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find art_imu)/rviz/imu.rviz\" if=\"$(arg use_rviz)\" />\n</launch>\n"
  },
  {
    "path": "src/art_imu/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>art_imu</name>\n  <version>0.1.0</version>\n  <description>The art_imu package</description>\n  <maintainer email=\"zhangnan@artrobot.com\">Steven Zhang</maintainer>\n\n  <author>Steven Zhang</author>\n  <license>BSD</license>\n  <buildtool_depend>catkin</buildtool_depend>\n  <buildtool_depend>roscpp</buildtool_depend>\n  <buildtool_depend>sensor_msgs</buildtool_depend>\n  <buildtool_depend>tf</buildtool_depend>\n  <buildtool_depend>cmake_modules</buildtool_depend>\n\n  <run_depend>catkin</run_depend>\n  <run_depend>roscpp</run_depend>\n  <run_depend>sensor_msgs</run_depend>\n  <run_depend>tf</run_depend>\n  <export>\n  </export>\n</package>\n"
  },
  {
    "path": "src/art_imu/rviz/imu.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Imu1\n        - /Imu1/Box properties1\n        - /Imu1/Axes properties1\n        - /Imu1/Acceleration properties1\n      Splitter Ratio: 0.5\n    Tree Height: 655\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679016\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: \"\"\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.0299999993\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 2666\n      Min Color: 0; 0; 0\n      Min Intensity: 2\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.0500000007\n      Style: Flat Squares\n      Topic: /scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        {}\n      Update Interval: 0\n      Value: true\n    - Acceleration properties:\n        Acc. vector alpha: 1\n        Acc. vector color: 255; 0; 0\n        Acc. vector scale: 1\n        Derotate acceleration: true\n        Enable acceleration: false\n      Axes properties:\n        Axes scale: 2\n        Enable axes: true\n      Box properties:\n        Box alpha: 1\n        Box color: 255; 0; 0\n        Enable box: true\n        x_scale: 0.400000006\n        y_scale: 0.300000012\n        z_scale: 0.300000012\n      Class: rviz_imu_plugin/Imu\n      Enabled: true\n      Name: Imu\n      Topic: /imu_data\n      Unreliable: false\n      Value: true\n      fixed_frame_orientation: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: IMU_link\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 19.7761364\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 1.2478348\n        Y: -3.33640909\n        Z: 0.00110054587\n      Focal Shape Fixed Size: true\n      Focal Shape Size: 0.0500000007\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Pitch: 1.56979632\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 3.04539394\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 936\n  Hide Left Dock: false\n  Hide Right Dock: true\n  QMainWindow State: 000000ff00000000fd00000004000000000000016a0000031efc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000031e000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006100000001d1000000b50000000000000000fb0000000a0049006d0061006700650000000000ffffffff0000000000000000fb0000000a0049006d00610067006501000002ab00000113000000000000000000000001000001a30000025efc0200000004fb0000000a0049006d00610067006500000000280000025e0000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005160000003efc0100000002fb0000000800540069006d00650100000000000005160000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003a60000031e00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1302\n  X: 538\n  Y: 105\n"
  },
  {
    "path": "src/art_imu/src/art_imu.cc",
    "content": "#include <deque>\n#include <ros/ros.h>\n#include <sensor_msgs/Imu.h>\n#include <sensor_msgs/MagneticField.h>\n#include <sensor_msgs/NavSatFix.h>\n#include <tf/tf.h>\n#include <eigen3/Eigen/Geometry> \n#include <chrono>\n#include <locale>\n#include <tuple>\n#include <algorithm>\n#include <iostream>\n#include <string>\n#include <sstream>\n#include <stdexcept>\n#include <boost/assert.hpp>\n#include <boost/asio.hpp>\n#include <boost/asio/serial_port.hpp>\n\nextern \"C\" {\n#include <fcntl.h>\n#include <getopt.h>\n#include <poll.h>\n#include <time.h>\n#include <errno.h>\n#include <termios.h>\n#include <sys/ioctl.h>\n#include <assert.h>\n#include <unistd.h> //  close\n#include <string.h> //  strerror\n}\n\n\nusing namespace std;\n\nstatic int data_length = 81;\n\n\nboost::asio::serial_port* serial_port = 0;\nstatic const uint8_t stop[6] = {0xA5, 0x5A, 0x04, 0x02, 0x06, 0xAA};\nstatic const uint8_t mode[6] = {0xA5, 0x5A, 0x04, 0x01, 0x05, 0xAA};\nstatic uint8_t data_raw[200];\nstatic std::vector<uint8_t> buffer_;\nstatic std::deque<uint8_t> queue_;\nstatic std::string name, frame_id;\nstatic sensor_msgs::Imu msg;\nstatic sensor_msgs::MagneticField msg_mag;\nstatic sensor_msgs::NavSatFix msg_gps;\nstatic int fd_ = -1;\nstatic ros::Publisher pub, pub_mag, pub_gps;\nstatic uint8_t tmp[81];\n\nstatic float d2f_acc(uint8_t a[2])\n{\n    int16_t acc = a[0];\n    acc = (acc << 8) | a[1];\n    return ((float) acc) / 16384.0f;\n}\n\nstatic float d2f_gyro(uint8_t a[2])\n{\n    int16_t acc = a[0];\n    acc = (acc << 8) | a[1];\n    return ((float) acc) / 32.8f;\n}\n\nstatic float d2f_mag(uint8_t a[2])\n{\n    int16_t acc = a[0];\n    acc = (acc << 8) | a[1];\n    return ((float) acc) / 1.0f;\n}\n\nstatic float d2f_euler(uint8_t a[2])\n{\n    int16_t acc = a[0];\n    acc = (acc << 8) | a[1];\n    return ((float) acc) / 10.0f;\n}\n\n\nstatic double d2f_latlon(uint8_t a[4])\n{\n    int64_t high = a[0];\n    high = (high << 8) | a[1];\n\n    int64_t low = a[2];\n    low = (low << 8) | a[3];\n    return (double)((high << 8) | low);\n}\n\nstatic double d2f_gpsvel(uint8_t a[2])\n{\n    int16_t acc = a[0];\n    acc = (acc << 8) | a[1];\n    return ((float) acc) / 10.0f;\n}\n\nstatic float d2ieee754(uint8_t a[4])\n{\n    union fnum {\n        float f_val;\n        uint8_t d_val[4];\n    } f;\n\n    memcpy(f.d_val, a, 4);\n    return f.f_val;\n}\n\n\nint uart_set(int fd, int baude, int c_flow, int bits, char parity, int stop)\n{\n    struct termios options;\n \n    if(tcgetattr(fd, &options) < 0)\n    {\n        perror(\"tcgetattr error\");\n        return -1;\n    }\n\n    cfsetispeed(&options,B115200);\n    cfsetospeed(&options,B115200);\n\n    options.c_cflag |= CLOCAL;\n    options.c_cflag |= CREAD;\n\n    switch(c_flow)\n    {\n        case 0:\n            options.c_cflag &= ~CRTSCTS;\n            break;\n        case 1:\n            options.c_cflag |= CRTSCTS;\n            break;\n        case 2:\n            options.c_cflag |= IXON|IXOFF|IXANY;\n            break;\n        default:\n            fprintf(stderr,\"Unkown c_flow!\\n\");\n            return -1;\n    }\n\n    switch(bits)\n    {\n        case 5:\n            options.c_cflag &= ~CSIZE;\n            options.c_cflag |= CS5;\n            break;\n        case 6:\n            options.c_cflag &= ~CSIZE;\n            options.c_cflag |= CS6;\n            break;\n        case 7:\n            options.c_cflag &= ~CSIZE;\n            options.c_cflag |= CS7;\n            break;\n        case 8:\n            options.c_cflag &= ~CSIZE;\n            options.c_cflag |= CS8;\n            break;\n        default:\n            fprintf(stderr,\"Unkown bits!\\n\");\n            return -1;\n    }\n\n    switch(parity)\n    {\n        case 'n':\n        case 'N':\n            options.c_cflag &= ~PARENB;\n            options.c_cflag &= ~INPCK;\n            break;\n\n        case 's':\n        case 'S':\n            options.c_cflag &= ~PARENB;\n            options.c_cflag &= ~CSTOPB;\n            break;\n\n        case 'o':\n        case 'O':\n            options.c_cflag |= PARENB;\n            options.c_cflag |= PARODD;\n            options.c_cflag |= INPCK;\n            options.c_cflag |= ISTRIP;\n            break;\n\n        case 'e':\n        case 'E':\n            options.c_cflag |= PARENB;\n            options.c_cflag &= ~PARODD;\n            options.c_cflag |= INPCK;\n            options.c_cflag |= ISTRIP;\n            break;\n        default:\n            fprintf(stderr,\"Unkown parity!\\n\");\n            return -1;\n    }\n\n    switch(stop)\n    {\n        case 1:\n            options.c_cflag &= ~CSTOPB;\n            break;\n        case 2:\n            options.c_cflag |= CSTOPB;\n            break;\n        default:\n            fprintf(stderr,\"Unkown stop!\\n\");\n            return -1;\n    }\n\n    options.c_oflag &= ~OPOST;\n    options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);\n    options.c_cc[VTIME] = 0;\n    options.c_cc[VMIN] = 1;\n\n    tcflush(fd,TCIFLUSH);\n\n    if(tcsetattr(fd,TCSANOW,&options) < 0)\n    {\n        perror(\"tcsetattr failed\");\n        return -1;\n    }\n\n    return 0;\n\n}\n\n\nint main(int argc, char** argv)\n{\n    ros::init(argc, argv, \"imu\");\n    ros::NodeHandle n(\"~\");\n\n    name = ros::this_node::getName();\n\n    std::string port;\n    if (n.hasParam(\"port\"))\n    n.getParam(\"port\", port);\n    else\n    {\n        ROS_ERROR(\"%s: must provide a port\", name.c_str());\n        return -1;\n    }\n\n    std::string model;\n    if (n.hasParam(\"model\"))\n    n.getParam(\"model\", model);\n    else\n    {\n        ROS_ERROR(\"%s: must provide a model name\", name.c_str());\n        return -1;\n    }\n\n\n    ROS_WARN(\"Model set to %s\", model.c_str());\n\n    int baud;\n    if (n.hasParam(\"baud\"))\n    n.getParam(\"baud\", baud);\n    else\n    {\n        ROS_ERROR(\"%s: must provide a baudrate\", name.c_str());\n        return -1;\n    }\n\n\n\n    ROS_WARN(\"Baudrate set to %d\", baud);\n  \n    n.param(\"frame_id\", frame_id, string(\"IMU_link\"));\n\n    double delay;\n    n.param(\"delay\", delay, 0.0);\n\n    boost::asio::io_service io_service;\n    serial_port = new boost::asio::serial_port(io_service);\n    try\n    {\n        serial_port->open(port);\n    }\n    catch (boost::system::system_error &error)\n    {\n        ROS_ERROR(\"%s: Failed to open port %s with error %s\",\n                name.c_str(), port.c_str(), error.what());\n        return -1;\n    }\n\n    if (!serial_port->is_open())\n    {\n        ROS_ERROR(\"%s: failed to open serial port %s\",\n                name.c_str(), port.c_str());\n        return -1;\n    }\n\n    typedef boost::asio::serial_port_base sb;\n\n    sb::baud_rate baud_option(baud);\n     sb::flow_control flow_control(sb::flow_control::none);\n    sb::parity parity(sb::parity::none);\n    sb::stop_bits stop_bits(sb::stop_bits::one);\n\n    serial_port->set_option(baud_option);\n    serial_port->set_option(flow_control);\n    serial_port->set_option(parity);\n    serial_port->set_option(stop_bits);\n\n    const char *path = port.c_str();\n    fd_ = open(path, O_RDWR);\n    if(fd_ < 0)\n    {\n        ROS_ERROR(\"Port Error!: %s\", path);\n        return -1;\n    }\n\n    int kk = 0;\n    double vyaw_sum = 0;\n    double vyaw_bias = 0;\n    pub = n.advertise<sensor_msgs::Imu>(\"/imu_data\", 1);\n    pub_mag = n.advertise<sensor_msgs::MagneticField>(\"mag\", 1);\n    pub_gps = n.advertise<sensor_msgs::NavSatFix>(\"gps\", 1);\n\n\n\tif(model == \"art_imu_02a\")\n    {\n       write(fd_, stop, 6);\n       usleep(1000 * 1000);\n       write(fd_, mode, 6);\n       usleep(1000 * 1000);\n       data_length = 40;\n   \t}\n\n\n    ROS_WARN(\"Streaming Data...\");\n    while (n.ok())\n    {\n        read(fd_, tmp, sizeof(uint8_t) * data_length);\n        memcpy(data_raw, tmp, sizeof(uint8_t) * data_length);\n\n        bool found = false;\n        for(kk = 0; kk < data_length - 1; ++kk)\n        {\n            \t  \n            if(model == \"art_imu_02a\" && data_raw[kk] == 0xA5 && data_raw[kk + 1] == 0x5A)\n            {\n                unsigned char *data = data_raw + kk;\n\n                uint8_t data_length = data[2];\n\n                uint32_t checksum = 0;\n                for(int i = 0; i < data_length - 1  ; ++i)\n                {\n                    checksum += (uint32_t) data[i+2];\n                }\n\n                uint16_t check = checksum % 256;\n                uint16_t check_true = data[data_length+1];\n\n                if (check != check_true)\n                {\n                    printf(\"check error,please wait\\n\");\n                    continue;\n                }\n\n                Eigen::Vector3d ea0((-vyaw_bias-d2f_euler(data + 3)) * M_PI / 180.0,\n                                 0,\n                                  0);\n                Eigen::Matrix3d R;\n                R = Eigen::AngleAxisd(ea0[0], ::Eigen::Vector3d::UnitZ())\n                  * Eigen::AngleAxisd(ea0[1], ::Eigen::Vector3d::UnitY())\n                  * Eigen::AngleAxisd(ea0[2], ::Eigen::Vector3d::UnitX());\n                Eigen::Quaterniond q;\n                q = R;\n                msg.orientation.w = (double)q.w();\n                msg.orientation.x = (double)q.x();\n                msg.orientation.y = (double)q.y();\n                msg.orientation.z = (double)q.z();\n\n                msg.header.stamp = ros::Time::now();\n                msg.header.frame_id = frame_id;\n                msg.angular_velocity.x = d2f_gyro(data + 15);\n                msg.angular_velocity.y = d2f_gyro(data + 17);\n                msg.angular_velocity.z = d2f_gyro(data + 19);\n                msg.linear_acceleration.x = d2f_acc(data + 9) * 9.81;\n                msg.linear_acceleration.y = d2f_acc(data + 11) * 9.81;\n                msg.linear_acceleration.z = d2f_acc(data + 13) * 9.81;\n                pub.publish(msg);\n\n                msg_mag.magnetic_field.x = d2f_mag(data + 21);\n                msg_mag.magnetic_field.y = d2f_mag(data + 23);\n                msg_mag.magnetic_field.z = d2f_mag(data + 25);\n                msg_mag.header.stamp = msg.header.stamp;\n                msg_mag.header.frame_id = msg.header.frame_id;\n                pub_mag.publish(msg_mag);\n\n                found = true;\n            }\n        }\n    }\n\n    // Stop continous and close device\n    ROS_WARN(\"Wait 0.1s\");\n    ros::Duration(0.1).sleep();\n    ::close(fd_);\n\n    return 0;\n}\n"
  },
  {
    "path": "src/art_racecar/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(art_racecar)\n\n## Compile as C++11, supported in ROS Kinetic and newer\n# add_compile_options(-std=c++11)\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED COMPONENTS\n  geometry_msgs\n  sensor_msgs\n  joy\n  move_base\n  tf\n  roscpp\n  rospy\n  std_msgs\n  visualization_msgs\n  dynamic_reconfigure\n)\n\ngenerate_dynamic_reconfigure_options(cfg/imu.cfg)\n\n#catkin_package(DEPENDS CATKIN DEPENDS dynamic_reconfigure)\n## System dependencies are found with CMake's conventions\n# find_package(Boost REQUIRED COMPONENTS system)\n\n\n## Uncomment this if the package has a setup.py. This macro ensures\n## modules and global scripts declared therein get installed\n## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html\n# catkin_python_setup()\n\n################################################\n## Declare ROS messages, services and actions ##\n################################################\n\n## To declare and build messages, services or actions from within this\n## package, follow these steps:\n## * Let MSG_DEP_SET be the set of packages whose message types you use in\n##   your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).\n## * In the file package.xml:\n##   * add a build_depend tag for \"message_generation\"\n##   * add a build_depend and a run_depend tag for each package in MSG_DEP_SET\n##   * If MSG_DEP_SET isn't empty the following dependency has been pulled in\n##     but can be declared for certainty nonetheless:\n##     * add a run_depend tag for \"message_runtime\"\n## * In this file (CMakeLists.txt):\n##   * add \"message_generation\" and every package in MSG_DEP_SET to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * add \"message_runtime\" and every package in MSG_DEP_SET to\n##     catkin_package(CATKIN_DEPENDS ...)\n##   * uncomment the add_*_files sections below as needed\n##     and list every .msg/.srv/.action file to be processed\n##   * uncomment the generate_messages entry below\n##   * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)\n\n## Generate messages in the 'msg' folder\n# add_message_files(\n#   FILES\n#   Message1.msg\n#   Message2.msg\n# )\n\n## Generate services in the 'srv' folder\n# add_service_files(\n#   FILES\n#   Service1.srv\n#   Service2.srv\n# )\n\n## Generate actions in the 'action' folder\n# add_action_files(\n#   FILES\n#   Action1.action\n#   Action2.action\n# )\n\n## Generate added messages and services with any dependencies listed here\n# generate_messages(\n#   DEPENDENCIES\n#   std_msgs\n# )\n\n################################################\n## Declare ROS dynamic reconfigure parameters ##\n################################################\n\n## To declare and build dynamic reconfigure parameters within this\n## package, follow these steps:\n## * In the file package.xml:\n##   * add a build_depend and a run_depend tag for \"dynamic_reconfigure\"\n## * In this file (CMakeLists.txt):\n##   * add \"dynamic_reconfigure\" to\n##     find_package(catkin REQUIRED COMPONENTS ...)\n##   * uncomment the \"generate_dynamic_reconfigure_options\" section below\n##     and list every .cfg file to be processed\n\n## Generate dynamic reconfigure parameters in the 'cfg' folder\n# generate_dynamic_reconfigure_options(\n#   cfg/DynReconf1.cfg\n#   cfg/DynReconf2.cfg\n# )\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if your package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n#  INCLUDE_DIRS include\n#  LIBRARIES art_racecar\n  CATKIN_DEPENDS roscpp rospy std_msgs\n#  DEPENDS system_lib\n)\n\n###########\n## Build ##\n###########\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(\n include\n  ${catkin_INCLUDE_DIRS}\n)\n\n## Declare a C++ library\n# add_library(${PROJECT_NAME}\n#   src/${PROJECT_NAME}/art_racecar.cpp\n# )\n\n## Add cmake target dependencies of the library\n## as an example, code may need to be generated before libraries\n## either from message generation or dynamic reconfigure\n# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Declare a C++ executable\n## With catkin_make all packages are built within a single CMake context\n## The recommended prefix ensures that target names across packages don't collide\n# add_executable(${PROJECT_NAME}_node src/art_racecar_node.cpp)\n\n## Rename C++ executable without prefix\n## The above recommended prefix causes long target names, the following renames the\n## target back to the shorter version for ease of user use\n## e.g. \"rosrun someones_pkg node\" instead of \"rosrun someones_pkg someones_pkg_node\"\n# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX \"\")\n\n## Add cmake target dependencies of the executable\n## same as for the library above\n# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})\n\n## Specify libraries to link a library or executable target against\n# target_link_libraries(${PROJECT_NAME}_node\n#   ${catkin_LIBRARIES}\n# )\n\n#############\n## Install ##\n#############\n\n# all install targets should use catkin DESTINATION variables\n# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html\n\n## Mark executable scripts (Python etc.) for installation\n## in contrast to setup.py, you can choose the destination\n# install(PROGRAMS\n#   scripts/my_python_script\n#   DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark executables and/or libraries for installation\n# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node\n#   ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n#   RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n# )\n\n## Mark cpp header files for installation\n# install(DIRECTORY include/${PROJECT_NAME}/\n#   DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n#   FILES_MATCHING PATTERN \"*.h\"\n#   PATTERN \".svn\" EXCLUDE\n# )\n\n## Mark other files for installation (e.g. launch and bag files, etc.)\n# install(FILES\n#   # myfile1\n#   # myfile2\n#   DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n# )\n\n#############\n## Testing ##\n#############\n\n## Add gtest based cpp test target and link libraries\n# catkin_add_gtest(${PROJECT_NAME}-test test/test_art_racecar.cpp)\n# if(TARGET ${PROJECT_NAME}-test)\n#   target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})\n# endif()\n\n## Add folders to be run by python nosetests\n# catkin_add_nosetests(test)\ninstall(DIRECTORY launch\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\ninstall(DIRECTORY src\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n\n\n\nadd_executable(art_car_controller \n\tsrc/art_car_controller.cpp \n\tsrc/art_car_controller.hpp\n\tsrc/PID.h\n)\ntarget_link_libraries(art_car_controller \n\t${catkin_LIBRARIES}\n\t${PROJECT_SOURCE_DIR}/src/lib/libart_controller.a\n)\n#add_dependencies(art_car_controller art_car_generate_messages_cpp)\n\n\n\n\n\n\n\n\n"
  },
  {
    "path": "src/art_racecar/README.md",
    "content": "# art_racecar  \r\n# art-racecar V1.0  2019.01.30   \r\n# art-racecar V1.1  2019.07.17 完善手柄遥控功能   \r\n\r\nROS racecar  \r\n************************安装************************  \r\ncd  ~/  \r\ngit clone https://github.com/ART-Robot-Release/racecar  \r\ncd racecar  \r\n./install.sh  \r\n配置小车串口udev：  \r\ncd  ~/racecar/src/art_racecar/udev  \r\nsudo  bash art_init.sh  \r\nsudo reboot  \r\n**********************建立地图**********************  \r\n先安装电脑用户名和主机名配置主从机  \r\na) 运行车  \r\nroslaunch art_racecar Run_car.launch  \r\nb) 3.3运行gmapping  \r\nroslaunch art_racecar Run_gmapping.launch  \r\nc) 3.4运行键盘控制  \r\nrosrun art_racecar racecar_teleop.py  \r\n或者手柄遥控  \r\nroslaunch art_racecar teleop_joy.launch  \r\nd) 3.5.本地电脑打开rviz  \r\n本地电脑打开：  \r\nsource  工作空间  \r\nsource art_racecar/art_rviz.sh  \r\nroslaunch art_racecar rviz.launch  \r\ne) 3.6 建立地图  \r\n键盘控制建立地图,按键如下：  \r\nU\tI \tO  \r\nJ\tK\tL  \r\nM\t, \t.  \r\n加减速为W，S.  \r\n手柄控制：  \r\nL侧方向键:上下为加速减速，左右为转向幅度大小调节  \r\nR侧摇杆：控制小车运动  \r\nf) 保存地图（地图直接保存在小车上）  \r\n在art_racecar文件夹下执行：bash save_map.sh  \r\n地图保存在art_racecar/map/mymap.pgm  \r\n检查无误后，修改mymap.pgm替换为test.pgm  \r\n\r\n************************导航************************  \r\na) SSH连接小车（Ubuntu系统为例）sz为小车用户名  \r\nssh sz@192.168.5.101  \r\nb) 运行车  \r\nroslaunch art_racecar Run_car.launch  \r\nc) 运行AMCL  \r\nroslaunch art_racecar amcl_nav.launch  \r\nd) .本地电脑打开rviz  \r\n本地电脑打开：  \r\nsource  工作空间  \r\nsource art_racecar/art_rviz.sh  \r\nroslaunch art_racecar rviz.launch  \r\ne) 4.5 开始导航   \r\n在RVIZ中设定初始坐标，设定目标位置，开始导航  \r\n*********************软件接口***********************  \r\n1.启动底盘  \r\n\t启动底盘需要启动rosserial_python节点。  \r\n\t设置参考art_racecar/launch/Run_car.launch  \r\n2.发布地盘控制指令：  \r\n\t通过发布Twist消息控制底盘。  \r\n\t线速度：twist.linear.x,这里的线速度范围为500～2500（对应PWM脉冲为0.5ms～2.5ms）,1500为静止，1500-2500为正向速度，500-1500为反向速度。  \r\n\t角速度：twist.angular.x，这里角度范围为0～180度,90度为中间值，90-180度左转，0-90度右转。  \r\n3.里程计数据：  \r\n\t里程计采用激光雷达和IMU数据融合的里程计。  \r\n\t需要先启动IMU节点和雷达节点，参考art_racecar/launch/Run_car.launch  \r\n\t然后启动rf2o节点，用rf2o生成激光里程计，参考art_racecar/launch/includes/rf2o.launch.xml  \r\n\t再启动robot_localization用EKF融合里程计信息，参考art_racecar/launch/Run_gmapping.launch  \r\n\t\r\n\r\n\r\n\t\t\t\t\t\t\t\t\t\t\t\r\n\t\t\t\t\t\t\t\t\t\t\t# Steven Zhang\r\n\t\t\t\t\t\t\t\t\t\t\t# 2019.01.30\r\n\t\r\n"
  },
  {
    "path": "src/art_racecar/art_rviz.sh",
    "content": "#!/bin/bash\n\n#for open rviz and set ROS master ip\n#Steven.Zhang\n#2018.03.09\n\nfunction get_ip_address { ifconfig | fgrep -v 127.0.0.1 | fgrep 'Mask:255.255.255.0' | egrep -o 'addr:[^ ]*' | fgrep '.8.'| sed 's/^.*://'; }        \n\n#export ROS_IP=$(get_ip_address) \nexport ROS_IP=`hostname -I`\nexport ROS_MASTER_URI=http://192.168.5.101:11311\n\n##source ../devel/setup.bash\n#rosrun rviz rviz \n"
  },
  {
    "path": "src/art_racecar/cfg/imu.cfg",
    "content": "#!/usr/bin/env python\nPACKAGE = \"art_racecar\"\n\nfrom dynamic_reconfigure.parameter_generator_catkin import *\n\ngen = ParameterGenerator()\ngen.add(\"yaw_calibration\", double_t, 0, \"Yaw Calibration\", 0, -10, 10)\n\nexit(gen.generate(PACKAGE, \"art_racecar\", \"imu\"))\n"
  },
  {
    "path": "src/art_racecar/launch/Run_car.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <master auto=\"start\"/>\n\n    <!-- TF setting -->\n    <include file=\"$(find art_racecar)/launch/includes/art_car_tf.launch.xml\" />\n\n    <!-- SENSOR DEVICE -->\n    <!-- second startup ls01g lidar -->\n    <include file=\"$(find art_racecar)/launch/ls01g_lidar.launch\"/>\n    <!-- IMU -->\n    <include file=\"$(find art_imu)/launch/imu.launch\" />\n    <!-- Car -->\n    <node pkg=\"art_driver\" type=\"art_driver_node\" name=\"art_driver_node\"/>\n\n\t\n      <!-- Rviz -->\n    <!--node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find art_racecar)/launch/rviz/gmapping.rviz\" if=\"$(arg use_rviz)\"/-->\n\n</launch>\n\n"
  },
  {
    "path": "src/art_racecar/launch/Run_gmapping.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n\n    <arg name=\"use_rviz\" default=\"false\" />\n\n    <!-- ODOMETRY -->\n    <!--rf2o_Laser_Odometry-->\n    <include file=\"$(find art_racecar)/launch/includes/rf2o.launch.xml\" />\n\n     <!-- Robot_Localization -->\n    <node pkg=\"robot_localization\" type=\"ekf_localization_node\" name=\"ekf_se\" clear_params=\"true\">\n        <rosparam command=\"load\" file=\"$(find art_racecar)/param/ekf_params.yaml\" />\n    </node>\n\n    <!-- gmapping -->\n    <node pkg=\"gmapping\" type=\"slam_gmapping\" name=\"slam_gmapping\" output=\"screen\">\n        <remap from=\"scan\" to=\"scan\"/>\n        <param name=\"map_update_interval\" value=\"2.5\"/>\n        <param name=\"maxUrange\" value=\"16.0\"/>\n        <param name=\"sigma\" value=\"0.05\"/>\n        <param name=\"kernelSize\" value=\"1\"/>\n        <param name=\"lstep\" value=\"0.05\"/>\n        <param name=\"astep\" value=\"0.05\"/>\n        <param name=\"iterations\" value=\"5\"/>\n        <param name=\"lsigma\" value=\"0.075\"/>\n        <param name=\"ogain\" value=\"3.0\"/>\n        <param name=\"lskip\" value=\"0\"/>\n        <param name=\"srr\" value=\"0.1\"/>\n        <param name=\"srt\" value=\"0.2\"/>\n        <param name=\"str\" value=\"0.1\"/>\n        <param name=\"stt\" value=\"0.2\"/>\n        <param name=\"linearUpdate\" value=\"0.10\"/>\n        <param name=\"angularUpdate\" value=\"0.25\"/>\n        <param name=\"temporalUpdate\" value=\"1.0\"/>\n        <param name=\"resampleThreshold\" value=\"0.25\"/>\n        <param name=\"particles\" value=\"30\"/>\n        <param name=\"xmin\" value=\"-100.0\"/>\n        <param name=\"ymin\" value=\"-100.0\"/>\n        <param name=\"xmax\" value=\"100.0\"/>\n        <param name=\"ymax\" value=\"100.0\"/>\n        <param name=\"delta\" value=\"0.05\"/>\n        <param name=\"llsamplerange\" value=\"0.01\"/>\n        <param name=\"llsamplestep\" value=\"0.01\"/>\n        <param name=\"lasamplerange\" value=\"0.005\"/>\n        <param name=\"lasamplestep\" value=\"0.005\"/>\n        <param name=\"odom_frame\" value=\"odom\"/>\n        <param name=\"base_frame\" value=\"base_footprint\"/>\n    </node>\n\n    <!-- Rviz -->\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find art_racecar)/rviz/gmapping.rviz\" if=\"$(arg use_rviz)\"/>\n\n</launch>\n\n"
  },
  {
    "path": "src/art_racecar/launch/amcl_nav.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <arg name=\"use_rviz\" default=\"false\" />\n\n    <!-- for amcl -->    \n    <arg name=\"init_x\" default=\"0.0\" />\n    <arg name=\"init_y\" default=\"0.0\" />\n    <arg name=\"init_a\" default=\"0.0\" />\n\n    <!-- Map server -->\n    <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find art_racecar)/map/test.yaml\"/>\n\n   \n\n    <!-- ODOMETRY -->\n    <!--rf2o_Laser_Odometry-->\n    <include file=\"$(find art_racecar)/launch/includes/rf2o.launch.xml\" />\n    <!-- Robot_Localization -->\n    <node pkg=\"robot_localization\" type=\"ekf_localization_node\" name=\"ekf_se\" clear_params=\"true\">\n        <rosparam command=\"load\" file=\"$(find art_racecar)/param/ekf_params.yaml\" />\n    </node>\n\n    <!-- Localization -->\n    <!-- AMCL -->\n    <include file=\"$(find art_racecar)/launch/includes/amcl.launch.xml\">\n        <arg name=\"init_x\" value=\"$(arg init_x)\"/>\n        <arg name=\"init_y\" value=\"$(arg init_y)\"/>\n        <arg name=\"init_a\" value=\"$(arg init_a)\"/>\n    </include>\n\n    <!-- Navstack -->\n    <node pkg=\"move_base\" type=\"move_base\" respawn=\"false\" name=\"move_base\">\n        <!-- local planner -->\n         <!--\n        <param name=\"base_global_planner\" value=\"global_planner/GlobalPlanner\"/>  \n         -->\n        <param name=\"base_global_planner\" value=\"navfn/NavfnROS\"/>  \n        <param name=\"base_local_planner\" value=\"dwa_local_planner/DWAPlannerROS\"/>  \n        \n\n        <rosparam file=\"$(find art_racecar)/param/dwa_local_planner_params.yaml\" command=\"load\"/>\n        <!-- costmap layers -->    \n        <rosparam file=\"$(find art_racecar)/param/local_costmap_params.yaml\" command=\"load\"/>\n        <rosparam file=\"$(find art_racecar)/param/global_costmap_params.yaml\" command=\"load\"/> \n        <!-- move_base params -->\n        <rosparam file=\"$(find art_racecar)/param/base_global_planner_params.yaml\" command=\"load\"/>\n        <rosparam file=\"$(find art_racecar)/param/move_base_params.yaml\" command=\"load\"/>\n        <remap from=\"/odom\" to=\"/odometry/filtered\"/>\n\n       \n    </node>\n\n    <!-- L1 controller -->  \n    <node pkg=\"art_racecar\" type=\"art_car_controller\" respawn=\"false\" name=\"art_car_controller\" output=\"screen\">       \n        <!-- L1 -->\n        <param name=\"Vcmd\" value=\"1.5\" /> <!-- speed of car m/s -->        \n        <!-- ESC -->\n        <param name=\"baseSpeed\" value=\"1565\"/> <!-- pwm for motor constant speed, 1500: stop --> \n \n\n        <!-- Servo -->\n        <param name=\"baseAngle\" value=\"90.0\"/> <!-- the middle pos of servo, for tt02: 87, for hsp: ? -->\n        <param name=\"AngleGain\" value=\"-3.0\"/> <!-- for tt02: >0, for hsp: <0 -->\t\n        <param name=\"GasGain\" value=\"1.0\"/>\n\n        <!-- remap from=\"/odometry/filtered\" to=\"odom\" / --> \n        <remap from=\"/move_base_node/NavfnROS/plan\" to=\"/move_base/NavfnROS/plan\" /> \n    </node>\n\n    <!-- Rviz -->\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find art_racecar)/rviz/amcl.rviz\" if=\"$(arg use_rviz)\" />\n</launch>\n"
  },
  {
    "path": "src/art_racecar/launch/car.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <master auto=\"start\"/>\n\n    <!-- TF setting -->\n    <include file=\"$(find art_racecar)/launch/includes/art_car_tf.launch.xml\" />\n\n    <!-- Car -->\n    <node pkg=\"art_driver\" type=\"art_driver_node\" name=\"art_driver_node\"/>\n  \n\n\t\n      <!-- Rviz -->\n    <!--node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find art_racecar)/launch/rviz/gmapping.rviz\" if=\"$(arg use_rviz)\"/-->\n\n</launch>\n\n"
  },
  {
    "path": "src/art_racecar/launch/includes/amcl.launch.xml",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <arg name=\"init_x\" default=\"0\" />\n    <arg name=\"init_y\" default=\"0\" />\n    <arg name=\"init_a\" default=\"0\" />\n\n    <node pkg=\"amcl\" type=\"amcl\" name=\"amcl\" output=\"screen\">\n        <!-- Publish scans from best pose at a max of 10 Hz -->\n        <param name=\"transform_tolerance\" value=\"0.2\" />\n        <param name=\"gui_publish_rate\" value=\"30.0\"/>\n        <param name=\"laser_max_beams\" value=\"30\"/>\n        <param name=\"min_particles\" value=\"100\"/>\n        <param name=\"max_particles\" value=\"5000\"/>\n        <param name=\"kld_err\" value=\"0.01\"/>\n        <param name=\"kld_z\" value=\"0.99\"/>\n        <!-- translation std dev, m -->\n        <param name=\"odom_alpha1\" value=\"0.2\"/>\n        <param name=\"odom_alpha2\" value=\"0.2\"/>\n        <param name=\"odom_alpha3\" value=\"0.8\"/>\n        <param name=\"odom_alpha4\" value=\"0.2\"/>\n        <param name=\"laser_z_hit\" value=\"0.5\"/>\n        <param name=\"laser_z_short\" value=\"0.05\"/>\n        <param name=\"laser_z_max\" value=\"0.05\"/>\n        <param name=\"laser_z_rand\" value=\"0.5\"/>\n        <param name=\"laser_sigma_hit\" value=\"0.2\"/>\n        <param name=\"laser_lambda_short\" value=\"0.1\"/>\n        <param name=\"laser_lambda_short\" value=\"0.1\"/>\n        <param name=\"laser_model_type\" value=\"likelihood_field\"/>\n\n        <!-- <param name=\"laser_model_type\" value=\"beam\"/> -->\n        <param name=\"laser_likelihood_max_dist\" value=\"2.0\"/>\n        <param name=\"update_min_d\" value=\"0.1\"/>\n        <param name=\"update_min_a\" value=\"0.1\"/>\n        <param name=\"resample_interval\" value=\"2\"/>\n        <param name=\"transform_tolerance\" value=\"0.1\"/>\n        <param name=\"recovery_alpha_slow\" value=\"0.0\"/>\n        <param name=\"recovery_alpha_fast\" value=\"0.1\"/>\n\n        <param name=\"use_map_topic\" value=\"true\"/>\n        <param name=\"first_map_only\" value=\"true\"/>\n        <param name=\"tf_broadcast\" value=\"true\"/>\n\n        <param name=\"odom_frame_id\" value=\"odom\"/>\n        <param name=\"global_frame_id\" value=\"map\"/>\n        <param name=\"base_frame_id\" value=\"base_footprint\"/>\n        <param name=\"odom_model_type\" value=\"diff\"/>\n\n        <param name=\"initial_pose_x\" value=\"$(arg init_x)\"/>\n        <param name=\"initial_pose_y\" value=\"$(arg init_y)\"/>\n        <param name=\"initial_pose_a\" value=\"$(arg init_a)\"/>\n        <param name=\"initial_cov_xx\" value=\"0.25\" />\n        <param name=\"initial_cov_yy\" value=\"0.25\" />\n        <param name=\"initial_cov_aa\" value=\"0.2\" />\n    </node>\n</launch>\n"
  },
  {
    "path": "src/art_racecar/launch/includes/art_car_tf.launch.xml",
    "content": "<launch>\n    <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"base_footprint2base_link\" args=\"0.0 0.0 0.15 0.0 0.0 0.0 /base_footprint /base_link 10\"/>\n    <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"base_link2laser_link\" args=\" 0.07 0.0 0.0 0.0 0.0 0.0 /base_link /laser 10\"/>\n    <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"base_link2imu\" args=\"0.1653 0.0 0.0 0.0 0.0 0.0 /base_link /IMU_link 10\"/>\n</launch>\n"
  },
  {
    "path": "src/art_racecar/launch/includes/default_mapping.launch.xml",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <arg name=\"tf_map_scanmatch_transform_frame_name\" default=\"scanmatcher_frame\"/>\n    <arg name=\"base_frame\" default=\"base_footprint\"/>\n    <arg name=\"odom_frame\" default=\"nav\"/>\n    <arg name=\"pub_map_odom_transform\" default=\"true\"/>\n    <arg name=\"scan_subscriber_queue_size\" default=\"5\"/>\n    <arg name=\"scan_topic\" default=\"scan\"/>\n    <arg name=\"map_size\" default=\"2048\"/>\n\n    <node pkg=\"hector_mapping\" type=\"hector_mapping\" name=\"hector_mapping\" output=\"screen\">\n        <!-- Frame names -->\n        <param name=\"map_frame\" value=\"map\" />\n        <param name=\"base_frame\" value=\"$(arg base_frame)\" />\n        <param name=\"odom_frame\" value=\"$(arg odom_frame)\" />\n\n        <!-- Tf use -->\n        <param name=\"use_tf_scan_transformation\" value=\"true\"/>\n        <param name=\"use_tf_pose_start_estimate\" value=\"false\"/>\n        <param name=\"pub_map_odom_transform\" value=\"$(arg pub_map_odom_transform)\"/>\n\n        <!-- Map size / start point -->\n        <param name=\"map_resolution\" value=\"0.050\"/>\n        <param name=\"map_size\" value=\"$(arg map_size)\"/>\n        <param name=\"map_start_x\" value=\"0.5\"/>\n        <param name=\"map_start_y\" value=\"0.5\" />\n        <param name=\"map_multi_res_levels\" value=\"2\" />\n\n        <!-- Map update parameters -->\n        <param name=\"update_factor_free\" value=\"0.4\"/>\n        <param name=\"update_factor_occupied\" value=\"0.9\" />    \n        <param name=\"map_update_distance_thresh\" value=\"0.4\"/>\n        <param name=\"map_update_angle_thresh\" value=\"0.06\" />\n        <param name=\"laser_z_min_value\" value = \"-1.0\" />\n        <param name=\"laser_z_max_value\" value = \"1.0\" />\n\n        <!-- Advertising config --> \n        <param name=\"advertise_map_service\" value=\"true\"/>\n\n        <param name=\"scan_subscriber_queue_size\" value=\"$(arg scan_subscriber_queue_size)\"/>\n        <param name=\"scan_topic\" value=\"$(arg scan_topic)\"/>\n\n        <!-- Debug parameters -->\n        <!--\n          <param name=\"output_timing\" value=\"false\"/>\n          <param name=\"pub_drawings\" value=\"true\"/>\n          <param name=\"pub_debug_output\" value=\"true\"/>\n        -->\n        <param name=\"tf_map_scanmatch_transform_frame_name\" value=\"$(arg tf_map_scanmatch_transform_frame_name)\" />\n    </node>\n\n    <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"map_nav_broadcaster\" args=\"0 0 0 0 0 0 map nav 100\"/>\n</launch>\n  \n  \n"
  },
  {
    "path": "src/art_racecar/launch/includes/ls01g.launch.xml",
    "content": "\n<launch>\n\t<arg name=\"inverted\" default=\"false\" />\n    <node name=\"ls01g\" pkg=\"ls01g\" type=\"ls01g\" output=\"screen\">\n　　\t\t<param name=\"scan_topic\" value=\"scan\"/>         #设置激光数据topic名称\n　　\t  <param name=\"laser_link\" value=\"base_laser_link\"/>     #激光坐标\n　　\t  <param name=\"serial_port\" value=\"/dev/laser\"/>  #雷达连接的串口\n      <param name=\"zero_as_max\" value=\"false\"/>        # 设置为true探测不到区域会变成最大值\n      <param name=\"min_as_zero\" value=\"false\"/>        # true：探测不到区域为0，false：探测不到区域为inf\n\t\t  <param name=\"angle_disable_min\" value=\"-1\"/>    # 角度制，从angle_disable_min到angle_disable_max之前的值为0\n\t\t  <param name=\"angle_disable_max\" value=\"-1\"/>\n      <param name=\"inverted\" value=\"$(arg inverted)\"/>           # 如果0度方向在串口线的方向上设置为true \n      \n    </node>\n    <!--<node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find ls01g)/launch/rviz.rviz\"/>-->\n</launch>\n"
  },
  {
    "path": "src/art_racecar/launch/includes/rf2o.launch.xml",
    "content": "<!-- \n  This node presents a fast and precise method to estimate the planar motion of a lidar\n  from consecutive range scans. It is very useful for the estimation of the robot odometry from\n  2D laser range measurements.\n  \n  Requirements:\n  - 2D laser scan, publishing sensor_msgs::LaserScan\n  - TF transform from the laser to the robot base\n-->\n\n<launch>\n\n    <node pkg=\"rf2o_laser_odometry\" type=\"rf2o_laser_odometry_node\" name=\"rf2o_laser_odometry\" >\n        <param name=\"laser_scan_topic\" value=\"scan\"/>        <!-- topic where the lidar scans are being published -->\n        <param name=\"base_frame_id\" value=\"base_footprint\"/>            <!-- frame_id (tf) of the mobile robot base. A tf transform from the laser_frame to the base_frame is mandatory -->\n        <param name=\"odom_topic\" value=\"odom_rf2o\" />              # topic where tu publish the odometry estimations\n        <param name=\"publish_tf\" value=\"true\" />                   # wheter or not to publish the tf::transform (base->odom)\n        <param name=\"odom_frame_id\" value=\"odom\" />                <!-- frame_id (tf) to publish the odometry estimations -->\n        <param name=\"freq\" value=\"20.0\"/>   \n        <param name=\"verbose\" value=\"true\" />                                  <!-- Execution frequency. See \"Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA'16\"-->\n    </node>\n\n</launch>\n"
  },
  {
    "path": "src/art_racecar/launch/includes/rplidar.launch.xml",
    "content": "<launch>\n    <node name=\"rplidarNode\"          pkg=\"rplidar_ros\"  type=\"rplidarNode\" output=\"screen\">\n        <param name=\"serial_port\"         type=\"string\" value=\"/dev/rplidar\"/>  \n        <param name=\"serial_baudrate\"     type=\"int\"    value=\"115200\"/>\n        <param name=\"frame_id\"            type=\"string\" value=\"laser\"/>\n        <param name=\"inverted\"            type=\"bool\"   value=\"false\"/>\n        <param name=\"angle_compensate\"    type=\"bool\"   value=\"true\"/>\n    </node>\n</launch>\n"
  },
  {
    "path": "src/art_racecar/launch/ls01g_lidar.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <arg name=\"inverted\" default=\"false\" />\n    <node name=\"ls01g\" pkg=\"ls01g\" type=\"ls01g\" output=\"screen\">\n        <param name=\"scan_topic\" value=\"scan\"/>         #设置激光数据topic名称\n        <param name=\"laser_link\" value=\"laser\"/>     #激光坐标\n        <param name=\"serial_port\" value=\"/dev/laser\"/>  #雷达连接的串口\n        <param name=\"zero_as_max\" value=\"false\"/>        # 设置为true探测不到区域会变成最大值\n        <param name=\"min_as_zero\" value=\"false\"/>        # true：探测不到区域为0，false：探测不到区域为inf\n        <param name=\"angle_disable_min\" value=\"-1\"/>    # 角度制，从angle_disable_min到angle_disable_max之前的值为0\n        <param name=\"angle_disable_max\" value=\"-1\"/>\n        <param name=\"inverted\" value=\"$(arg inverted)\"/>           # 如果0度方向在串口线的方向上设置为true \n    </node>\n    <!--<node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find art_racecar)/launch/rviz.rviz\"/>-->\n</launch>\n"
  },
  {
    "path": "src/art_racecar/launch/rviz.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <arg name=\"use_rviz\" default=\"true\" />\n\n   \n\n    <!-- Rviz -->\n    <node pkg=\"rviz\" type=\"rviz\" name=\"rviz\" args=\"-d $(find art_racecar)/rviz/amcl.rviz\" if=\"$(arg use_rviz)\" />\n</launch>\n"
  },
  {
    "path": "src/art_racecar/launch/teleop_joy.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n\n    <node name=\"joy_node\" pkg=\"joy\" type=\"joy_node\" />\n    <node name=\"racecar_joy\" pkg=\"art_racecar\" type=\"racecar_joy.py\" output=\"screen\" />\n        \n   \n    <!--<node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find art_racecar)/launch/rviz.rviz\"/>-->\n</launch>\n"
  },
  {
    "path": "src/art_racecar/map/mymap.yaml",
    "content": "image: /home/art/racecar/src/art_racecar/map/mymap.pgm\nresolution: 0.050000\norigin: [-100.000000, -100.000000, 0.000000]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n"
  },
  {
    "path": "src/art_racecar/map/test.yaml",
    "content": "image: test.pgm\nresolution: 0.050000\norigin: [-100.000000, -100.000000, 0.000000]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n"
  },
  {
    "path": "src/art_racecar/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>art_racecar</name>\n  <version>0.1.0</version>\n  <description>The art_racecar package</description>\n\n  <!-- One maintainer tag required, multiple allowed, one person per tag -->\n  <!-- Example:  -->\n  <!-- <maintainer email=\"jane.doe@example.com\">Jane Doe</maintainer> -->\n  <maintainer email=\"zhangnan@artrobot.com\">Steven Zhang</maintainer>\n\n\n  <!-- One license tag required, multiple allowed, one license per tag -->\n  <!-- Commonly used license strings: -->\n  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->\n  <license>TODO</license>\n\n\n  <!-- Url tags are optional, but multiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/art_racecar</url> -->\n\n\n  <!-- Author tags are optional, multiple are allowed, one per tag -->\n  <!-- Authors do not have to be maintainers, but could be -->\n  <!-- Example: -->\n  <!-- <author email=\"jane.doe@example.com\">Jane Doe</author> -->\n\n\n  <!-- The *depend tags are used to specify dependencies -->\n  <!-- Dependencies can be catkin packages or system dependencies -->\n  <!-- Examples: -->\n  <!-- Use depend as a shortcut for packages that are both build and exec dependencies -->\n  <!--   <depend>roscpp</depend> -->\n  <!--   Note that this is equivalent to the following: -->\n  <!--   <build_depend>roscpp</build_depend> -->\n  <!--   <exec_depend>roscpp</exec_depend> -->\n  <!-- Use build_depend for packages you need at compile time: -->\n  <!--   <build_depend>message_generation</build_depend> -->\n  <!-- Use build_export_depend for packages you need in order to build against this package: -->\n  <!--   <build_export_depend>message_generation</build_export_depend> -->\n  <!-- Use buildtool_depend for build tool packages: -->\n  <!--   <buildtool_depend>catkin</buildtool_depend> -->\n  <!-- Use exec_depend for packages you need at runtime: -->\n  <!--   <exec_depend>message_runtime</exec_depend> -->\n  <!-- Use test_depend for packages you need only for testing: -->\n  <!--   <test_depend>gtest</test_depend> -->\n  <!-- Use doc_depend for packages you need only for building documentation: -->\n  <!--   <doc_depend>doxygen</doc_depend> -->\n  <buildtool_depend>catkin</buildtool_depend>\n  <build_depend>geometry_msgs</build_depend>\n  <build_depend>joy</build_depend>\n  <build_depend>move_base</build_depend>\n  <build_depend>roscpp</build_depend>\n  <build_depend>rospy</build_depend>\n  <build_depend>std_msgs</build_depend>\n  <build_depend>visualization_msgs</build_depend>\n  <build_depend>tf</build_depend> \n  <build_depend>sensor_msgs</build_depend>\n  <build_depend>python-serial</build_depend>\n  <build_depend>dynamic_reconfigure</build_depend>\n\n\n  <exec_depend>geometry_msgs</exec_depend>\n  <exec_depend>move_base</exec_depend>\n  <exec_depend>joy</exec_depend>\n  <exec_depend>roscpp</exec_depend>\n  <exec_depend>rospy</exec_depend>\n  <exec_depend>std_msgs</exec_depend>\n  <exec_depend>visualization_msgs</exec_depend>\n  <exec_depend>tf</exec_depend> \n  <exec_depend>tf</exec_depend>\n  <exec_depend>sensor_msgs</exec_depend>\n  <exec_depend>python-serial</exec_depend>   \n  <exec_depend>dynamic_reconfigure</exec_depend>\n\n\n\n\n  <!-- The export tag contains other, unspecified, tags -->\n  <export>\n    <!-- Other tools can request additional information be placed here -->\n\n  </export>\n</package>\n"
  },
  {
    "path": "src/art_racecar/param/base_global_planner_params.yaml",
    "content": "GlobalPlanner:\n    allow_unknown: false\n#    default_tolerance: 0.5      #路径规划器目标点的公差范围\n#   visualize_potential: true   #指定是否通过可视化PointCloud2计算的潜在区域\n#    use_dijkstra: true          #如果为ture，则使用dijkstra算法。 否则使用A *算法\n#    use_quadratic: true         #二次逼近\n#    use_grid_path: true         #如果为true，沿着栅格边界创建路径。 否则，使用梯度下降的方法。\n#    old_navfn_behavior: true    #如果你想要global_planner准确反映navfn的行为，此项设置为true。\n\n#    lethal_cost: 25\n#    neutral_cost: 50\n#    cost_factor: 3\n#    publish_potential: True\n\n\nNavfnROS:\n    allow_unknown: false\n"
  },
  {
    "path": "src/art_racecar/param/dwa_local_planner_params.yaml",
    "content": "DWAPlannerROS: \n\n  acc_lim_th: 0.1\n  acc_lim_x: 0.5\n  acc_lim_y: 0.0 \n\n\n  max_vel_x: 0.5\n  min_vel_x: 0.0 \n\n  max_vel_y: 0.0 \n  min_vel_y: 0.0\n\n  max_trans_vel: 0.5\n  min_trans_vel: 0.1\n  max_rot_vel: 0.2\n  min_rot_vel: 0.0\n\n  sim_time: 1.5\n\n  sim_granularity: 0.025\n\n  goal_distance_bias: 30.0\n  path_distance_bias: 20.0 \n  occdist_scale: 0.01\n  forward_point_distance: 0.5\n  stop_time_buffer: 0.2 \n#######\n  scaling_speed: 0.5\n#######\n  max_scaling_factor: 0.2 \n  oscillation_reset_dist: 0.05 \n   \n  #\n  vx_samples: 20\n  vy_samples: 0 \n  vtheta_samples: 10\n  \n  rot_stopped_vel: 0.01 \n  trans_stopped_vel: 0.01\n  #\n  xy_goal_tolerance: 0.2 \n  yaw_goal_tolerance: 0.1 \n  latch_xy_goal_tolerance: true #如果目标误差被锁定，若机器人达到目标XY位置，它将旋转到位，即使误差没有达到，也会做旋转 \n"
  },
  {
    "path": "src/art_racecar/param/ekf_params.yaml",
    "content": "\nfrequency: 30\nsensor_timeout: 0.025\ntwo_d_mode: true\ntransform_time_offset: 0.0001\ntransform_timeout: 0.025\nprint_diagnostics: true\ndebug: false\n\n# Defaults to \"robot_localization_debug.txt\" if unspecified. Please specify the full path.\ndebug_out_file: /path/to/debug/file.txt\n\n# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified.\npublish_tf: true\n\n# Whether to publish the acceleration state. Defaults to false if unspecified.\npublish_acceleration: true\n\nmap_frame: /map              # Defaults to \"map\" if unspecified\nodom_frame: /odom            # Defaults to \"odom\" if unspecified\nbase_link_frame: /base_footprint  # Defaults to \"base_link\" if unspecified\nworld_frame: /odom           # Defaults to the value of odom_frame if unspecified\n\n# The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry,\n# geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped,\n# sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its \"base\" name, e.g., odom0,\n# odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no\n# default values, and must be specified.\nodom0: /rf2o_laser_odometry/odom\n\n# Each sensor reading updates some or all of the filter's state. These options give you greater control over which\n# values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only\n# want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the\n# values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types\n# do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message\n# has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false\n# if unspecified, effectively making this parameter required for each sensor.\nodom0_config: [false, false, false,\n               false, false, false,\n               true, true, false,\n               false, false, false,\n               false, false, false]\n\n# If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase\n# the size of the subscription queue so that more measurements are fused.\nodom0_queue_size: 5\n\n# [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result\n# of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's\n# algorithm.\nodom0_nodelay: true\n\n# [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under-\n# report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they\n# arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also\n# measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't\n# always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose\n# data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then\n# integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true\n# for twist measurements has no effect.\nodom0_differential: true\n\n# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a \"zero point\"\n# for all future measurements. While you can achieve the same effect with the differential paremeter, the key\n# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before\n# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true.\nodom0_relative: false\n\n# [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to\n# control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to\n# numeric_limits<double>::max() if unspecified. It is strongly recommended that these parameters be removed if not\n# required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation.\n# For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying\n# the thresholds. \nodom0_pose_rejection_threshold: 8\nodom0_twist_rejection_threshold: 0.75\n\nimu0: /imu_data\nimu0_config: [false, false, false,\n              false, false, true,\n              false, false, false,\n              false,  false,  false,\n              false,  false,  false]\nimu0_nodelay: false\nimu0_differential: false\nimu0_relative: true\nimu0_queue_size: 8\nimu0_pose_rejection_threshold: 0.8                 # Note the difference in parameter names\nimu0_twist_rejection_threshold: 0.8                #\nimu0_linear_acceleration_rejection_threshold: 0.8  #\n\n# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set\n# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame.\nimu0_remove_gravitational_acceleration: true\n\n\n# [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\n# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each\n# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be.\n# However, if users find that a given variable is slow to converge, one approach is to increase the\n# process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error\n# to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are\n# ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if\n# unspecified.\nprocess_noise_covariance: [0.01, 0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0.01, 0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0.01, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0.03, 0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0.03, 0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0.5,  0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0.5,   0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0.025, 0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0.04, 0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0.01, 0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.01, 0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.08, 0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.05, 0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.01, 0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.015]\n\n# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal\n# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in\n# question. Users should take care not to use large values for variables that will not be measured directly. The values\n# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below\n#if unspecified.\ninitial_estimate_covariance: [1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    1e-9, 0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    1e-9, 0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    1e-9, 0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    1e-9,  0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1e-9,  0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1e-9,  0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1e-9, 0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1e-9, 0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1e-9]\n\n"
  },
  {
    "path": "src/art_racecar/param/global_costmap_params.yaml",
    "content": "global_costmap:\n    footprint: [[-0.305, -0.18], [-0.305, 0.18], [0.305, 0.18], [0.305, -0.18]]\n    footprint_padding: 0.01\n    transform_tolerance: 0.5\n    update_frequency: 10.0\n    publish_frequency: 10.0\n\n    global_frame: /map\n    robot_base_frame: /base_footprint\n    resolution: 0.10\n\n    rolling_window: true\n    width: 10.0\n    height: 10.0\n    track_unknown_space: false\n\n    plugins: \n        - {name: static,    type: \"costmap_2d::StaticLayer\"}            \n        - {name: sensor,    type: \"costmap_2d::ObstacleLayer\"}\n        - {name: inflation, type: \"costmap_2d::InflationLayer\"}\n\n    static:        \n        map_topic: /map \n        subscribe_to_updates: true\n\n    sensor:\n        observation_sources: laser_scan_sensor\n        laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}\n\n    inflation:\n        inflation_radius: 0.1\n        cost_scaling_factor: 8.0\n\n"
  },
  {
    "path": "src/art_racecar/param/local_costmap_params.yaml",
    "content": "local_costmap:\n    footprint: [[-0.305, -0.18], [-0.305, 0.18], [0.305, 0.18], [0.305, -0.18]]\n    footprint_padding: 0.01\n    transform_tolerance: 0.5\n    update_frequency: 10.0\n    publish_frequency: 10.0\n\n    global_frame: /odom\n    robot_base_frame: /base_footprint\n    resolution: 0.10\n    static_map: true\n\n    rolling_window: true\n    width: 10.0\n    height: 10.0\n    resolution: 0.05\n\n    track_unknown_space: false\n\n    plugins:            \n        - {name: sensor,    type: \"costmap_2d::ObstacleLayer\"}\n        - {name: inflation, type: \"costmap_2d::InflationLayer\"}\n\n    sensor:\n        observation_sources: laser_scan_sensor\n        laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}\n\n    inflation:\n        inflation_radius: 0.1\n        cost_scaling_factor: 8.0\n"
  },
  {
    "path": "src/art_racecar/param/move_base_params.yaml",
    "content": "# Move base node parameters. For full documentation of the parameters in this file, please see\n#\n#  http://www.ros.org/wiki/move_base\n#\nshutdown_costmaps: false\n\ncontroller_frequency: 10.0\ncontroller_patience: 3.0\n\nplanner_frequency: 10.0\nplanner_patience: 5.0\n\noscillation_timeout: 10.0\noscillation_distance: 0.2\n\nclearing_rotation_allowed: false\n"
  },
  {
    "path": "src/art_racecar/rviz/amcl.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Imu1/Box properties1\n      Splitter Ratio: 0.5\n    Tree Height: 528\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679016\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.0299999993\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 100\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 0.699999988\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Unreliable: false\n      Use Timestamp: false\n      Value: true\n    - Alpha: 0.200000003\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: true\n      Name: global_costmap\n      Topic: /move_base/global_costmap/costmap\n      Unreliable: false\n      Use Timestamp: false\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 402\n      Min Color: 0; 0; 0\n      Min Intensity: 2\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.0500000007\n      Style: Flat Squares\n      Topic: /scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n        IMU_link:\n          Value: true\n        base_footprint:\n          Value: true\n        base_link:\n          Value: true\n        laser:\n          Value: true\n        map:\n          Value: true\n        odom:\n          Value: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        map:\n          odom:\n            base_footprint:\n              base_link:\n                IMU_link:\n                  {}\n                laser:\n                  {}\n      Update Interval: 0\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.300000012\n      Head Length: 0.200000003\n      Length: 0.300000012\n      Line Style: Lines\n      Line Width: 0.0299999993\n      Name: Path\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.0299999993\n      Shaft Diameter: 0.100000001\n      Shaft Length: 0.100000001\n      Topic: /move_base/NavfnROS/plan\n      Unreliable: true\n      Value: true\n    - Angle Tolerance: 0.100000001\n      Class: rviz/Odometry\n      Covariance:\n        Orientation:\n          Alpha: 0.5\n          Color: 255; 255; 127\n          Color Style: Unique\n          Frame: Local\n          Offset: 1\n          Scale: 1\n          Value: true\n        Position:\n          Alpha: 0.300000012\n          Color: 204; 51; 204\n          Scale: 1\n          Value: true\n        Value: false\n      Enabled: true\n      Keep: 100\n      Name: Odometry\n      Position Tolerance: 0.100000001\n      Shape:\n        Alpha: 1\n        Axes Length: 1\n        Axes Radius: 0.100000001\n        Color: 255; 25; 0\n        Head Length: 0.300000012\n        Head Radius: 0.100000001\n        Shaft Length: 0.100000001\n        Shaft Radius: 0.0199999996\n        Value: Arrow\n      Topic: /odometry/filtered\n      Unreliable: false\n      Value: true\n    - Acceleration properties:\n        Acc. vector alpha: 1\n        Acc. vector color: 255; 0; 0\n        Acc. vector scale: 1\n        Derotate acceleration: true\n        Enable acceleration: false\n      Axes properties:\n        Axes scale: 1\n        Enable axes: true\n      Box properties:\n        Box alpha: 1\n        Box color: 255; 0; 0\n        Enable box: false\n        x_scale: 0.400000006\n        y_scale: 0.300000012\n        z_scale: 0.300000012\n      Class: rviz_imu_plugin/Imu\n      Enabled: false\n      Name: Imu\n      Topic: /imu_data\n      Unreliable: false\n      Value: false\n      fixed_frame_orientation: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 17.7873268\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 1.2478348\n        Y: -3.33640909\n        Z: 0.00110054587\n      Focal Shape Fixed Size: true\n      Focal Shape Size: 0.0500000007\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Pitch: 1.56979632\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 2.95539427\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 809\n  Hide Left Dock: false\n  Hide Right Dock: true\n  QMainWindow State: 000000ff00000000fd00000004000000000000016a0000029ffc020000000bfb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000029f000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006100000001d1000000b50000000000000000fb0000000a0049006d0061006700650000000000ffffffff0000000000000000fb0000000a0049006d00610067006501000002ab00000113000000000000000000000001000001a30000025efc0200000004fb0000000a0049006d00610067006500000000280000025e0000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000005160000003efc0100000002fb0000000800540069006d00650100000000000005160000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000003a60000029f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1302\n  X: 519\n  Y: 235\n"
  },
  {
    "path": "src/art_racecar/rviz/gmapping.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n        - /ekf_odom1/Shape1\n        - /rf2o_odom1/Shape1\n      Splitter Ratio: 0.5\n    Tree Height: 775\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679016\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.0299999993\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n        IMU_link:\n          Value: true\n        base_footprint:\n          Value: true\n        base_link:\n          Value: true\n        laser:\n          Value: true\n        map:\n          Value: true\n        odom:\n          Value: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        map:\n          odom:\n            base_footprint:\n              base_link:\n                IMU_link:\n                  {}\n                laser:\n                  {}\n      Update Interval: 0\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 2390\n      Min Color: 0; 0; 0\n      Min Intensity: 3\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.0500000007\n      Style: Flat Squares\n      Topic: /scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 0.699999988\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Unreliable: false\n      Use Timestamp: false\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 25; 255; 0\n      Enabled: true\n      Head Diameter: 0.300000012\n      Head Length: 0.200000003\n      Length: 0.300000012\n      Line Style: Lines\n      Line Width: 0.0299999993\n      Name: Path\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Pose Color: 255; 85; 255\n      Pose Style: None\n      Radius: 0.0299999993\n      Shaft Diameter: 0.100000001\n      Shaft Length: 0.100000001\n      Topic: /move_base/TrajectoryPlannerROS/global_plan\n      Unreliable: false\n      Value: true\n    - Angle Tolerance: 0.100000001\n      Class: rviz/Odometry\n      Covariance:\n        Orientation:\n          Alpha: 0.5\n          Color: 255; 255; 127\n          Color Style: Unique\n          Frame: Local\n          Offset: 1\n          Scale: 1\n          Value: true\n        Position:\n          Alpha: 0.300000012\n          Color: 204; 51; 204\n          Scale: 1\n          Value: true\n        Value: false\n      Enabled: true\n      Keep: 500\n      Name: ekf_odom\n      Position Tolerance: 0.100000001\n      Shape:\n        Alpha: 1\n        Axes Length: 1\n        Axes Radius: 0.100000001\n        Color: 0; 0; 255\n        Head Length: 0.300000012\n        Head Radius: 0.100000001\n        Shaft Length: 0.200000003\n        Shaft Radius: 0.0500000007\n        Value: Arrow\n      Topic: /odometry/filtered\n      Unreliable: false\n      Value: true\n    - Angle Tolerance: 0.100000001\n      Class: rviz/Odometry\n      Covariance:\n        Orientation:\n          Alpha: 0.5\n          Color: 255; 255; 127\n          Color Style: Unique\n          Frame: Local\n          Offset: 1\n          Scale: 1\n          Value: true\n        Position:\n          Alpha: 0.300000012\n          Color: 204; 51; 204\n          Scale: 1\n          Value: true\n        Value: false\n      Enabled: true\n      Keep: 500\n      Name: rf2o_odom\n      Position Tolerance: 0.100000001\n      Shape:\n        Alpha: 1\n        Axes Length: 1\n        Axes Radius: 0.100000001\n        Color: 255; 25; 0\n        Head Length: 0.300000012\n        Head Radius: 0.100000001\n        Shaft Length: 0.200000003\n        Shaft Radius: 0.0500000007\n        Value: Arrow\n      Topic: /rf2o_laser_odometry/odom\n      Unreliable: false\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 17.5254555\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 0.00508546829\n        Y: -0.0301897526\n        Z: 0.0989120007\n      Focal Shape Fixed Size: true\n      Focal Shape Size: 0.0500000007\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Pitch: 0.3878344\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 5.83341122\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 1056\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000396000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006100000001d1000000b5000000000000000000000001000001a30000025efc0200000004fb0000000a0049006d00610067006500000000280000025e0000000000000000fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007300000000280000025e000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006501000000000000073f0000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000005cf0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1855\n  X: 65\n  Y: 24\n"
  },
  {
    "path": "src/art_racecar/rviz/test_laser.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n        - /Grid1\n        - /LaserScan1\n        - /Axes1\n        - /Axes1/Status1\n        - /TF1/Frames1\n      Splitter Ratio: 0.5\n    Tree Height: 490\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679016\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.0299999993\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 26\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 2319\n      Min Color: 0; 0; 0\n      Min Intensity: 2\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.00999999978\n      Style: Points\n      Topic: /scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.5\n      Name: Axes\n      Radius: 0.0500000007\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Class: rviz/TF\n      Enabled: true\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        {}\n      Update Interval: 1\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Default Light: true\n    Fixed Frame: laser\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 10.5115833\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 0\n        Y: 0\n        Z: 0\n      Focal Shape Fixed Size: true\n      Focal Shape Size: 0.0500000007\n      Invert Z Axis: false\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Pitch: 1.06979573\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 2.66859388\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 773\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000017000000279fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000279000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000279fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000279000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000054300000040fc0100000002fb0000000800540069006d00650100000000000005430000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000002b80000027900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1347\n  X: 152\n  Y: 136\n"
  },
  {
    "path": "src/art_racecar/save_map.sh",
    "content": "#!/bin/bash\n\nrosrun map_server map_saver -f  ~/racecar/src/art_racecar/map/mymap"
  },
  {
    "path": "src/art_racecar/src/ESC_calibration.py",
    "content": "#!/usr/bin/env python\n\nimport rospy\n\nfrom geometry_msgs.msg import Twist\n\nimport sys, select, termios, tty\nimport time\n\nmsg = \"\"\n\n\ndef getKey():\n    tty.setraw(sys.stdin.fileno())\n    rlist, _, _ = select.select([sys.stdin], [], [], 0.1)\n    if rlist:\n        key = sys.stdin.read(1)\n    else:\n        key = ''\n\n    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)\n    return key\n\n\ndef vels(speed,turn):\n    return \"currently:\\tspeed %s\\tturn %s \" % (speed,turn)\n\nif __name__==\"__main__\":\n    settings = termios.tcgetattr(sys.stdin)\n    \n    rospy.init_node('racecar_teleop')\n    pub = rospy.Publisher('~/car/cmd_vel', Twist, queue_size=5)\n\n\n    run = 0\n\n    try:\n        while(1):\n            key = getKey()\n            twist = Twist()\n            if key == '1':\n            \ttwist.linear.x = 1500; twist.linear.y = 0; twist.linear.z = 0\n                twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 90\n                print \"vel = 0\"\n            elif key == '2':\n            \ttwist.linear.x = 2000; twist.linear.y = 0; twist.linear.z = 0\n                twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 90\n                print \"vel = +Max\"\n            elif key == '3':\n            \ttwist.linear.x = 1000; twist.linear.y = 0; twist.linear.z = 0\n                twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 90\n                print \"vel = -Max\"\n            else:\n            \ttwist.linear.x = 1500; twist.linear.y = 0; twist.linear.z = 0\n                twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 90\n                print \"stop\"\n\n            pub.publish(twist)\n            \n            \n\n            if (key == '\\x03'):   #for ctrl + c exit\n                break\n\n    except:\n        print \"error\"\n\n    finally:\n        twist = Twist()\n        twist.linear.x = speed_mid; twist.linear.y = 0; twist.linear.z = 0\n        twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = turn_mid\n        pub.publish(twist)\n\n    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)\n"
  },
  {
    "path": "src/art_racecar/src/PID.h",
    "content": "﻿\n#ifndef PID_H\n#define\tPID_H\n\n/***********************************/\ntypedef struct PID\n{              //结构体定义\n    double SetPoint;         //设定值\n    double Proportion;         // Proportion 比例系数\n    double  Integral;            // Integral   积分系数\n    double  Derivative;          // Derivative  微分系数\n    double  LastError;          // Error[-1]  前一拍误差\n    double  PreError;           // Error[-2]  前两拍误差\n\n\n}PID;\n\n\nvoid PIDInit (struct PID *pp);\ndouble PIDCal(struct PID *pp, double ThisError);\n\n\n\n\n#endif\n\n\n"
  },
  {
    "path": "src/art_racecar/src/art_car_controller.cpp",
    "content": "/*\nCopyright (c) 2017, ChanYuan KUO, YoRu LU,\nlatest editor: HaoChih, LIN\nAll rights reserved. (Hypha ROS Workshop)\n\nThis file is part of hypha_racecar package.\n\nhypha_racecar is free software: you can redistribute it and/or modify\nit under the terms of the GNU LESSER GENERAL PUBLIC LICENSE as published\nby the Free Software Foundation, either version 3 of the License, or\nany later version.\n\nhypha_racecar is distributed in the hope that it will be useful,\nbut WITHOUT ANY WARRANTY; without even the implied warranty of\nMERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\nGNU LESSER GENERAL PUBLIC LICENSE for more details.\n\nYou should have received a copy of the GNU LESSER GENERAL PUBLIC LICENSE\nalong with hypha_racecar.  If not, see <http://www.gnu.org/licenses/>.\n*/\n\n#include <iostream>\n#include \"ros/ros.h\"\n#include <geometry_msgs/PoseStamped.h>\n#include <geometry_msgs/Twist.h>\n#include <tf/transform_listener.h>\n#include <tf/transform_datatypes.h>\n#include \"nav_msgs/Path.h\"\n#include <nav_msgs/Odometry.h>\n#include <visualization_msgs/Marker.h>\n#include \"PID.h\"\n#include \"art_car_controller.hpp\"\n\n#define PI 3.14159265358979\nint start_loop_flag = 0;\nint start_speed = 1560;\nextern  PID  pid_speed;\n\nL1Controller::L1Controller()\n{\n    //Private parameters handler\n    ros::NodeHandle pn(\"~\");\n\n    //Car parameter\n    pn.param(\"L\", L, 0.26);\n    pn.param(\"Lrv\", Lrv, 10.0);\n    pn.param(\"Vcmd\", Vcmd, 1.0);\n    pn.param(\"lfw\", lfw, 0.13);\n    pn.param(\"lrv\", lrv, 10.0);\n\n    //Controller parameter\n    pn.param(\"controller_freq\", controller_freq, 20);\n    pn.param(\"AngleGain\", Angle_gain, -1.0);\n    pn.param(\"GasGain\", Gas_gain, 1.0);\n    pn.param(\"baseSpeed\", baseSpeed, 1575);\n    pn.param(\"baseAngle\", baseAngle, 90.0);\n\n    //Publishers and Subscribers\n    odom_sub = n_.subscribe(\"/odometry/filtered\", 1, &L1Controller::odomCB, this);\n    path_sub = n_.subscribe(\"/move_base_node/NavfnROS/plan\", 1, &L1Controller::pathCB, this);\n    goal_sub = n_.subscribe(\"/move_base_simple/goal\", 1, &L1Controller::goalCB, this);\n    marker_pub = n_.advertise<visualization_msgs::Marker>(\"car_path\", 10);\n    pub_ = n_.advertise<geometry_msgs::Twist>(\"car/cmd_vel\", 1);\n\n    //Timer\n    timer1 = n_.createTimer(ros::Duration((1.0)/controller_freq), &L1Controller::controlLoopCB, this); // Duration(0.05) -> 20Hz\n    timer2 = n_.createTimer(ros::Duration((0.5)/controller_freq), &L1Controller::goalReachingCB, this); // Duration(0.05) -> 20Hz\n\n    //Init variables\n    Lfw = goalRadius = getL1Distance(Vcmd);\n    foundForwardPt = false;\n    goal_received = false;\n    goal_reached = false;\n    cmd_vel.linear.x = 1500; // 1500 for stop\n    cmd_vel.angular.z = baseAngle;\n\n    //Show info\n    ROS_INFO(\"[param] baseSpeed: %d\", baseSpeed);\n    ROS_INFO(\"[param] baseAngle: %f\", baseAngle);\n    ROS_INFO(\"[param] AngleGain: %f\", Angle_gain);\n    ROS_INFO(\"[param] Vcmd: %f\", Vcmd);\n    ROS_INFO(\"[param] Lfw: %f\", Lfw);\n\n    //Visualization Marker Settings\n    initMarker();\n    car_stop = 0;\n}\n\nvoid L1Controller::goalReachingCB(const ros::TimerEvent&)\n{\n\n    if(goal_received)\n    {\n        double car2goal_dist = getCar2GoalDist();\n        if(car2goal_dist < goalRadius)\n        {\n            goal_reached = true;\n            goal_received = false;\n            //ROS_INFO(\"Goal Reached !\");\n            car_stop = 100;\n        }\n    }\n}\n\n\n\n\nvoid L1Controller::controlLoopCB(const ros::TimerEvent&)\n{\n    int count = 100;\n    geometry_msgs::Pose carPose = odom.pose.pose;\n    geometry_msgs::Twist carVel = odom.twist.twist;\n    cmd_vel.linear.x = 1500;\n    cmd_vel.angular.z = baseAngle;\n\n    if(goal_received)\n    {\n        /*Estimate Steering Angle*/\n        double eta = getEta(carPose);  \n        if(foundForwardPt)\n        {\n\n            cmd_vel.angular.z = baseAngle + getSteeringAngle(eta)*Angle_gain;\n            /*Estimate Gas Input*/\n\n            if(!goal_reached)\n            {\n                if(start_loop_flag++ <= 10)\n                {\n\n                    double u = getGasInput(carVel.linear.x);\n                    \n                    cmd_vel.linear.x = start_speed + PIDCal(&pid_speed,u);\n\n\n\n                     start_speed += 4;\n                     if(cmd_vel.linear.x > baseSpeed)   cmd_vel.linear.x = baseSpeed;\n                     ROS_INFO(\"baseSpeed = %.2f\\tSteering angle = %.2f\",cmd_vel.linear.x,cmd_vel.angular.z);\n                }\n                else\n                {\n                    //ROS_INFO(\"!goal_reached\");\n                    double u = getGasInput(carVel.linear.x);                   \n                    cmd_vel.linear.x = baseSpeed + PIDCal(&pid_speed,u);\n                    \n                    ROS_INFO(\"Gas = %.2f\\tSteering angle = %.2f\",cmd_vel.linear.x,cmd_vel.angular.z);\n                }  \n            }\n\n        }\n    }\n    if(car_stop > 0)\n    {\n        start_loop_flag = 0;\n        if(carVel.linear.x > 0)\n        {\n\n            cmd_vel.linear.x = 1300; //反向刹车\n            pub_.publish(cmd_vel);\n           // for(int i=0;i<20;i++)\n           // {\n           //     pub_.publish(cmd_vel);\n           //     sleep(0.1);\n           //     ROS_INFO(\"cat stop cmd_vel= %f\",cmd_vel.linear.x);\n           // }\n            \n        }\n        else\n        {\n            car_stop = 0;\n            cmd_vel.linear.x = 1500;\n            pub_.publish(cmd_vel);\n\n            //ROS_INFO(\"cmd_vel= %f\",cmd_vel.linear.x);\n        }\n    }\n    else\n    {\n        pub_.publish(cmd_vel);\n        car_stop = 0;\n        //ROS_INFO(\"car run cmd_vel= %f\",cmd_vel.linear.x);\n    }\n}\n\n\n/*****************/\n/* MAIN FUNCTION */\n/*****************/\nint main(int argc, char **argv)\n{\n    //Initiate ROS\n    ros::init(argc, argv, \"art_car_controller\");\n    L1Controller controller;\n    controller.PID_init();\n    ros::spin();\n    return 0;\n}\n"
  },
  {
    "path": "src/art_racecar/src/art_car_controller.hpp",
    "content": "/********************/\n/* CLASS DEFINITION */\n/********************/\nclass L1Controller\n{\n    public:\n        L1Controller();\n        void initMarker();\n        bool isForwardWayPt(const geometry_msgs::Point& wayPt, const geometry_msgs::Pose& carPose);\n        bool isWayPtAwayFromLfwDist(const geometry_msgs::Point& wayPt, const geometry_msgs::Point& car_pos);\n        double getYawFromPose(const geometry_msgs::Pose& carPose);        \n        double getEta(const geometry_msgs::Pose& carPose);\n        double getCar2GoalDist();\n        double getL1Distance(const double& _Vcmd);\n        double getSteeringAngle(double eta);\n        double getGasInput(const float& current_v);\n        geometry_msgs::Point get_odom_car2WayPtVec(const geometry_msgs::Pose& carPose);\n        void PID_init();\n\n    private:\n        struct PID *speed_pid;\n        ros::NodeHandle n_;\n        ros::Subscriber odom_sub, path_sub, goal_sub;\n        ros::Publisher pub_, marker_pub;\n        ros::Timer timer1, timer2;\n        tf::TransformListener tf_listener;\n\n        visualization_msgs::Marker points, line_strip, goal_circle;\n        geometry_msgs::Twist cmd_vel;\n        geometry_msgs::Point odom_goal_pos;\n        nav_msgs::Odometry odom;\n        nav_msgs::Path map_path, odom_path;\n\n        double L, Lfw, Lrv, Vcmd, lfw, lrv, steering, u, v;\n        double Gas_gain, baseAngle, Angle_gain, goalRadius;\n        int controller_freq, baseSpeed;\n        bool foundForwardPt, goal_received, goal_reached;\n        int car_stop;\n\n        void odomCB(const nav_msgs::Odometry::ConstPtr& odomMsg);\n        void pathCB(const nav_msgs::Path::ConstPtr& pathMsg);\n        void goalCB(const geometry_msgs::PoseStamped::ConstPtr& goalMsg);\n        void goalReachingCB(const ros::TimerEvent&);\n        void controlLoopCB(const ros::TimerEvent&);\n\n\n\n}; // end of class\n\n"
  },
  {
    "path": "src/art_racecar/src/racecar_joy.py",
    "content": "#!/usr/bin/env python\n\nimport rospy\n\nfrom geometry_msgs.msg import Twist\nfrom sensor_msgs.msg import Joy\n\nimport sys, select, termios, tty\nimport time\n\nmsg = \"\"\"\n\nCTRL-C to quit\n\"\"\"\nglobal run\nglobal speed_add_once,turn_add_once,speed_mid,turn_mid,control_speed,control_turn,speed_max,turn_max,speed_min,turn_min\nglobal last_speed_add_once,last_turn_add_once\n\n\n\ndef callback(data):\n    twist = Twist()   \n    car_twist = Twist() \n    global speed_add_once,turn_add_once\n    global last_turn_add_once,last_speed_add_once\n    if (data.buttons[6] == 1 or data.buttons[7] == 1):\n        twist.linear.x = 0\n        twist.angular.z = 0\n        print(\"STOP!!\")\n    else:\n        if(data.axes[5] != 0):\n            if(last_speed_add_once == 0):\n                speed_add_once = speed_add_once + data.axes[5] * 0.1\n            last_speed_add_once = 1\n        else:\n            last_speed_add_once = 0\n        if(data.axes[4] != 0):\n            if(last_turn_add_once == 0):\n                turn_add_once = turn_add_once + data.axes[4] * 0.1\n            last_turn_add_once = 1\n        else:\n            last_turn_add_once = 0\n        if(speed_add_once > 1):\n            speed_add_once = 1\n        elif(speed_add_once < -1):\n            speed_add_once = -1\n        if(turn_add_once > 1):\n            turn_add_once = 1\n        elif(turn_add_once < -1):\n            turn_add_once = -1\n        twist.linear.x = data.axes[3] * speed_add_once\n        twist.angular.z = data.axes[2] * turn_add_once\n        control_speed = (data.axes[3] * (speed_max - speed_min) * speed_add_once / 2 + speed_mid)  \n        if(control_speed > 1500):\n            control_speed = control_speed + 30\n        elif(control_speed < 1500):\n\t    control_speed = control_speed - 200\t\n        control_turn = (data.axes[2] * (turn_max - turn_min) * turn_add_once  / 2 + turn_mid) \n        #print('speed: %.2f, turn: %.2f'%(twist.linear.x,twist.angular.z))\n        car_twist.linear.x = control_speed\n        car_twist.angular.z = control_turn\n        print('speed: %.2f, turn: %.2f'%(control_speed,control_turn))\n    pub.publish(twist)\n    pub_car.publish(car_twist)\n\n\n\ndef vels(speed,turn):\n    return \"currently:\\tspeed %s\\tturn %s \" % (speed,turn)\n\n\ndef getKey():\n    tty.setraw(sys.stdin.fileno())\n    rlist, _, _ = select.select([sys.stdin], [], [], 0.1)\n    if rlist:\n        key = sys.stdin.read(1)\n    else:\n        key = ''\n\n    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)\n    return key\n\n\nif __name__==\"__main__\":\n\n    settings = termios.tcgetattr(sys.stdin)\n    speed_add_once = 0.25\n    turn_add_once = 0.5\n    speed_max = 1600\n    speed_min = 1400\n    speed_mid = 1500\n    turn_max = 180\n    turn_min = 0\n    turn_mid = (turn_max + turn_min)/2\n\n    control_speed = speed_mid\n    control_turn = turn_mid\n\n    global pub\n    rospy.init_node('racecar_joy')\n    pub = rospy.Publisher('~/cmd_vel', Twist, queue_size=5)\n    pub_car = rospy.Publisher('~/car/cmd_vel', Twist, queue_size=5)\n    try:\n       \n        while(1):\n            \n            key = getKey()\n           \n            rospy.Subscriber(\"joy\", Joy, callback)\n            \n            rospy.spin()\n            \n            if (key == '\\x03'):   #for ctrl + c exit\n                break \n           \n\n    except:\n        print \"error\"\n\n    finally:\n    \tprint \"finally\"\n        twist = Twist()\n        car_twist = Twist()\n        twist.linear.x = 0; twist.linear.y = 0; twist.linear.z = 0\n        twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = 0\n        pub.publish(twist)\n        pub_car.publish(car_twist)\n\n    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)\n"
  },
  {
    "path": "src/art_racecar/src/racecar_teleop.py",
    "content": "#!/usr/bin/env python\n\nimport rospy\n\nfrom geometry_msgs.msg import Twist\n\nimport sys, select, termios, tty\nimport time\n\nmsg = \"\"\"\nControl Your racecar!\nReading from the keyboard  and Publishing to Twist!\n---------------------------\nMoving around:\n   u    i    o\n   j    k    l\n   m    ,    .\n\nFor Holonomic mode (strafing), hold down the shift key:\n---------------------------\n   U    I    O\n   J    K    L\n   M    <    >\n\nspace key, k : force stop\nw/x: shift the middle pos of throttle by +/- 5 pwm\na/d: shift the middle pos of steering by +/- 2 pwm\nCTRL-C to quit\n\"\"\"\n\nmoveBindings = {\n        'i':(1,0),\n        'o':(1,-1),\n        'j':(0,1),\n        'l':(0,-1),\n        'u':(1,1),\n        ',':(-1,0),\n        '.':(-1,-1),\n        'm':(-1,1),\n        'I':(1,0),\n        'O':(1,-1),\n        'J':(0,1),\n        'L':(0,-1),\n        'U':(1,1),\n        '<':(-1,0),\n        '>':(-1,-1),\n        'M':(-1,1),\n           }\n\n\ndef getKey():\n    tty.setraw(sys.stdin.fileno())\n    rlist, _, _ = select.select([sys.stdin], [], [], 0.1)\n    if rlist:\n        key = sys.stdin.read(1)\n    else:\n        key = ''\n\n    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)\n    return key\n\n\ndef vels(speed,turn):\n    return \"currently:\\tspeed %s\\tturn %s \" % (speed,turn)\n\nif __name__==\"__main__\":\n    settings = termios.tcgetattr(sys.stdin)\n    \n    rospy.init_node('racecar_teleop')\n    pub = rospy.Publisher('~/car/cmd_vel', Twist, queue_size=5)\n\n    speed_start_value = 70 \n    turn_start_value = 50\n    speed_mid = 1500\n    turn_mid = 90\n    speed_bias = 0\n    turn_bias = 0\n    speed_add_once = 5\n    turn_add_once = 2\n    control_speed = speed_mid\n    control_turn = turn_mid\n    speed_dir = 0\n    last_speed_dir = 0\n    last_turn_dir = 0\n    last_control_speed = control_speed\n    last_control_turn = control_turn\n\n    run = 0\n\n    try:\n        while(1):\n            key = getKey()\n            twist = Twist()\n            if key in moveBindings.keys():\n                run = 1\n\n                #print \"key =\",key\n                speed_dir = moveBindings[key][0]\n                if(speed_dir!=0 and speed_dir + last_speed_dir == 0):#Reverse\n                    control_speed = speed_mid                 \n                    last_speed_dir = speed_dir\n                    control_turn = turn_mid\n                    print \"Reverse\"\n                else:\n                    if(speed_dir > 0):\n                        control_speed = speed_dir * (speed_start_value + speed_bias) + speed_mid \n                    elif(speed_dir < 0):\n                        control_speed = speed_dir * (speed_start_value + speed_bias) + speed_mid - 140\n                    else:\n                        control_speed = 1500\n\n                    control_turn = moveBindings[key][1] * (turn_start_value + turn_bias)+ turn_mid \n                    last_speed_dir = speed_dir\n                   \n                    #print \" \"\n                #print \"speed_dir = \",speed_dir\n                #print \"control_speed = \",control_speed\n                #print \"control_turn = \",control_turn\n                last_control_speed = control_speed\n                last_control_turn = control_turn\n            elif key == ' ' or key == 'k' :\n                speed_dir = -speed_dir #for ESC Forward/Reverse with brake mode\n                control_speed = last_control_speed * speed_dir\n                control_turn = turn_mid\n                run = 0\n            elif key == 'w' :\n                speed_bias += speed_add_once              \n                if(speed_bias >= 450):  \n                    speed_bias = 450\n                else:\n                    last_control_speed = last_control_speed+speed_add_once\n                run = 0\n            elif key == 's' :\n                speed_bias -= speed_add_once\n                last_control_speed = last_control_speed-speed_add_once\n                if(speed_bias <= 0):  \n                    speed_bias = 0\n                run = 0\n            elif key == 'a' :\n                turn_bias += turn_add_once\n                last_control_turn = last_control_turn+turn_add_once \n                if(turn_bias >= 80):  \n                    turn_bias = 80\n                run = 0\n            elif key == 'd' :\n                turn_bias -= turn_add_once\n                last_control_turn = last_control_turn-turn_add_once \n                if(turn_bias <= 0):  \n                    turn_bias = 0\n                run = 0\n            else:\n                run = 0   \n            print vels(control_speed,control_turn)     \n            #print \"speed_dir=\",speed_dir,\"last_speed_dir\",last_speed_dir\n            if(run == 1):                      \n                twist.linear.x = control_speed; twist.linear.y = 0; twist.linear.z = 0\n                twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = control_turn\n                #print \"control_speed =\",control_speed\n                pub.publish(twist)\n            else:              \n                twist.linear.x = speed_mid; twist.linear.y = 0; twist.linear.z = 0\n                twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = turn_mid\n                pub.publish(twist)\n\n            if (key == '\\x03'):   #for ctrl + c exit\n                break\n\n    except:\n        print \"error\"\n\n    finally:\n        twist = Twist()\n        twist.linear.x = speed_mid; twist.linear.y = 0; twist.linear.z = 0\n        twist.angular.x = 0; twist.angular.y = 0; twist.angular.z = turn_mid\n        pub.publish(twist)\n\n    termios.tcsetattr(sys.stdin, termios.TCSADRAIN, settings)\n"
  },
  {
    "path": "src/art_racecar/ssh.sh",
    "content": "#!/bin/bash\n\n#for run artrobot\n#Steven.Zhang\n#2018.03.09\n\nssh sz@192.168.5.101\n\n\n\n"
  },
  {
    "path": "src/art_racecar/udev/README",
    "content": "#添加ART_Racecar的USB设备,使用如下指令:\nsudo bash art_init.sh\n然后重启电脑\n"
  },
  {
    "path": "src/art_racecar/udev/art_init.sh",
    "content": "#!/bin/bash\nsudo cp ./car.rules /etc/udev/rules.d\nsudo cp ./laser.rules /etc/udev/rules.d\nsudo cp ./imu.rules /etc/udev/rules.d\n#\nexit 0\n"
  },
  {
    "path": "src/art_racecar/udev/car.rules",
    "content": "# set the udev rule , make the device_port be fixed by arduino\n#\nKERNEL==\"ttyUSB*\", ATTRS{idVendor}==\"1a86\", ATTRS{idProduct}==\"7523\", MODE:=\"666\", SYMLINK+=\"car\"\n\n"
  },
  {
    "path": "src/art_racecar/udev/imu.rules",
    "content": "# set the udev rule , make the device_port be fixed by sanchi_imu\n#\nKERNEL==\"ttyUSB*\", ATTRS{idVendor}==\"10c4\", ATTRS{idProduct}==\"ea60\", ATTRS{serial}==\"0001\", MODE:=\"666\", SYMLINK+=\"imu\"\n\n"
  },
  {
    "path": "src/art_racecar/udev/laser.rules",
    "content": "# set the udev rule , make the device_port be fixed by ls-lidar\n#\nKERNEL==\"ttyUSB*\", ATTRS{idVendor}==\"0403\", ATTRS{idProduct}==\"6001\",MODE:=\"0666\", SYMLINK+=\"laser\"\n\n"
  },
  {
    "path": "src/ls01g/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(ls01g)\n\nfind_package(catkin REQUIRED COMPONENTS\n  roscpp\n  rospy\n  std_msgs\n  sensor_msgs\n)\n\n\ncatkin_package()\n\ninclude_directories(\n  ${catkin_INCLUDE_DIRS}/src\n)\n\n\n\nadd_executable(ls01g src/main.cpp src/uart_driver.cpp)\n\ntarget_link_libraries(ls01g ${catkin_LIBRARIES})\n\ninstall(TARGETS ls01g\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}\n)\n\ninstall(DIRECTORY launch\n        DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n"
  },
  {
    "path": "src/ls01g/Y.txt",
    "content": "﻿Stop the scan command：\n\trostopic pub /startOrStop std_msgs/Int32 \"data: 1\"\n\nStop the motor command（Stop the motor will stop scanning）:\n\trostopic pub /startOrStop std_msgs/Int32 \"data: 2\"\n\nStart scanning（Drive motor, and then open the scanning）：\n\trostopic pub /startOrStop std_msgs/Int32 \"data: 4\"\n"
  },
  {
    "path": "src/ls01g/launch/ls01g.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <arg name=\"inverted\" default=\"false\" />\n    <node name=\"ls01g\" pkg=\"ls01g\" type=\"ls01g\" output=\"screen\">\n        <param name=\"scan_topic\" value=\"scan\"/>         #设置激光数据topic名称\n        <param name=\"laser_link\" value=\"base_laser_link\"/>     #激光坐标\n        <param name=\"serial_port\" value=\"/dev/ttyUSB0\"/>  #雷达连接的串口\n        <param name=\"zero_as_max\" value=\"false\"/>        # 设置为true探测不到区域会变成最大值\n        <param name=\"min_as_zero\" value=\"false\"/>        # true：探测不到区域为0，false：探测不到区域为inf\n        <param name=\"angle_disable_min\" value=\"-1\"/>    # 角度制，从angle_disable_min到angle_disable_max之前的值为0\n        <param name=\"angle_disable_max\" value=\"-1\"/>\n        <param name=\"inverted\" value=\"$(arg inverted)\"/>           # 如果0度方向在串口线的方向上设置为true \n    </node>\n    <!--<node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find ls01g)/launch/rviz.rviz\"/>-->\n</launch>\n"
  },
  {
    "path": "src/ls01g/launch/rviz.launch",
    "content": "<launch>\n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find ls01g)/launch/rviz.rviz\"/>\n</launch>\n"
  },
  {
    "path": "src/ls01g/launch/rviz.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n        - /Grid1\n        - /Axes1\n      Splitter Ratio: 0.5\n    Tree Height: 765\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.03\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 26\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 0\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.01\n      Style: Points\n      Topic: /scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.1\n      Name: Axes\n      Radius: 0.05\n      Reference Frame: <Fixed Frame>\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: laser_link\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 15.7352\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.06\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 0\n        Y: 0\n        Z: 0\n      Name: Current View\n      Near Clip Distance: 0.01\n      Pitch: 1.5698\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 3.14858\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 1056\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000017000000391fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000391000000e200fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000391fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000391000000b800fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000078000000040fc0100000002fb0000000800540069006d00650100000000000007800000033b00fffffffb0000000800540069006d00650100000000000004500000000000000000000004f50000039100000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1920\n  X: 0\n  Y: 24\n"
  },
  {
    "path": "src/ls01g/launch/talker2.launch",
    "content": "<launch>\n    <node name=\"ls01g\" pkg=\"ls01g\" type=\"ls01g\" output=\"screen\" ns=\"l0\" launch-prefix=\"gnome-terminal -e\" >\n　　\t\t<param name=\"scan_topic\" value=\"scan\"/>         #设置激光数据topic名称\n　　\t\t<param name=\"laser_link\" value=\"laser_link\"/>     #激光坐标\n　　\t\t<param name=\"serial_port\" value=\"/dev/ttyUSB0\"/>  #雷达连接的串口\n        <param name=\"zero_as_max\" value=\"false\"/>\n        <param name=\"min_as_zero\" value=\"true\"/>\n\t\t<param name=\"angle_disable_min\" value=\"-1\"/>\n\t\t<param name=\"angle_disable_max\" value=\"-1\"/>\n    </node>\n\t\n<node name=\"ls01g\" pkg=\"ls01g\" type=\"ls01g\" output=\"screen\" ns=\"l1\" launch-prefix=\"gnome-terminal -e\" >\n　　\t\t<param name=\"scan_topic\" value=\"scan\"/>         #设置激光数据topic名称\n　　\t\t<param name=\"laser_link\" value=\"laser_link\"/>     #激光坐标\n　　\t\t<param name=\"serial_port\" value=\"/dev/ttyUSB1\"/>  #雷达连接的串口\n        <param name=\"zero_as_max\" value=\"false\"/>\n        <param name=\"min_as_zero\" value=\"true\"/>\n\t\t<param name=\"angle_disable_min\" value=\"-1\"/>\n\t\t<param name=\"angle_disable_max\" value=\"-1\"/>\n    </node>\n\n<node name=\"ls01g\" pkg=\"ls01g\" type=\"ls01g\" output=\"screen\" ns=\"l2\" launch-prefix=\"gnome-terminal -e\" >\n　　\t\t<param name=\"scan_topic\" value=\"scan\"/>         #设置激光数据topic名称\n　　\t\t<param name=\"laser_link\" value=\"laser_link\"/>     #激光坐标\n　　\t\t<param name=\"serial_port\" value=\"/dev/ttyUSB2\"/>  #雷达连接的串口\n        <param name=\"zero_as_max\" value=\"false\"/>\n        <param name=\"min_as_zero\" value=\"true\"/>\n\t\t<param name=\"angle_disable_min\" value=\"-1\"/>\n\t\t<param name=\"angle_disable_max\" value=\"-1\"/>\n    </node>\n\n</launch>\n"
  },
  {
    "path": "src/ls01g/launch/talker_shell.launch",
    "content": "<launch>\n\t<param name=\"/talker/inverted\" value=\"true\"/>\n    <include file=\"$(find ls01a)/launch/talker.launch\">\n    <!--<arg name=\"inverted\" value=\"true\"/>-->\n  </include>\n</launch>\n"
  },
  {
    "path": "src/ls01g/launch/test.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n    <arg name=\"inverted\" default=\"false\" />\n    <node name=\"ls01g\" pkg=\"ls01g\" type=\"ls01g\" output=\"screen\">\n        <param name=\"scan_topic\" value=\"scan\"/>         #设置激光数据topic名称\n        <param name=\"laser_link\" value=\"base_laser_link\"/>     #激光坐标\n        <param name=\"serial_port\" value=\"/dev/ttyUSB0\"/>  #雷达连接的串口\n        <param name=\"zero_as_max\" value=\"false\"/>        # 设置为true探测不到区域会变成最大值\n        <param name=\"min_as_zero\" value=\"false\"/>        # true：探测不到区域为0，false：探测不到区域为inf\n        <param name=\"angle_disable_min\" value=\"-1\"/>    # 角度制，从angle_disable_min到angle_disable_max之前的值为0\n        <param name=\"angle_disable_max\" value=\"-1\"/>\n        <param name=\"inverted\" value=\"$(arg inverted)\"/>           # 如果0度方向在串口线的方向上设置为true \n    </node>\n    <!--<node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find ls01g)/launch/rviz.rviz\"/>-->\n</launch>\n"
  },
  {
    "path": "src/ls01g/launch/test_ls01g.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n  <arg name=\"scan_topic\"  default=\"scan\" />\n  <arg name=\"base_frame\"  default=\"base_footprint\"/>\n  <arg name=\"odom_frame\"  default=\"odom\"/>\n  \n  <arg name=\"inverted\" default=\"false\" />\n    <node name=\"ls01g\" pkg=\"ls01g\" type=\"ls01g\" output=\"screen\">\n　　\t\t<param name=\"scan_topic\" value=\"scan\"/>         #设置激光数据topic名称\n　　\t    <param name=\"laser_link\" value=\"base_laser_link\"/>     #激光坐标\n　　\t    <param name=\"serial_port\" value=\"/dev/laser\"/>  #雷达连接的串口\n         <param name=\"zero_as_max\" value=\"false\"/>        # 设置为true探测不到区域会变成最大值\n         <param name=\"min_as_zero\" value=\"false\"/>        # true：探测不到区域为0，false：探测不到区域为inf\n\t\t <param name=\"angle_disable_min\" value=\"-1\"/>    # 角度制，从angle_disable_min到angle_disable_max之前的值为0\n\t\t <param name=\"angle_disable_max\" value=\"-1\"/>\n         <param name=\"inverted\" value=\"$(arg inverted)\"/>           # 如果0度方向在串口线的方向上设置为true \n    </node>\n    <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find ls01g)/launch/rviz.rviz\"/>\n</launch>\n"
  },
  {
    "path": "src/ls01g/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>ls01g</name>\n  <version>0.0.0</version>\n  <description>The ls01g laser package</description>\n\n  <!-- One maintainer tag required, multiple allowed, one person per tag --> \n  <!-- Example:  -->\n  <!-- <maintainer email=\"jane.doe@example.com\">Jane Doe</maintainer> -->\n  <maintainer email=\"yutong@todo.todo\">yutong</maintainer>\n\n\n  <!-- One license tag required, multiple allowed, one license per tag -->\n  <!-- Commonly used license strings: -->\n  <!--   BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->\n  <license>TODO</license>\n\n\n  <!-- Url tags are optional, but mutiple are allowed, one per tag -->\n  <!-- Optional attribute type can be: website, bugtracker, or repository -->\n  <!-- Example: -->\n  <!-- <url type=\"website\">http://wiki.ros.org/talker</url> -->\n\n\n  <!-- Author tags are optional, mutiple are allowed, one per tag -->\n  <!-- Authors do not have to be maintianers, but could be -->\n  <!-- Example: -->\n  <!-- <author email=\"jane.doe@example.com\">Jane Doe</author> -->\n\n\n  <!-- The *_depend tags are used to specify dependencies -->\n  <!-- Dependencies can be catkin packages or system dependencies -->\n  <!-- Examples: -->\n  <!-- Use build_depend for packages you need at compile time: -->\n  <!--   <build_depend>message_generation</build_depend> -->\n  <!-- Use buildtool_depend for build tool packages: -->\n  <!--   <buildtool_depend>catkin</buildtool_depend> -->\n  <!-- Use run_depend for packages you need at runtime: -->\n  <!--   <run_depend>message_runtime</run_depend> -->\n  <!-- Use test_depend for packages you need only for testing: -->\n  <!--   <test_depend>gtest</test_depend> -->\n  <buildtool_depend>catkin</buildtool_depend>\n  <build_depend>roscpp</build_depend>\n  <build_depend>rospy</build_depend>\n  <build_depend>std_msgs</build_depend>\n  <run_depend>roscpp</run_depend>\n  <run_depend>rospy</run_depend>\n  <run_depend>std_msgs</run_depend>\n\n\n  <!-- The export tag contains other, unspecified, tags -->\n  <export>\n    <!-- Other tools can request additional information be placed here -->\n\n  </export>\n</package>\n"
  },
  {
    "path": "src/ls01g/rviz/kobuki_rviz_viewer.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n        - /LaserScan1\n        - /Axes1\n        - /Axes2\n      Splitter Ratio: 0.5\n    Tree Height: 727\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.03\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 65122\n      Min Color: 0; 0; 0\n      Min Intensity: 1\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 5\n      Size (m): 0.01\n      Style: Points\n      Topic: /scan\n      Unreliable: false\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.15\n      Name: Axes\n      Radius: 0.05\n      Reference Frame: laser_link\n      Value: true\n    - Alpha: 0.7\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Unreliable: false\n      Value: true\n    - Class: rviz/Axes\n      Enabled: true\n      Length: 0.2\n      Name: Axes\n      Radius: 0.1\n      Reference Frame: base_link\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 30.5779\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.06\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: -10.6774\n        Y: 1.87741\n        Z: -0.740706\n      Name: Current View\n      Near Clip Distance: 0.01\n      Pitch: 1.4998\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 3.14359\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 1028\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd0000000400000000000001820000036ffc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006800fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000036f000000e600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c0000026100000001000001170000036ffc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a0056006900650077007301000000280000036f000000be00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f00000044fc0100000002fb0000000800540069006d006501000000000000073f000003a700fffffffb0000000800540069006d006501000000000000045000000000000000000000049a0000036f00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1855\n  X: 5\n  Y: 14\n"
  },
  {
    "path": "src/ls01g/rviz/slam.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n        - /Status1\n        - /RPLidarLaserScan1\n      Splitter Ratio: 0.5\n    Tree Height: 413\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: RPLidarLaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.5\n      Cell Size: 1\n      Class: rviz/Grid\n      Color: 160; 160; 164\n      Enabled: true\n      Line Style:\n        Line Width: 0.03\n        Value: Lines\n      Name: Grid\n      Normal Cell Count: 0\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Plane: XY\n      Plane Cell Count: 10\n      Reference Frame: <Fixed Frame>\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 0\n        Min Value: 0\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: AxisColor\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 4096\n      Min Color: 0; 0; 0\n      Min Intensity: 0\n      Name: RPLidarLaserScan\n      Position Transformer: XYZ\n      Queue Size: 1000\n      Selectable: true\n      Size (Pixels): 5\n      Size (m): 0.03\n      Style: Squares\n      Topic: /scan\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 0.7\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/MoveCamera\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/Select\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 11.1184\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.06\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: -0.0344972\n        Y: 0.065886\n        Z: 0.148092\n      Name: Current View\n      Near Clip Distance: 0.01\n      Pitch: 1.5698\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 5.66358\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 626\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd0000000400000000000001950000022cfc0200000006fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f0070006500720074006900650073020000019b000001b500000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c00610079007301000000280000022c000000dd00fffffffb0000000a0049006d006100670065000000028d000000c60000000000000000000000010000010b00000294fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003300000294000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004a00000003efc0100000002fb0000000800540069006d00650000000000000004a0000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000003240000022c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1215\n  X: 503\n  Y: 227\n"
  },
  {
    "path": "src/ls01g/scripts/LS01A.py",
    "content": "#!/usr/bin/env python\n# -*- coding:utf-8 -*-\n\nimport serial\nimport math\nimport time\nfrom array import *\nimport rospy\nimport numpy as np\nfrom sensor_msgs.msg import LaserScan\n\nd2r = (2 * math.pi) / 360.0\nr2d = 360.0 / (2 * math.pi)\npack_len = 1812\n\nclass ls01c:\n    def __init__(self):\n        # default parameters on parameter server\n        self.angle_min = rospy.get_param('~/angle_min', -math.pi)\n        self.angle_max = rospy.get_param('~/angle_max', math.pi)\n        serial_baudrate = rospy.get_param('~/baudrate', 230400)\n        serial_port = rospy.get_param('~/port', '/dev/laser')\n        ScanPub = rospy.Publisher('scan', LaserScan, queue_size=5)\n        ScanPub2 = rospy.Publisher('scan2', LaserScan, queue_size=5)\n        angle_range1 = np.arange(0, -math.pi, math.radians(-1))\n        angle_range2 = np.arange(math.pi, 0, math.radians(-1))\n        self.angle_range = np.append(angle_range1, angle_range2)\n        rospy.loginfo(\"laser is connected through port:%s and baudrate is %d\" %(serial_port, serial_baudrate))\n        rospy.loginfo(\"min angle is :%f and max angle is %f\" %(self.angle_min, self.angle_max))\n        rospy.on_shutdown(self.shutdown)\n\n        header = [0xA5]\n        ender = [0xE1, 0xAA, 0xBB, 0xCC, 0xDD]\n        cmd_control = [0x3A]\n        cmd_start = [0x2C]\n        cmd_scan_continue = [0x20]\n        cmd_scan_once = [0x22]\n        cmd_stop = [0x21]\n        cmd_stop_rot = [0x25]\n        self.cmdstr_start = array(\"B\", header + cmd_start + ender).tostring()\n        self.cmdstr_control = array(\"B\", header + cmd_control + ender).tostring()\n        self.cmdstr_scan_continue = array(\"B\", header + cmd_scan_continue + ender).tostring()\n        self.cmdstr_scan_once = array(\"B\", header + cmd_scan_once + ender).tostring()\n        self.cmdstr_stop = array(\"B\", header + cmd_stop + ender).tostring()\n        self.cmdstr_stop_rot = array(\"B\", header + cmd_stop_rot + ender).tostring()\n\n        try:\n            self.device = serial.Serial(serial_port, serial_baudrate, timeout=0.05)\n            print(\"port opened successfully\")\n        except:\n            print(\"Port failed open.\\n\"\n                  \"Are you sure device is connected correctly?\\n\"\n                  \"Please press (ctrl+c) and restart it after checked!\"\n                  )\n            return\n\n        time.sleep(0.2)\n        #self.device.write(self.cmdstr_control)\n        #time.sleep(3)\n        self.device.write(self.cmdstr_start)\n        time.sleep(0.2)\n        #self.device.write(self.cmdstr_stop)  ## make sure no data is sending\n        #time.sleep(0.2)\n        self.device.write(self.cmdstr_scan_continue)\n        time.sleep(5)\n\n        rospy.loginfo(\"lidar is ready!\")\n        print self.angle_min, self.angle_max\n        cnt = 0\n        try:\n            while not rospy.is_shutdown():\n                laser_distance, laser_angle = self.resolveData()\n                rospy.loginfo_throttle(30, \"return data length is %d --->> \"\n                                           \"this message appear every 30s to check driver\"\n                                       % len(laser_distance))\n                if (cnt% 2== 0):\n                    self.ls_scan_pub(ScanPub, laser_distance, laser_angle)\n                else:\n                    self.ls_scan_pub(ScanPub2, laser_distance, laser_angle)\n                cnt += 1\n                rospy.sleep(0.01)\n        except:\n            pass\n        rospy.logwarn(\"keyboard interrupt---> rosnode shutdown is requested!\")\n        self.LaserStop()\n\n    def LaserStop(self):\n        self.device.write(self.cmdstr_stop)\n        time.sleep(0.2)\n        self.device.write(self.cmdstr_stop_rot)\n        time.sleep(0.2)\n        print('Laser is stopped to send data and thread is stopped')\n\n    def resolveData(self):\n        buffer_len = self.device.inWaiting()\n        if buffer_len >= (pack_len * 3):\n            print(\"need to empty buffer\")\n            self.device.read(pack_len * (buffer_len / pack_len))\n        data = self.device.read(pack_len)\n        cnt = 0\n        while len(data) != pack_len:\n            cnt += 1\n            data_memst = self.device.read(pack_len - len(data))\n            data = data + data_memst\n            print(\"timeout %d times to read data from laser\" % cnt)\n            if cnt >= 50:\n                raise IOError\n        # print \"go\"\n        if (data[0] == '\\xA5') and (data[6] == '\\x81'):\n            # print \"found\"\n            print ord(data[1]) / 15.0\n            data_final = data[7:pack_len]\n            pass\n        else:\n            while 1:\n                data_check = self.device.read(1)\n                if data_check != '\\xA5':\n                    continue\n                else:\n                    dat2 = self.device.read(6)\n                    if dat2[-1] != '\\x81':\n                        continue\n                    else:\n                        data_final = self.device.read(pack_len - 7)\n                        print ord(data_final[-4]), ord(data_final[-1])\n                        if (data_final[-4] == '\\xAA') and (data_final[-1] == '\\xDD'):\n                            break\n                        else:\n                            continue\n        laser_distance = [0] * 360\n        laser_angle = [0] * 360\n        for i in range(360):\n            laser_angle[i] = -(ord(data_final[2 + i * 5]) + ord(data_final[2 + i * 5]) * 256) / 10.0 * ((2 * math.pi) / 360.0)\n            laser_distance[i] = (ord(data_final[3 + i * 5]) + ord(data_final[4 + i * 5]) * 256) / 1000.0\n\n        return laser_distance, laser_angle\n\n    def shutdown(self):\n        # Always stop the robot when shutting down the node\n        rospy.loginfo(\"Stopping the laser...\")\n        # self.dev.LaserStop()\n\n    def ls_scan_pub(self, pub, laser_distance1, laser_angle1):\n        # distance data is from -pi to pi\n        laser_distance1 = np.array(laser_distance1)\n        scan_msg = LaserScan()\n        point_num = 360.0\n        scan_msg.angle_max = self.angle_max  # LS-lidar rotates clockwise, which is disobey right-hand rules for coordinate system\n        scan_msg.angle_min = self.angle_min\n        scan_msg.header.frame_id = 'base_laser_link'\n        scan_msg.angle_increment = 2 * math.pi / point_num\n        scan_msg.range_min = 0.15\n        scan_msg.range_max = 3.0\n        scan_msg.header.stamp = rospy.Time.now()\n        # print(\"begin to select\")\n        if (self.angle_min > 0) or (self.angle_max <= 0):\n            range_part = laser_distance1[(self.angle_range >= self.angle_min) & (self.angle_range <= self.angle_max)]\n            scan_msg.ranges = np.flipud(range_part)\n        else:\n            range_part1 = laser_distance1[(self.angle_range >= self.angle_min) & (self.angle_range <= 0)]\n            range_part2 = laser_distance1[(self.angle_range <= self.angle_max) & (self.angle_range > 0)]\n            p1 = np.flipud(range_part1)\n            p2 = np.flipud(range_part2)\n            scan_msg.ranges = np.append(p1, p2)\n        scan_msg.intensities = [255] * len(laser_distance1)\n        pub.publish(scan_msg)\n\n\nif __name__ == '__main__':\n    try:\n        rospy.init_node('LeiShen_Lidar')\n        rospy.loginfo(\"Leishen node is initialized!\")\n        print(\"Initialize node %s with Node_URI %s under namespace: %s\"\n              % (rospy.get_name(), rospy.get_node_uri(), rospy.get_namespace()))\n        if rospy.get_namespace() != '/':\n            rospy.logwarn(\"This node is contained under namespace %s, be careful\" %rospy.get_namespace())\n        ls01c = ls01c()\n        try:\n            rospy.spin()\n            # pass\n        except:\n            pass\n        # rospy.logwarn(\"keyboard interrupt---> rosnode shutdown is requested!\")\n\n    except rospy.ROSInterruptException:\n        rospy.logerr(\"Leishen node initialization failed!\")\n\n"
  },
  {
    "path": "src/ls01g/scripts/create_udev_rules.sh",
    "content": "#!/bin/bash\n\necho \"remap the device serial port(ttyUSBX) to  laser\"\necho \"ls01g usb cp210x connection as /dev/laser , check it using the command : ls -l /dev|grep ttyUSB\"\necho \"start copy laser.rules to  /etc/udev/rules.d/\"\necho \"`rospack find ls01g`/scripts/laser.rules\"\nsudo cp `rospack find ls01g`/scripts/laser.rules  /etc/udev/rules.d\necho \" \"\necho \"Restarting udev\"\necho \"\"\nsudo service udev reload\nsudo service udev restart\necho \"finish \"\n"
  },
  {
    "path": "src/ls01g/scripts/delete_udev_rules.sh",
    "content": "#!/bin/bash\n\necho \"delete remap the device serial port(ttyUSBX) to laser\"\necho \"sudo rm   /etc/udev/rules.d/laser.rules\"\nsudo rm   /etc/udev/rules.d/laser.rules\necho \" \"\necho \"Restarting udev\"\necho \"\"\nsudo service udev reload\nsudo service udev restart\necho \"finish  delete\"\n"
  },
  {
    "path": "src/ls01g/scripts/laser.rules",
    "content": "# set the udev rule , make the device_port be fixed by ls-lidar\n#\nKERNEL==\"ttyUSB*\", ATTRS{idVendor}==\"10c4\", ATTRS{idProduct}==\"ea60\", MODE:=\"0777\", SYMLINK+=\"laser\"\n\n"
  },
  {
    "path": "src/ls01g/slam_launch/gmapping.launch",
    "content": "<launch>\n  <arg name=\"scan_topic\"  default=\"scan\" />\n  <arg name=\"base_frame\"  default=\"base_footprint\"/>\n  <arg name=\"odom_frame\"  default=\"odom\"/>\n  <!--\n<node pkg=\"tf\" type=\"static_transform_publisher\" name=\"link2_broadcaster\" args=\"0 0 0 0 0 0 odom base_link 100\" /> \n  <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"laser_link_broadcaster\" args=\"0 0 0 0 0 0 base_footprint laser_link 100\" /> \n-->\n  <node pkg=\"gmapping\" type=\"slam_gmapping\" name=\"simple_gmapping\" output=\"screen\">\n      <!--remap from=\"scan\" to=\"base_scan\"/-->\n\t  <param name=\"base_frame\" value=\"$(arg base_frame)\"/>\n      <param name=\"odom_frame\" value=\"$(arg odom_frame)\"/>\n      <param name=\"map_update_interval\" value=\"5.0\"/>\n      <param name=\"maxUrange\" value=\"8.0\"/>\n      <param name=\"sigma\" value=\"0.05\"/>\n      <param name=\"kernelSize\" value=\"1\"/>\n      <param name=\"lstep\" value=\"0.05\"/>\n      <param name=\"astep\" value=\"0.05\"/>\n      <param name=\"iterations\" value=\"5\"/>\n      <param name=\"lsigma\" value=\"0.075\"/>\n      <param name=\"ogain\" value=\"3.0\"/>\n      <param name=\"lskip\" value=\"0\"/>\n      <param name=\"minimumScore\" value=\"50\"/>\n      <param name=\"srr\" value=\"0.1\"/>\n      <param name=\"srt\" value=\"0.2\"/>\n      <param name=\"str\" value=\"0.1\"/>\n      <param name=\"stt\" value=\"0.2\"/>\n      <param name=\"linearUpdate\" value=\"0.3\"/>\n      <param name=\"angularUpdate\" value=\"0.4\"/>\n      <param name=\"temporalUpdate\" value=\"3.0\"/>\n      <param name=\"resampleThreshold\" value=\"0.5\"/>\n      <param name=\"particles\" value=\"30\"/>\n      <param name=\"xmin\" value=\"-5.0\"/>\n      <param name=\"ymin\" value=\"-5.0\"/>\n      <param name=\"xmax\" value=\"5.0\"/>\n      <param name=\"ymax\" value=\"5.0\"/>\n      <param name=\"delta\" value=\"0.05\"/>\n      <param name=\"llsamplerange\" value=\"0.01\"/>\n      <param name=\"llsamplestep\" value=\"0.01\"/>\n      <param name=\"lasamplerange\" value=\"0.005\"/>\n      <param name=\"lasamplestep\" value=\"0.005\"/>\n  </node>\n\n\n\n</launch>\n"
  },
  {
    "path": "src/ls01g/slam_launch/hectormapping.launch",
    "content": "<?xml version=\"1.0\"?>\n\n<launch>\n\n\n  <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"laser_link_broadcaster\" args=\"0 0 0 0 0 0 base_footprint laser_link 100\" /> \n\n    <node pkg=\"hector_mapping\" type=\"hector_mapping\" name=\"hector_height_mapping\" output=\"screen\">\n    <param name=\"scan_topic\" value=\"scan\" />\n    <param name=\"base_frame\" value=\"base_footprint\" />\n    <param name=\"odom_frame\" value=\"base_footprint\" />\n\n    <param name=\"output_timing\" value=\"false\"/>\n    <param name=\"advertise_map_service\" value=\"true\"/>\n    <param name=\"use_tf_scan_transformation\" value=\"true\"/>\n    <param name=\"use_tf_pose_start_estimate\" value=\"false\"/>\n    <param name=\"pub_map_odom_transform\" value=\"true\"/>\n    <param name=\"map_with_known_poses\" value=\"false\"/>\n\n    <param name=\"map_pub_period\" value=\"0.5\"/>\n    <param name=\"update_factor_free\" value=\"0.45\"/>\n\n    <param name=\"map_update_distance_thresh\" value=\"0.02\"/>\n    <param name=\"map_update_angle_thresh\" value=\"0.1\"/>\n\n    <param name=\"map_resolution\" value=\"0.05\"/>\n    <param name=\"map_size\" value=\"1024\"/>\n    <param name=\"map_start_x\" value=\"0.5\"/>\n    <param name=\"map_start_y\" value=\"0.5\"/>\n\n  </node>\n\n\n\n</launch>\n"
  },
  {
    "path": "src/ls01g/slam_launch/karto.launch",
    "content": "\n<launch>\n\n<!--\n  <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"link2_broadcaster\" args=\"0 0 0 0 0 0 odom base_link 100\" /> \n-->\n <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"laser_link_broadcaster\" args=\"0 0 0 0 0 0 base_footprint laser_link 100\" /> \n  <node pkg=\"slam_karto\" type=\"slam_karto\" name=\"slam_karto\" output=\"screen\">\n    <remap from=\"scan\" to=\"scan\"/>\n    <param name=\"odom_frame\" value=\"odom\"/>\n    <param name=\"map_update_interval\" value=\"5\"/>\n    <param name=\"resolution\" value=\"0.05\"/>\n    <rosparam command=\"load\" file=\"$(find ls01g)/slam_launch/karto_mapper_params.yaml\" />\n  </node>\n\n</launch>\n"
  },
  {
    "path": "src/ls01g/slam_launch/karto_mapper_params.yaml",
    "content": "# General Parameters\nuse_scan_matching: true\nuse_scan_barycenter: true\nminimum_travel_distance: 0.3 \nminimum_travel_heading: 0.4  # 0.2         #in radians\n\nscan_buffer_size: 67                       \nscan_buffer_maximum_scan_distance: 20.0\nlink_match_minimum_response_fine: 0.15\nlink_scan_maximum_distance: 6         #  6\n\ndo_loop_closing: true\nloop_match_minimum_chain_size: 5\nloop_match_maximum_variance_coarse: 0.4    # gets squared later\nloop_match_minimum_response_coarse: 0.4        # 0.6\nloop_match_minimum_response_fine: 0.6\n\n# Correlation Parameters -              Correlation Parameters\ncorrelation_search_space_dimension: 2\ncorrelation_search_space_resolution: 0.05\ncorrelation_search_space_smear_deviation: 0.05\n\n# Correlation Parameters - Loop Closure Parameters\nloop_search_space_dimension: 10  # 2.8\nloop_search_space_resolution: 0.1\nloop_search_space_smear_deviation: 0.05\nloop_search_maximum_distance: 4.0\n\n# Scan Matcher Parameters\ndistance_variance_penalty: 0.3             # gets squared later\nangle_variance_penalty: 0.35                # in degrees (gets converted to radians then squared)\nfine_search_angle_offset: 0.00349               # in degrees (gets converted to radians)\ncoarse_search_angle_offset: 0.349            # in degrees (gets converted to radians)\ncoarse_angle_resolution: 0.0349                # in degrees (gets converted to radians)\nminimum_angle_penalty: 0.9\nminimum_distance_penalty: 0.5\nuse_response_expansion: false\n"
  },
  {
    "path": "src/ls01g/slam_launch/viewer_rviz.launch",
    "content": "<launch>\n<node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find ls01g)/rviz/kobuki_rviz_viewer.rviz\" />\n\n</launch>\n"
  },
  {
    "path": "src/ls01g/src/main.cpp",
    "content": "#include <iostream>\n#include <std_msgs/Int32.h>\n#include \"ros/ros.h\"\n#include \"std_msgs/String.h\"\n#include \"sensor_msgs/LaserScan.h\"\n#include \"uart_driver.h\"\nusing namespace std;\n\nbool is_scan_stop = false;\nbool is_motor_stop = false;\nbool zero_as_max = true;\nbool min_as_zero = true;\nbool inverted = true;\nstring laser_link = \"laser_link\";\ndouble angle_disable_min = -1;\ndouble angle_disable_max = -1;\nio_driver driver;\n\nvoid publish_scan(ros::Publisher *pub, double *dist, double *intensities, int count, ros::Time start, double scan_time)\n{\n\tstatic int scan_count = 0;\n\tsensor_msgs::LaserScan scan_msg;\n\tscan_msg.header.stamp = start;\n\tscan_msg.header.frame_id = laser_link;\n\tscan_count++;\n\t// scan_msg.angle_min = (angle_disable_min < 0) ? 0 : angle_disable_min;\n\t// scan_msg.angle_max = (angle_disable_max < 0) ? 2 * M_PI : angle_disable_max;\n\tscan_msg.angle_min = 0.0;\n\tscan_msg.angle_max = 2 * M_PI;\n\tscan_msg.angle_increment = (scan_msg.angle_max - scan_msg.angle_min) / (double) (count - 1);\n\tscan_msg.scan_time = scan_time;\n\tscan_msg.time_increment = scan_time / (double) (count - 1);\n\n\tscan_msg.range_min = 0.1;\n\tscan_msg.range_max = 10.0;\n\n\tscan_msg.intensities.resize(count);\n\tscan_msg.ranges.resize(count);\n\n\tif (!inverted)\n\t{\n\tfor (int i = count - 1; i >= 0; i--)\n\t{\n\t\tif((i >= angle_disable_min) && (i < angle_disable_max))\t\t// disable angle part\n\t\t{\n\t\t\tif (min_as_zero)\n\t\t\t\tscan_msg.ranges[i] = 0.0;\n\t\t\telse\n\t\t\t\tscan_msg.ranges[i] = std::numeric_limits<float>::infinity();\n\t\t}\n\t\telse if(dist[count - i - 1] == 0.0 && zero_as_max)\n\t\t\tscan_msg.ranges[i] = scan_msg.range_max - 0.2;\n\t\telse if(dist[count - i - 1] == 0.0)\n\t\t\tif (min_as_zero)\n\t\t\t\tscan_msg.ranges[i] = 0.0;\n\t\t\telse\n\t\t\t\tscan_msg.ranges[i] = std::numeric_limits<float>::infinity();\n\t\telse\n\t\t\tscan_msg.ranges[i] = dist[count - i - 1] / 1000.0;\n\t\tscan_msg.intensities[i] = floor(intensities[count - i - 1]);\n\t}}\n\telse\n\t{\n\t\tfor (int i = 0; i <= 179; i++)\n\t\t\t{\n\t\t\t\tif((i >= angle_disable_min) && (i < angle_disable_max))\n\t\t\t\t{\n\t\t\t\t\tif (min_as_zero)\n\t\t\t\t\t\tscan_msg.ranges[i] = 0.0;\n\t\t\t\t\telse\n\t\t\t\t\t\tscan_msg.ranges[i] = std::numeric_limits<float>::infinity();\n\t\t\t\t}\n\t\t\t\telse if(dist[179-i] == 0.0 && zero_as_max)\n\t\t\t\t\tscan_msg.ranges[i] = scan_msg.range_max - 0.2;\n\t\t\t\telse if(dist[179-i] == 0.0)\n\t\t\t\t\tif (min_as_zero)\n\t\t\t\t\t\tscan_msg.ranges[i] = 0.0;\n\t\t\t\t\telse\n\t\t\t\t\t\tscan_msg.ranges[i] = std::numeric_limits<float>::infinity();\n\t\t\t\telse\n\t\t\t\t\tscan_msg.ranges[i] = dist[179-i] / 1000.0;\n\t\t\t\tscan_msg.intensities[i] = floor(intensities[179-i]);\n\t\t\t}\n\t\tfor (int i = 180; i < 360; i++)\n\t\t\t{\n\t\t\t\tif((i >= angle_disable_min) && (i < angle_disable_max))\n\t\t\t\t{\n\t\t\t\t\tif (min_as_zero)\n\t\t\t\t\t\tscan_msg.ranges[i] = 0.0;\n\t\t\t\t\telse\n\t\t\t\t\t\tscan_msg.ranges[i] = std::numeric_limits<float>::infinity();\n\t\t\t\t}\n\t\t\t\telse if(dist[540-i] == 0.0 && zero_as_max)\n\t\t\t\t\tscan_msg.ranges[i] = scan_msg.range_max - 0.2;\n\t\t\t\telse if(dist[540-i] == 0.0)\n\t\t\t\t\tif (min_as_zero)\n\t\t\t\t\t\tscan_msg.ranges[i] = 0.0;\n\t\t\t\t\telse\n\t\t\t\t\t\tscan_msg.ranges[i] = std::numeric_limits<float>::infinity();\n\t\t\t\telse\n\t\t\t\t\tscan_msg.ranges[i] = dist[540-i] / 1000.0;\n\t\t\t\tscan_msg.intensities[i] = floor(intensities[540-i]);\n\t\t\t}\n\t}\n\tpub->publish(scan_msg);\n}\n\nvoid startStopCB(const std_msgs::Int32ConstPtr msg)\n{\n\tCommand cmd = (Command) msg->data;\n\tswitch (cmd)\n\t{\n\tcase STOP_DATA:\n\t\tif (!is_scan_stop)\n\t\t{\n\t\t\tdriver.StopScan(STOP_DATA);\n\t\t\tis_scan_stop = true;\n\t\t\tROS_INFO(\"stop scan\");\n\t\t}\n\t\tbreak;\n\tcase STOP_MOTOR:\n\t\tif (!is_scan_stop)\n\t\t{\n\t\t\tdriver.StopScan(STOP_DATA);\n\t\t\tis_scan_stop = true;\n\t\t\tROS_INFO(\"stop scan\");\n\t\t}\n\t\tif (!is_motor_stop)\n\t\t{\n\t\t\tdriver.StopScan(STOP_MOTOR);\n\t\t\tis_motor_stop = true;\n\t\t\tROS_INFO(\"stop motor\");\n\t\t}\n\t\tbreak;\n\tcase START_MOTOR_AND_SCAN:\n\t\tif (is_scan_stop)\n\t\t{\n\t\t\tROS_INFO(\"start scan\");\n\t\t\tint res = driver.StartScan();\n\t\t\tROS_INFO(\"start: %d\", res);\n\t\t\tis_scan_stop = false;\n\t\t\tis_motor_stop = false;\n\t\t}\n\t\tbreak;\n\tdefault:\n\t\tROS_WARN(\"Unkonw command: %d \", cmd);\n\t\tbreak;\n\t}\n}\n\nint main(int argv, char **argc)\n{\n\tros::init(argv, argc, \"ls01g\");\n\tros::NodeHandle n;\n\tstring scan_topic = \"scan\";\n\tstring port = \"/dev/ttyUSB0\";\n\tros::param::get(\"~scan_topic\", scan_topic);\n\tros::param::get(\"~laser_link\", laser_link);\n\tros::param::get(\"~serial_port\", port);\n\tros::param::get(\"~angle_disable_min\", angle_disable_min);\n\tros::param::get(\"~angle_disable_max\", angle_disable_max);\n\tros::param::get(\"~zero_as_max\", zero_as_max);\n\tros::param::get(\"~min_as_zero\", min_as_zero);\n\tros::param::get(\"~inverted\", inverted);\n\tros::Publisher scan_pub = n.advertise<sensor_msgs::LaserScan>(scan_topic, 1000);\n\tros::Subscriber stop_sub = n.subscribe<std_msgs::Int32>(\"startOrStop\", 10, startStopCB);\n\tint ret;\n\tret = driver.OpenSerial(port.c_str(), B230400);\n\tif (ret < 0)\n\t{\n\t\tROS_ERROR(\"could not open port:%s\", port.c_str());\n\t\treturn 0;\n\t}\n\telse\n\t{\n\t\tROS_INFO(\"open port:%s\", port.c_str());\n\t}\n\n\tif (inverted)\n\t{\n\t\tROS_INFO(\"This laser is inverted, zero degree direction is align with line\");\n\t}\n\n\tdriver.StartScan();\n\n\tROS_INFO(\"Send start command successfully\");\n\n\tdouble angle[PACKLEN + 10];\n\tdouble distance[PACKLEN + 10];\n\tdouble data[PACKLEN + 10];\n\tdouble data_intensity[PACKLEN + 10];\n\tdouble speed;\n\tint count = 0;\n\n\tros::Time starts = ros::Time::now();\n\tros::Time ends = ros::Time::now();\n\tROS_INFO(\"talker....\");\n\twhile (ros::ok())\n\t{\n\t\tros::spinOnce();\n\n\t\tif (is_scan_stop)\n\t\t\tcontinue;\n\n\t\t// ROS_INFO_THROTTLE(2, \"talker\");\n\t\tmemset(data, 0, sizeof(data));\n\t\tint ret = driver.GetScanData(angle, distance, PACKLEN, &speed);\n\t\tfor (int i = 0; i < ret; i++)\n\t\t{\n\t\t\tdata[i] = distance[i];\n\t\t\tdata_intensity[i] = angle[i];\n\t\t}\n\t\tROS_INFO_THROTTLE(30, \"ls01g works fine!\");\n\t\tends = ros::Time::now();\n\t\tfloat scan_duration = (ends - starts).toSec() * 1e-3;\n\t\tpublish_scan(&scan_pub, data, data_intensity, ret, starts, scan_duration);\n\t\tstarts = ends;\n\t}\n\tdriver.StopScan(STOP_DATA);\n\tdriver.StopScan(STOP_MOTOR);\n\tdriver.CloseSerial();\n\tROS_INFO(\"Keyboard Interrupt, ls01g stop!\");\n\n\treturn 0;\n}\n\n"
  },
  {
    "path": "src/ls01g/src/uart_driver.cpp",
    "content": "#include \"uart_driver.h\"\n\n#define NO_SCAN       0\n#define START_SCAN    1\n#define STOP_SCAN     2\n\nstatic pthread_t id;\nstatic int m_dFd;\nstatic pthread_mutex_t g_tMutex = PTHREAD_MUTEX_INITIALIZER;\nstatic pthread_cond_t g_tConVar = PTHREAD_COND_INITIALIZER;\nstatic double g_angle[PACKLEN];\nstatic double g_distance[PACKLEN];\nstatic int creatPthread = 1;\nstatic struct basedata *g_pcurr = NULL;\nstatic double g_speed;\nstatic int IS360;\nstatic int g_start_scan = NO_SCAN;\n//static struct wifides pack;\n\n#define DEBUG  0\n\n#if DEBUG\n#define ALOGI(x...)     printf( x)\n#else\n#define ALOGI(x...)    \n#endif\n\nstatic int RestartGetData(void)\n{\n\tint wRet;\n\tchar wificmd0[] =\n\t{ 0xa5, 0x3A, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\tchar wificmd1[] =\n\t{ 0xa5, 0x2C, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\tchar wificmd2[] =\n\t{ 0xa5, 0x20, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\n\tALOGI(\"--------start scan----------\\n\");\n\n\twRet = write(m_dFd, wificmd0, 7);\n\t\tif (wRet < 0)\n\t\t\treturn wRet;\n\tusleep(5000000);\n\t\n\twRet = write(m_dFd, wificmd1, 7);\n\tif (wRet < 0)\n\t\treturn wRet;\n\n\tusleep(3000);\n\twRet = write(m_dFd, wificmd2, 7);\n\tif (wRet < 0)\n\t\treturn wRet;\n\n\tALOGI(\"-------------end------------\\n\");\n\n\treturn 0;\n}\n\nstatic int Uart_parameter(unsigned char *data, double *angle, double *dist, int len)\n{\n\tint i, j;\n\tunsigned char *tmp;\n\trplidar_response_measurement_node_t *curr;\n\n\tALOGI(\"len = %d, data[] = %02x  %d\\n\", len, data[len-1], IS360);\n\tif (data[0] == 0xA5 && data[6] == 0x81 && data[len - 1] == 0xdd)\n\t{\n\t\t//pthread_mutex_lock(&g_tMutex);\n\t\t//pthread_cond_signal(&g_tConVar);\n\t\ttmp = data + 7;\n\t\tg_speed = data[1] / 15.0;\n\t\tcurr = (rplidar_response_measurement_node_t *) tmp;\n\n\t\tfor (i = 7, j = 0; i < len - 4 && j < IS360; curr++, i += 5, j++)\n\t\t{\n\t\t\tALOGI(\"%d  \", curr->sync_quality);ALOGI(\"%d  \", curr->angle_q6_checkbit);\n\t\t\tif (IS360 == 720)\n\t\t\t{ //720\n\t\t\t\tif (curr->angle_q6_checkbit != (j + 1) * 5)\n\t\t\t\t{\n\t\t\t\t\tif (curr->angle_q6_checkbit == (j + 2) * 5)\n\t\t\t\t\t{\n\t\t\t\t\t\tangle[j] = (j + 1) * 5 / 10.0;\n\t\t\t\t\t\tdist[j] = 0;\n\t\t\t\t\t\tj++;\n\t\t\t\t\t\tangle[j] = curr->angle_q6_checkbit / 10.0;\n\t\t\t\t\t\tdist[j] = curr->distance_q2 / 1.0;\n\t\t\t\t\t}\n\t\t\t\t\telse\n\t\t\t\t\t{\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\telse\n\t\t\t\t{\n\t\t\t\t\tangle[j] = curr->angle_q6_checkbit / 10.0;\n\t\t\t\t\tALOGI(\"%d  \\n\", curr->distance_q2);\n\t\t\t\t\tdist[j] = curr->distance_q2 / 1.0;\n\t\t\t\t}\n\n\t\t\t}\n\t\t\telse if (IS360 == 360)\n\t\t\t{\n\t\t\t\tangle[j] = curr->angle_q6_checkbit / 10.0;\n\t\t\t\tALOGI(\"%d  \\n\", curr->distance_q2);\n\t\t\t\tdist[j] = curr->distance_q2 / 1.0;\n\t\t\t}\n\t\t}ALOGI(\"j= %d\\n\", j);\n\t\tif (j >= IS360)\n\t\t{\n\t\t\tpthread_mutex_lock(&g_tMutex);\n\t\t\tpthread_cond_signal(&g_tConVar);\n\t\t\tj = 0;\n\t\t\tpthread_mutex_unlock(&g_tMutex);\n\t\t}\n\t\treturn j;\n\t}\n\telse\n\t{\n\t\treturn 0;\n\t}\n\n}\n\nstatic struct basedata *creatlist(void)\n{\n\tstruct basedata *head;\n\n\thead = (struct basedata *) malloc(sizeof(struct basedata));\n\tif (NULL == head)\n\t\treturn NULL;\n\thead->flag = 0;\n\thead->start = 0;\n\thead->end = 0;\n\thead->curr = 0;\n\thead->next = NULL;\n\n\treturn head;\n}\n\nstatic struct basedata *initlist(void)\n{\n\tstruct basedata *head, *p;\n\n\thead = creatlist();\n\tif (NULL == head)\n\t\treturn NULL;\n\tp = creatlist();\n\tif (NULL == p)\n\t{\n\t\tfree(head);\n\t\treturn NULL;\n\t}\n\thead->next = p;\n\tp->next = head;\n\n\treturn head;\n}\n\nstatic int InitPackageSize()\n{\n\tif (1812 == PACKSIZE)\n\t{\n\t\tIS360 = 360;\n\t}\n\telse if (3611 == PACKSIZE)\n\t{\n\t\tIS360 = 720;\n\t}\n\telse\n\t{\n\t\treturn -1;\n\t}\n\n\treturn 0;\n}\n\nstatic void analysis(unsigned char *buf, int nRet)\n{\n\tunsigned char tempbuffer[2048];\n\tint i, j;\n\tint clen = 0;\n\n\tif (nRet > 0)\n\t{\n\t\tif (!g_pcurr->start && !g_pcurr->flag)\n\t\t{\n\t\t\tfor (i = 0; i < nRet - 6; i++)\n\t\t\t{\n\t\t\t\tif (buf[i] == 0xa5 && buf[i + 6] == 0x81)\n\t\t\t\t{\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}ALOGI(\"i0 = %d\\n\", i);\n\t\t\tif (i >= nRet - 6)\n\t\t\t{\n\t\t\t\tmemcpy(g_pcurr->data, buf + nRet - 6, 6);\n\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\tg_pcurr->curr = 6;\n\t\t\t}\n\t\t\telse\n\t\t\t{\n\t\t\t\tmemcpy(g_pcurr->data, buf + i, nRet - i);\n\t\t\t\tg_pcurr->start = 1;\n\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\tg_pcurr->curr = nRet - i;\n\t\t\t}\n\t\t}\n\t\telse if (!g_pcurr->start && g_pcurr->flag)\n\t\t{\n\t\t\tmemset(tempbuffer, 0, sizeof(tempbuffer));\n\t\t\tmemcpy(tempbuffer, g_pcurr->data, g_pcurr->curr);\n\t\t\tmemcpy(tempbuffer + g_pcurr->curr, buf, nRet);\n\t\t\tclen = g_pcurr->curr + nRet;\n\t\t\tALOGI(\"clen=%d,nRet=%d\\n\", clen,nRet);\n\t\t\tg_pcurr->start = 0;\n\t\t\tg_pcurr->end = 0;\n\t\t\tg_pcurr->flag = 0;\n\t\t\tg_pcurr->curr = 0;\n\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\tfor (i = 0; i < clen - 6; i++)\n\t\t\t{\n\t\t\t\tif (tempbuffer[i] == 0xa5 && tempbuffer[i + 6] == 0x81)\n\t\t\t\t{\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}ALOGI(\"i1=%d\\n\", i);\n\t\t\tif (i >= clen - 6)\n\t\t\t{\n\t\t\t\tmemcpy(g_pcurr->data, tempbuffer + clen - 6, 6);\n\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\tg_pcurr->curr = 6;\n\t\t\t}\n\t\t\telse\n\t\t\t{\n\t\t\t\tif (clen - i < PACKSIZE)\n\t\t\t\t{\n\t\t\t\t\tmemcpy(g_pcurr->data, tempbuffer + i, clen - i);\n\t\t\t\t\tg_pcurr->start = 1;\n\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\tg_pcurr->curr = clen - i;\n\t\t\t\t}\n\t\t\t\telse if (clen - i == PACKSIZE)\n\t\t\t\t{\n\t\t\t\t\tmemcpy(g_pcurr->data, tempbuffer + i, clen - i);\n\t\t\t\t\tg_pcurr->start = 1;\n\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\tg_pcurr->end = 1;\n\t\t\t\t\tg_pcurr->curr += clen - i;\n\t\t\t\t}\n\t\t\t\telse\n\t\t\t\t{\n\t\t\t\t\tif (tempbuffer[i + PACKSIZE] == 0xa5)\n\t\t\t\t\t{\n\t\t\t\t\t\tmemcpy(g_pcurr->data, tempbuffer + i, PACKSIZE);\n\t\t\t\t\t\tg_pcurr->start = 1;\n\t\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\t\tg_pcurr->end = 1;\n\t\t\t\t\t\tg_pcurr->curr = PACKSIZE;\n\t\t\t\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\tg_pcurr->flag = 0;\n\t\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\t\tg_pcurr->curr = 0;\n\t\t\t\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\t\t\t\tmemcpy(g_pcurr->data, tempbuffer + i + PACKSIZE, clen - i - PACKSIZE);\n\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\t\tg_pcurr->curr = clen - i - PACKSIZE;\n\t\t\t\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t\t\t}\n\t\t\t\t\telse\n\t\t\t\t\t{\n\t\t\t\t\t\tmemcpy(g_pcurr->data, tempbuffer + i + 1, clen - i - 1);\n\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\t\tg_pcurr->curr = clen - i - 1;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\telse if (g_pcurr->start && !g_pcurr->end)\n\t\t{\n\t\t\tfor (i = 0; i < nRet - 6; i++)\n\t\t\t{\n\t\t\t\tif (buf[i] == 0xa5 && buf[i + 6] == 0x81)\n\t\t\t\t{\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\t\t\t}\n\n\t\t\tALOGI(\"i2=%d,nRet=%d\\n\",i,nRet);\n\t\t\tif (i >= nRet - 6)\n\t\t\t{\n\t\t\t\tif (g_pcurr->curr + i < PACKSIZE)\n\t\t\t\t{\n\t\t\t\t\tif (g_pcurr->curr + nRet < PACKSIZE)\n\t\t\t\t\t{\n\t\t\t\t\t\tmemcpy(g_pcurr->data + g_pcurr->curr, buf, nRet);\n\t\t\t\t\t\tg_pcurr->curr += nRet;\n\t\t\t\t\t}\n\t\t\t\t\telse if (g_pcurr->curr + nRet == PACKSIZE)\n\t\t\t\t\t{\n\t\t\t\t\t\tmemcpy(g_pcurr->data + g_pcurr->curr, buf, nRet);\n\t\t\t\t\t\tg_pcurr->curr += nRet;\n\t\t\t\t\t\tg_pcurr->end = 1;\n\t\t\t\t\t}\n\t\t\t\t\telse\n\t\t\t\t\t{\n\t\t\t\t\t\tclen = PACKSIZE - g_pcurr->curr;\n\t\t\t\t\t\tif (buf[clen] == 0xa5)\n\t\t\t\t\t\t{\n\t\t\t\t\t\t\tmemcpy(g_pcurr->data + g_pcurr->curr, buf, clen);\n\t\t\t\t\t\t\tg_pcurr->end = 1;\n\t\t\t\t\t\t\tg_pcurr->curr += clen;\n\t\t\t\t\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\t\t\tg_pcurr->flag = 0;\n\t\t\t\t\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\t\t\t\t\tmemcpy(g_pcurr->data, buf + clen, nRet - clen);\n\t\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\t\tg_pcurr->curr = nRet - clen;\n\t\t\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t\t\t\t}\n\t\t\t\t\t\telse\n\t\t\t\t\t\t{\n\t\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\t\t\tg_pcurr->flag = 0;\n\t\t\t\t\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\t\t\t\t\tmemcpy(g_pcurr->data, buf + nRet - 3, 3);\n\t\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\t\t\tg_pcurr->curr = 3;\n\t\t\t\t\t\t}\n\t\t\t\t\t}\n\t\t\t\t} //\n\t\t\t\telse if (g_pcurr->curr + i == PACKSIZE)\n\t\t\t\t{\n\t\t\t\t\tif (buf[i] == 0xa5)\n\t\t\t\t\t{\n\t\t\t\t\t\tmemcpy(g_pcurr->data + g_pcurr->curr, buf, i);\n\t\t\t\t\t\tg_pcurr->curr += i;\n\t\t\t\t\t\tg_pcurr->end = 1;\n\t\t\t\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\t\tg_pcurr->flag = 0;\n\t\t\t\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\t\t\t\tmemcpy(g_pcurr->data, buf + i, nRet - i);\n\t\t\t\t\t\tg_pcurr->start = 0; /* no start*/\n\t\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\t\tg_pcurr->curr = nRet - i;\n\t\t\t\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t\t\t}\n\t\t\t\t\telse\n\t\t\t\t\t{\n\n\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\t\tg_pcurr->flag = 0;\n\t\t\t\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\t\t\t\tmemcpy(g_pcurr->data, buf + nRet - 6, 6);\n\t\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\t\tg_pcurr->curr = 6;\n\t\t\t\t\t}\n\t\t\t\t}\n\t\t\t\telse\n\t\t\t\t{             //(g_pcurr->curr+i > PACKSIZE)\n\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\tg_pcurr->flag = 0;\n\t\t\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\t\t\tmemcpy(g_pcurr->data, buf + nRet - 6, 6);\n\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\tg_pcurr->curr = 6;\n\n\t\t\t\t}\n\t\t\t}\n\t\t\telse\n\t\t\t{\n\t\t\t\tif (g_pcurr->curr + i != PACKSIZE)\n\t\t\t\t{\n\t\t\t\t\tg_pcurr->start = 0;\n\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\tg_pcurr->flag = 0;\n\t\t\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\t\t\tmemcpy(g_pcurr->data, buf + i, nRet - i);\n\t\t\t\t\tg_pcurr->start = 1;\n\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\tg_pcurr->curr = nRet - i;\n\t\t\t\t}\n\t\t\t\telse\n\t\t\t\t{\n\t\t\t\t\tmemcpy(g_pcurr->data + g_pcurr->curr, buf, i);\n\t\t\t\t\tg_pcurr->start = 1;\n\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\tg_pcurr->end = 1;\n\t\t\t\t\tg_pcurr->curr += i;\n\t\t\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t\t\tmemcpy(g_pcurr->data, buf + i, nRet - i);\n\t\t\t\t\tg_pcurr->start = 1;\n\t\t\t\t\tg_pcurr->flag = 1;\n\t\t\t\t\tg_pcurr->end = 0;\n\t\t\t\t\tg_pcurr->curr = nRet - i;\n\t\t\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\tif (g_pcurr->start && g_pcurr->end)\n\t\t{\n\t\t\t//pthread_mutex_lock(&g_tMutex);\n\t\t\t//pthread_cond_signal(&g_tConVar);\n\t\t\tUart_parameter(g_pcurr->data, g_angle, g_distance, g_pcurr->curr);\n\t\t\tg_pcurr->start = 0;\n\t\t\tg_pcurr->end = 0;\n\t\t\tg_pcurr->flag = 0;\n\t\t\tmemset(g_pcurr->data, 0, PACKSIZE);\n\t\t\tg_pcurr = g_pcurr->next;\n\t\t\t//pthread_mutex_unlock(&g_tMutex);\n\n\t\t}\n\t}\n}\n\nvoid *Uart_creatPthread(void *data)\n{\n\n\tunsigned char buf[1024];\n\tfd_set read_fds;\n\tstruct timeval tm;\n\tint nRet;\n\n\twhile (creatPthread)\n\t{\n\t\tFD_ZERO(&read_fds);\n\t\tFD_SET(m_dFd, &read_fds);\n\t\ttm.tv_sec = 1;\n\t\ttm.tv_usec = 0;\n\t\tnRet = select(m_dFd + 1, &read_fds, NULL, NULL, &tm);\n\t\tif (nRet < 0)\n\t\t{\n\t\t\tprintf(\"select error!\\n\");\n\t\t}\n\t\telse if (nRet == 0)\n\t\t{\n\t\t\tALOGI(\"select timeout!\\n\");\n\t\t\tif (START_SCAN == g_start_scan)\n\t\t\t{\n\t\t\t\tprintf(\"timeout----\\n\");\n\t\t\t\tRestartGetData();\n\t\t\t}\n\t\t}\n\t\telse\n\t\t{\n\t\t\tif (FD_ISSET(m_dFd, &read_fds))\n\t\t\t{\n\t\t\t\tbzero(buf, 1024);\n\t\t\t\tnRet = read(m_dFd, buf, 1024);\n\t\t\t\tif (nRet > 0)\n\t\t\t\t{\n\n\t\t\t\t\t//ALOGI(\"nRet = %d\\n\", nRet);\n\t\t\t\t\t//printf(\"nRet = %d\\n\", nRet);\n\t\t\t\t\tanalysis(buf, nRet);\n\t\t\t\t\tusleep(30000);\n\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t\t// usleep(30000);\n\t}\n\treturn NULL;\n}\n\nint io_driver::OpenSerial(const char* port, unsigned int baudrate)\n{\n\tint ret;\n\tstruct termios m_stNew;\n\tstruct termios m_stOld;\n\n\tconst char* addr = port;\n\tconst char* addr2 = port;\n\n\tm_dFd = open(addr, O_RDWR | O_NOCTTY | O_NDELAY);\n\tif (-1 == m_dFd)\n\t{\n\t\t//perror(\"Open Serial Port Error!\\n\");\n\t\tm_dFd = open(addr2, O_RDWR | O_NOCTTY | O_NDELAY);\n\t\tif (m_dFd < 0)\n\t\t\treturn -1;\n\t}ALOGI(\"start init serial\\n\");\n\tif ((fcntl(m_dFd, F_SETFL, 0)) < 0)\n\t{\n\t\tperror(\"Fcntl F_SETFL Error!\\n\");\n\t\treturn -1;\n\t}\n\tif (tcgetattr(m_dFd, &m_stOld) != 0)\n\t{\n\t\tperror(\"tcgetattr error!\\n\");\n\t\treturn -1;\n\t}\n\n\tm_stNew = m_stOld;\n\tcfmakeraw(&m_stNew);\t\t    //将终端设置为原始模式，该模式下所有的输入数据以字节为单位被处理\n\n\t//set speed\n\tcfsetispeed(&m_stNew, baudrate);\t\t    //115200\n\tcfsetospeed(&m_stNew, baudrate);\n\n\t//set databits\n\tm_stNew.c_cflag |= (CLOCAL | CREAD);\n\tm_stNew.c_cflag &= ~CSIZE;\n\tm_stNew.c_cflag |= CS8;\n\n\t//set parity\n\tm_stNew.c_cflag &= ~PARENB;\n\tm_stNew.c_iflag &= ~INPCK;\n\n\t//set stopbits\n\tm_stNew.c_cflag &= ~CSTOPB;\n\tm_stNew.c_cc[VTIME] = 0;\t//指定所要读取字符的最小数量\n\tm_stNew.c_cc[VMIN] = 1;\t//指定读取第一个字符的等待时间，时间的单位为n*100ms\n\t//如果设置VTIME=0，则无字符输入时read（）操作无限期的阻塞\n\ttcflush(m_dFd, TCIFLUSH);\t//清空终端未完成的输入/输出请求及数据。\n\tif (tcsetattr(m_dFd, TCSANOW, &m_stNew) != 0)\n\t{\n\t\tperror(\"tcsetattr Error!\\n\");\n\t\treturn -1;\n\t}\n\tg_pcurr = initlist();\n\tif (NULL == g_pcurr)\n\t\treturn -1;\n\tif (InitPackageSize())\n\t\treturn -1;ALOGI(\"finish init seria!\\n\");\n\treturn m_dFd;\n}\n\nint io_driver::StartScan(void)\n{\n\n\tstatic int scanflags = 0;\n\tint wRet;\n\tchar wificmd0[] =\n\t{ 0xa5, 0x3A, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\tchar wificmd1[] =\n\t{ 0xa5, 0x2C, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\tchar wificmd2[] =\n\t{ 0xa5, 0x20, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\tchar wificmd3[] =\n\t{ 0xa5, 0x50, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\n\tg_start_scan = START_SCAN;\n\tALOGI(\"--------start scan----------\\n\");\n//\tif (scanflags == 0)\n//\t{\n\twRet = write(m_dFd, wificmd0, 7);\n\t\tif (wRet < 0)\n\t\t\treturn wRet;\n\tusleep(5000000);\n\twRet = write(m_dFd, wificmd1, 7);\n\tif (wRet < 0)\n\t\treturn wRet;\n//\t}\n\tusleep(30000);\n\twRet = write(m_dFd, wificmd2, 7);\n\tif (wRet < 0)\n\t\treturn wRet;\n\n\tusleep(30000);\n\twRet = write(m_dFd, wificmd3, 7);\n\tif (wRet < 0)\n\t\treturn wRet;\n\tALOGI(\"-------------end------------\\n\");\n\tcreatPthread = 1;\n\tif (scanflags == 0)\n\t{\n\t\tscanflags = 1;\n\t\tpthread_create(&id, NULL, Uart_creatPthread, NULL);\n\t}\n\treturn wRet;\n\n}\n\nint io_driver::GetScanData(double *angle, double *distance, int len, double *speed)\n{\n\tint min = 0;\n\tint i;\n\tunsigned char buffer[PACKSIZE];\n\tpthread_mutex_lock(&g_tMutex);\n\tpthread_cond_wait(&g_tConVar, &g_tMutex);\n\tmin = len > PACKLEN ? PACKLEN : len;\n\tfor (i = 0; i < min; i++)\n\t{\n\t\tangle[i] = g_angle[i];\n\t\tdistance[i] = g_distance[i];\n\t}\n\t*speed = g_speed;\n\tpthread_mutex_unlock(&g_tMutex);\n\n\treturn min;\n}\n\nint io_driver::Reset(void)\n{\n\tchar buf[] =\n\t{ 0xa5, 0x40, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\n\treturn write(m_dFd, buf, 7);\n}\n\nint io_driver::StopScan(Command cmd)\n{\n\t//unsigned char buf[] = {LSLIDAR_CMD_BYTE, LSLIDAR_CMD_STOPSCAN, LSLIDAR_CMD_STOPSCAN_END};\n\tchar stop_scan[] =\n\t{ 0xa5, 0x21, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\tchar stop_motor[] =\n\t{ 0xa5, 0x25, 0xe1, 0xaa, 0xbb, 0xcc, 0xdd };\n\n\tg_start_scan = STOP_SCAN;\n\n\tif (STOP_DATA == cmd)\n\t{\n\t\tusleep(50000);\n\t\twrite(m_dFd, stop_scan, 7);\n\t}\n\tif (STOP_MOTOR == cmd)\n\t{\n\t\tusleep(50000);\n\t\twrite(m_dFd, stop_motor, 7);\n\t}\n\n\treturn 0;\n}\n\nvoid io_driver::CloseSerial(void)\n{\n\tstruct basedata *tmp;\n\tcreatPthread = 0;\n\tg_start_scan = NO_SCAN;\n\t//sleep(2);\n\tpthread_join(id, NULL);\n\n\ttmp = g_pcurr;\n\tfree(tmp);\n\tg_pcurr = g_pcurr->next;\n\twhile (g_pcurr != tmp)\n\t{\n\t\tfree(g_pcurr);\n\t\tg_pcurr = g_pcurr->next;\n\t}\n\tg_pcurr = tmp = NULL;\n\tclose(m_dFd);\n}\n\n"
  },
  {
    "path": "src/ls01g/src/uart_driver.h",
    "content": "\n\n#ifndef  __UART_DRIVER_H\n#define  __UART_DRIVER_H\n\n#include <iostream>\n#include <stdio.h>\n#include <stdlib.h>\n#include <unistd.h>\n#include <string>\n#include <string.h>\n#include <termios.h>\n#include <fcntl.h>\n#include <sstream>\n\n\n#include <semaphore.h>\n#include <pthread.h>\n#include <sys/types.h>\n#include <sys/stat.h>\n#include <fcntl.h>\n\n#include <errno.h>\n#include <malloc.h>\n#include <termios.h>\n#include \"math.h\"\n#include <stdbool.h>\n#include <sys/time.h>\n\n\n#define PACKSIZE 1812\n#define PACKLEN (PACKSIZE/5-2)\n\n#define LSLIDAR_CMD_BYTE               0xa5\n#define LSLIDAR_CMD_START              0x2c\n#define LSLIDAR_CMD_STOP               0x25\n#define LSLIDAR_CMD_SCAN               0x20\n#define LSLIDAR_CMD_END                0xd1\n\n#define LSLIDAR_CMD_RESET              0x40\n#define LSLIDAR_CMD_RESET_END          0xe5\n#define LSLIDAR_CMD_STOPSCAN           0x21\n#define LSLIDAR_CMD_STOPSCAN_END       0xc6\n\nenum Command\n{\n\tSTOP_DATA = 1, STOP_MOTOR = 2, START_MOTOR_AND_SCAN = 4\n};\n\nstruct ture_data{\n\tint ture;\n\tint curr;\n\tunsigned char data[1024];\n};\n\n\nstruct wifides {\n    int start;\n    int end;\n    int flag;\n    int packsize;\n    int packcurr;\n    unsigned char buf[1024];\n};\n\nstruct basedata {\n   \n     int flag;\n     int start;\n     int end;\n     int curr;\n     unsigned char data[PACKSIZE];\n     struct basedata *next;\n};\n\n#pragma pack(1)\ntypedef struct _rplidar_response_measurement_node_t {\n    unsigned char    sync_quality;      \n    unsigned short   angle_q6_checkbit; //角度\n    unsigned short   distance_q2;       //距离\n}rplidar_response_measurement_node_t;\n\nstruct scanDot {\n    unsigned char   quality;\n    float angle;\n    float dist;\n};\n\n\nclass  io_driver\n{\n\npublic:\n\n    int OpenSerial(const char*, unsigned int baudrate);//it means fail if return -1\n    int StartScan();\n    int GetScanData( double *angle, double *distance, int len, double *speed);\n    int Reset(void);\n    int StopScan(Command cmd);\n    void CloseSerial();\n};\n\n#endif\n"
  },
  {
    "path": "src/navigation_tutorials/README.md",
    "content": "# navigation_tutorials\n\nTutorials about using the ROS Navigation stack.\nSee:\n\n- http://wiki.ros.org/navigation_tutorials\n- http://wiki.ros.org/navigation/Tutorials\n"
  },
  {
    "path": "src/navigation_tutorials/laser_scan_publisher_tutorial/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(laser_scan_publisher_tutorial)\n\n# Find catkin dependencies\nfind_package(catkin REQUIRED COMPONENTS roscpp sensor_msgs)\n\n# Call catkin_package\ncatkin_package()\n\n# Add catkin_INCLUDE_DIRS to the include path\ninclude_directories(${catkin_INCLUDE_DIRS})\n\n# Build the laser_scan_publisher executable\nadd_executable(laser_scan_publisher src/laser_scan_publisher.cpp)\n# Add a build order dependency on sensor_msgs\n# This ensures that sensor_msgs' msg headers are built before your executable\nif(sensor_msgs_EXPORTED_TARGETS)\n  add_dependencies(laser_scan_publisher ${sensor_msgs_EXPORTED_TARGETS})\nendif()\n# Link against the catkin_LIBRARIES\ntarget_link_libraries(laser_scan_publisher ${catkin_LIBRARIES})\n\n# Mark executables and/or libraries for installation\ninstall(TARGETS laser_scan_publisher\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})\n"
  },
  {
    "path": "src/navigation_tutorials/laser_scan_publisher_tutorial/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>laser_scan_publisher_tutorial</name>\n  <version>0.2.3</version>\n  <description>The laser_scan_publisher_tutorial package</description>\n\n  <maintainer email=\"william@osrfoundation.org\">William Woodall</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://ros.org/wiki/laser_scan_publisher_tutorial</url>\n  <url type=\"repository\">https://github.com/ros-planning/navigation_tutorials</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/navigation_tutorials/issues</url>\n\n  <author>Eitan Marder-Eppstein</author>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>roscpp</build_depend>\n  <build_depend>sensor_msgs</build_depend>\n\n  <run_depend>roscpp</run_depend>\n  <run_depend>sensor_msgs</run_depend>\n\n</package>"
  },
  {
    "path": "src/navigation_tutorials/laser_scan_publisher_tutorial/src/laser_scan_publisher.cpp",
    "content": "/*********************************************************************\n*\n* Software License Agreement (BSD License)\n*\n*  Copyright (c) 2009, Willow Garage, Inc.\n*  All rights reserved.\n*\n*  Redistribution and use in source and binary forms, with or without\n*  modification, are permitted provided that the following conditions\n*  are met:\n*\n*   * Redistributions of source code must retain the above copyright\n*     notice, this list of conditions and the following disclaimer.\n*   * Redistributions in binary form must reproduce the above\n*     copyright notice, this list of conditions and the following\n*     disclaimer in the documentation and/or other materials provided\n*     with the distribution.\n*   * Neither the name of Willow Garage, Inc. nor the names of its\n*     contributors may be used to endorse or promote products derived\n*     from this software without specific prior written permission.\n*\n*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n*  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n*  POSSIBILITY OF SUCH DAMAGE.\n*\n* Author: Eitan Marder-Eppstein\n*********************************************************************/\n#include <ros/ros.h>\n#include <sensor_msgs/LaserScan.h>\n\nint main(int argc, char** argv){\n  ros::init(argc, argv, \"laser_scan_publisher\");\n\n  ros::NodeHandle n;\n  ros::Publisher scan_pub = n.advertise<sensor_msgs::LaserScan>(\"scan\", 50);\n\n  unsigned int num_readings = 100;\n  double laser_frequency = 40;\n  double ranges[num_readings];\n  double intensities[num_readings];\n\n  int count = 0;\n  ros::Rate r(1.0);\n  while(n.ok()){\n    //generate some fake data for our laser scan\n    for(unsigned int i = 0; i < num_readings; ++i){\n      ranges[i] = count;\n      intensities[i] = 100 + count;\n    }\n    ros::Time scan_time = ros::Time::now();\n\n    //populate the LaserScan message\n    sensor_msgs::LaserScan scan;\n    scan.header.stamp = scan_time;\n    scan.header.frame_id = \"laser_frame\";\n    scan.angle_min = -1.57;\n    scan.angle_max = 1.57;\n    scan.angle_increment = 3.14 / num_readings;\n    scan.time_increment = (1 / laser_frequency) / (num_readings);\n    scan.range_min = 0.0;\n    scan.range_max = 100.0;\n\n    scan.ranges.resize(num_readings);\n    scan.intensities.resize(num_readings);\n    for(unsigned int i = 0; i < num_readings; ++i){\n      scan.ranges[i] = ranges[i];\n      scan.intensities[i] = intensities[i];\n    }\n\n    scan_pub.publish(scan);\n    ++count;\n    r.sleep();\n  }\n}\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(navigation_stage)\n\n# Find catkin\nfind_package(catkin REQUIRED)\n\ncatkin_package()\n\n# Install launch files\ninstall(DIRECTORY launch\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n\n# Install move_base_config files\ninstall(DIRECTORY move_base_config\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n\n# Install stage_config files\ninstall(DIRECTORY stage_config\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n\n# Install the rviz files\ninstall(FILES multi_robot.rviz single_robot.rviz\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/launch/move_base_amcl_10cm.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n  <param name=\"/use_sim_time\" value=\"true\"/>\n  <include file=\"$(find navigation_stage)/move_base_config/move_base.xml\"/>\n  <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find navigation_stage)/stage_config/maps/willow-full.pgm 0.1\" respawn=\"false\" />\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(find navigation_stage)/stage_config/worlds/willow-pr2.world\" respawn=\"false\">\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n  <include file=\"$(find navigation_stage)/move_base_config/amcl_node.xml\"/>\n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find navigation_stage)/single_robot.rviz\" />\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/launch/move_base_amcl_2.5cm.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n  <param name=\"/use_sim_time\" value=\"true\"/>\n  <include file=\"$(find navigation_stage)/move_base_config/move_base.xml\"/>\n  <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find navigation_stage)/stage_config/maps/willow-full-0.025.pgm 0.025\" />\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(find navigation_stage)/stage_config/worlds/willow-pr2-2.5cm.world\" respawn=\"false\" >\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n  <include file=\"$(find navigation_stage)/move_base_config/amcl_node.xml\"/>  \n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find navigation_stage)/single_robot.rviz\" />\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/launch/move_base_amcl_5cm.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n  <param name=\"/use_sim_time\" value=\"true\"/>\n  <include file=\"$(find navigation_stage)/move_base_config/move_base.xml\"/>\n  <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find navigation_stage)/stage_config/maps/willow-full-0.05.pgm 0.05\" respawn=\"false\" />\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(find navigation_stage)/stage_config/worlds/willow-pr2-5cm.world\" respawn=\"false\" >\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n  <include file=\"$(find navigation_stage)/move_base_config/amcl_node.xml\"/>  \n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find navigation_stage)/single_robot.rviz\" />\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/launch/move_base_fake_localization_10cm.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n  <param name=\"/use_sim_time\" value=\"true\"/>\n  <include file=\"$(find navigation_stage)/move_base_config/move_base.xml\"/>\n  <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find navigation_stage)/stage_config/maps/willow-full.pgm 0.1\" respawn=\"false\" />\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(find navigation_stage)/stage_config/worlds/willow-pr2.world\" respawn=\"false\" >\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n  <node name=\"fake_localization\" pkg=\"fake_localization\" type=\"fake_localization\" respawn=\"false\" />\n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find navigation_stage)/single_robot.rviz\" />\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/launch/move_base_fake_localization_2.5cm.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n  <param name=\"/use_sim_time\" value=\"true\"/>\n  <include file=\"$(find navigation_stage)/move_base_config/move_base.xml\"/>\n  <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find navigation_stage)/stage_config/maps/willow-full-0.025.pgm 0.025\" />\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(optenv ROS_STAGE_GRAPHICS -g) $(find navigation_stage)/stage_config/worlds/willow-pr2-2.5cm.world\" respawn=\"false\" >\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n  <node name=\"fake_localization\" pkg=\"fake_localization\" type=\"fake_localization\" respawn=\"false\" />\n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find navigation_stage)/single_robot.rviz\" />\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/launch/move_base_fake_localization_5cm.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n  <param name=\"/use_sim_time\" value=\"true\"/>\n  <include file=\"$(find navigation_stage)/move_base_config/move_base.xml\"/>\n  <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find navigation_stage)/stage_config/maps/willow-full-0.05.pgm 0.05\" respawn=\"false\" />\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(find navigation_stage)/stage_config/worlds/willow-pr2-5cm.world\" respawn=\"false\" >\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n  <node name=\"fake_localization\" pkg=\"fake_localization\" type=\"fake_localization\" respawn=\"false\" />\n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find navigation_stage)/single_robot.rviz\" />\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/launch/move_base_gmapping_5cm.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n  <param name=\"/use_sim_time\" value=\"true\"/>\n  <include file=\"$(find navigation_stage)/move_base_config/move_base.xml\"/>\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(find navigation_stage)/stage_config/worlds/willow-pr2-5cm.world\" respawn=\"false\" >\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n  <include file=\"$(find navigation_stage)/move_base_config/slam_gmapping.xml\"/>  \n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find navigation_stage)/single_robot.rviz\" />\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/launch/move_base_multi_robot.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n  <param name=\"/use_sim_time\" value=\"true\"/>\n\n  <node pkg=\"map_server\" type=\"map_server\" name=\"map_server\" args=\"$(find navigation_stage)/stage_config/maps/willow-full.pgm 0.1\" respawn=\"false\" >\n    <param name=\"frame_id\" value=\"/map\" />\n  </node>\n\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(optenv ROS_STAGE_GRAPHICS -g) $(find navigation_stage)/stage_config/worlds/willow-pr2-multi.world\" respawn=\"false\">\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n\n  <!-- BEGIN ROBOT 0 -->\n  <group ns=\"robot_0\">\n    <param name=\"tf_prefix\" value=\"robot_0\" />\n\n    <node pkg=\"move_base\" type=\"move_base\" respawn=\"false\" name=\"move_base_node\" output=\"screen\">\n      <remap from=\"map\" to=\"/map\" />\n      <param name=\"controller_frequency\" value=\"10.0\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/local_costmap_params.yaml\" command=\"load\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/global_costmap_params.yaml\" command=\"load\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/base_local_planner_params.yaml\" command=\"load\" />\n    </node>\n\n    <node pkg=\"fake_localization\" type=\"fake_localization\" name=\"fake_localization\" respawn=\"false\" output=\"screen\">\n      <param name=\"odom_frame_id\" value=\"robot_0/odom\" />\n      <param name=\"base_frame_id\" value=\"robot_0/base_link\" />\n    </node>\n  </group>\n  <!-- END ROBOT 0 -->\n\n  <!-- BEGIN ROBOT 1 -->\n  <group ns=\"robot_1\">\n    <param name=\"tf_prefix\" value=\"robot_1\" />\n\n    <node pkg=\"move_base\" type=\"move_base\" respawn=\"false\" name=\"move_base_node\" output=\"screen\">\n      <remap from=\"map\" to=\"/map\" />\n      <param name=\"controller_frequency\" value=\"10.0\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/local_costmap_params.yaml\" command=\"load\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/global_costmap_params.yaml\" command=\"load\" />\n      <rosparam file=\"$(find navigation_stage)/move_base_config/base_local_planner_params.yaml\" command=\"load\" />\n    </node>\n\n    <node pkg=\"fake_localization\" type=\"fake_localization\" name=\"fake_localization\" respawn=\"false\">\n      <param name=\"odom_frame_id\" value=\"robot_1/odom\" />\n      <param name=\"base_frame_id\" value=\"robot_1/base_link\" />\n    </node>\n  </group>\n  <!-- END ROBOT 1 -->\n\n  <node name=\"rviz\" pkg=\"rviz\" type=\"rviz\" args=\"-d $(find navigation_stage)/multi_robot.rviz\" />\n\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/move_base_config/amcl_node.xml",
    "content": "<launch>\n<!-- \n  Example amcl configuration. Descriptions of parameters, as well as a full list of all amcl parameters, can be found at http://www.ros.org/wiki/amcl.\n-->\n<node pkg=\"amcl\" type=\"amcl\" name=\"amcl\" respawn=\"true\">\n  <remap from=\"scan\" to=\"base_scan\" />\n  <!-- Publish scans from best pose at a max of 10 Hz -->\n  <param name=\"odom_model_type\" value=\"omni\"/>\n  <param name=\"odom_alpha5\" value=\"0.1\"/>\n  <param name=\"transform_tolerance\" value=\"0.2\" />\n  <param name=\"gui_publish_rate\" value=\"10.0\"/>\n  <param name=\"laser_max_beams\" value=\"30\"/>\n  <param name=\"min_particles\" value=\"500\"/>\n  <param name=\"max_particles\" value=\"5000\"/>\n  <param name=\"kld_err\" value=\"0.05\"/>\n  <param name=\"kld_z\" value=\"0.99\"/>\n  <param name=\"odom_alpha1\" value=\"0.2\"/>\n  <param name=\"odom_alpha2\" value=\"0.2\"/>\n  <!-- translation std dev, m -->\n  <param name=\"odom_alpha3\" value=\"0.8\"/>\n  <param name=\"odom_alpha4\" value=\"0.2\"/>\n  <param name=\"laser_z_hit\" value=\"0.5\"/>\n  <param name=\"laser_z_short\" value=\"0.05\"/>\n  <param name=\"laser_z_max\" value=\"0.05\"/>\n  <param name=\"laser_z_rand\" value=\"0.5\"/>\n  <param name=\"laser_sigma_hit\" value=\"0.2\"/>\n  <param name=\"laser_lambda_short\" value=\"0.1\"/>\n  <param name=\"laser_lambda_short\" value=\"0.1\"/>\n  <param name=\"laser_model_type\" value=\"likelihood_field\"/>\n  <!-- <param name=\"laser_model_type\" value=\"beam\"/> -->\n  <param name=\"laser_likelihood_max_dist\" value=\"2.0\"/>\n  <param name=\"update_min_d\" value=\"0.2\"/>\n  <param name=\"update_min_a\" value=\"0.5\"/>\n  <param name=\"odom_frame_id\" value=\"odom\"/>\n  <param name=\"resample_interval\" value=\"1\"/>\n  <param name=\"transform_tolerance\" value=\"0.1\"/>\n  <param name=\"recovery_alpha_slow\" value=\"0.0\"/>\n  <param name=\"recovery_alpha_fast\" value=\"0.0\"/>\n  <param name=\"initial_pose_x\" value=\"12.0\" />\n  <param name=\"initial_pose_y\" value=\"26.0\" />\n  <param name=\"initial_pose_a\" value=\"0.0\" />\n  <param name=\"initial_cov_xx\" value=\"0.5\" />\n  <param name=\"initial_cov_yy\" value=\"0.5\" />\n  <param name=\"initial_cov_aa\" value=\"0.1\" />\n</node>\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/move_base_config/base_local_planner_params.yaml",
    "content": "#For full documentation of the parameters in this file, and a list of all the\n#parameters available for TrajectoryPlannerROS, please see\n#http://www.ros.org/wiki/base_local_planner\nTrajectoryPlannerROS:\n  #Set the acceleration limits of the robot\n  acc_lim_th: 3.2 \n  acc_lim_x: 2.5\n  acc_lim_y: 2.5\n\n  #Set the velocity limits of the robot\n  max_vel_x: 0.65\n  min_vel_x: 0.1\n  max_rotational_vel: 1.0\n  min_in_place_rotational_vel: 0.4\n\n  #The velocity the robot will command when trying to escape from a stuck situation\n  escape_vel: -0.1\n  \n  #For this example, we'll use a holonomic robot\n  holonomic_robot: true\n\n  #Since we're using a holonomic robot, we'll set the set of y velocities it will sample\n  y_vels: [-0.3, -0.1, 0.1, -0.3]\n\n  #Set the tolerance on achieving a goal\n  xy_goal_tolerance: 0.1\n  yaw_goal_tolerance: 0.05\n\n  #We'll configure how long and with what granularity we'll forward simulate trajectories\n  sim_time: 1.7\n  sim_granularity: 0.025\n  vx_samples: 3\n  vtheta_samples: 20\n\n  #Parameters for scoring trajectories\n  goal_distance_bias: 0.8\n  path_distance_bias: 0.6\n  occdist_scale: 0.01\n  heading_lookahead: 0.325\n\n  #We'll use the Dynamic Window Approach to control instead of Trajectory Rollout for this example\n  dwa: true\n\n  #How far the robot must travel before oscillation flags are reset\n  oscillation_reset_dist: 0.05\n\n  #Eat up the plan as the robot moves along it\n  prune_plan: true\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/move_base_config/costmap_common_params.yaml",
    "content": "#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\n\n#For this example we'll configure the costmap in voxel-grid mode\nmap_type: voxel\n\n#Voxel grid specific parameters\norigin_z: 0.0\nz_resolution: 0.2\nz_voxels: 10\nunknown_threshold: 9\nmark_threshold: 0\n\n#Set the tolerance we're willing to have for tf transforms\ntransform_tolerance: 0.3\n\n#Obstacle marking parameters\nobstacle_range: 2.5\nmax_obstacle_height: 2.0\nraytrace_range: 3.0\n\n#The footprint of the robot and associated padding\nfootprint: [[-0.325, -0.325], [-0.325, 0.325], [0.325, 0.325], [0.46, 0.0], [0.325, -0.325]]\nfootprint_padding: 0.01\n\n#Cost function parameters\ninflation_radius: 0.55\ncost_scaling_factor: 10.0\n\n#The cost at which a cell is considered an obstacle when a map is read from the map_server\nlethal_cost_threshold: 100\n\n#Configuration for the sensors that the costmap will use to update a map\nobservation_sources: base_scan\nbase_scan: {data_type: LaserScan, expected_update_rate: 0.4,\n  observation_persistence: 0.0, marking: true, clearing: true, max_obstacle_height: 0.4, min_obstacle_height: 0.08}\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/move_base_config/dwa_local_planner_params.yaml",
    "content": "#For full documentation of the parameters in this file, and a list of all the\n#parameters available for DWAPlannerROS, please see\n#http://www.ros.org/wiki/dwa_local_planner\nDWAPlannerROS:\n  acc_lim_th: 3.2\n  acc_lim_x: 2.5\n  acc_lim_y: 2.5\n\n  max_vel_x: 0.65\n  min_vel_x: 0.0\n\n  max_vel_y: 0.1\n  min_vel_y: -0.1\n\n  max_trans_vel: 0.65\n  min_trans_vel: 0.1\n\n  max_rot_vel: 1.0\n  min_rot_vel: 0.4\n\n  sim_time: 1.7\n  sim_granularity: 0.025\n\n  goal_distance_bias: 32.0\n  path_distance_bias: 24.0\n  occdist_scale: 0.01\n\n  stop_time_buffer: 0.2\n  oscillation_reset_dist: 0.05\n\n  forward_point_distance: 0.325\n\n  scaling_speed: 0.25\n  max_scaling_factor: 0.2\n\n  vx_samples: 3\n  vy_samples: 10\n  vtheta_samples: 20\n\n  sim_period: 0.1\n\n  xy_goal_tolerance: 0.2\n  yaw_goal_tolerance: 0.17\n\n  rot_stopped_vel: 0.01\n  trans_stopped_vel: 0.01\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/move_base_config/global_costmap_params.yaml",
    "content": "#Independent settings for the global planner's costmap. Detailed descriptions of these parameters can be found at http://www.ros.org/wiki/costmap_2d\n\nglobal_costmap:\n  #Set the global and robot frames for the costmap\n  global_frame: /map\n  robot_base_frame: base_link\n\n  #Set the update and publish frequency of the costmap\n  update_frequency: 5.0\n  publish_frequency: 0.0\n\n  #We'll use a map served by the map_server to initialize this costmap\n  static_map: true\n  rolling_window: false\n\n  footprint_padding: 0.02\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/move_base_config/local_costmap_params.yaml",
    "content": "#Independent settings for the local planner's costmap. Detailed descriptions of these parameters can be found at http://www.ros.org/wiki/costmap_2d\n\nlocal_costmap:\n  #We'll publish the voxel grid used by this costmap\n  publish_voxel_map: true\n\n  #Set the global and robot frames for the costmap\n  global_frame: odom\n  robot_base_frame: base_link\n\n  #Set the update and publish frequency of the costmap\n  update_frequency: 5.0\n  publish_frequency: 2.0\n\n  #We'll configure this costmap to be a rolling window... meaning it is always\n  #centered at the robot\n  static_map: false\n  rolling_window: true\n  width: 6.0\n  height: 6.0\n  resolution: 0.025\n  origin_x: 0.0\n  origin_y: 0.0\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/move_base_config/move_base.xml",
    "content": "<launch>\n<!--\n  Example move_base configuration. Descriptions of parameters, as well as a full list of all amcl parameters, can be found at http://www.ros.org/wiki/move_base.\n-->\n  <node pkg=\"move_base\" type=\"move_base\" respawn=\"false\" name=\"move_base_node\" output=\"screen\">\n    <param name=\"footprint_padding\" value=\"0.01\" />\n    <param name=\"controller_frequency\" value=\"10.0\" />\n    <param name=\"controller_patience\" value=\"3.0\" />\n\n    <param name=\"oscillation_timeout\" value=\"30.0\" />\n    <param name=\"oscillation_distance\" value=\"0.5\" />\n\n    <!--\n    <param name=\"base_local_planner\" value=\"dwa_local_planner/DWAPlannerROS\" />\n    -->\n\n    <rosparam file=\"$(find navigation_stage)/move_base_config/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n    <rosparam file=\"$(find navigation_stage)/move_base_config/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n    <rosparam file=\"$(find navigation_stage)/move_base_config/local_costmap_params.yaml\" command=\"load\" />\n    <rosparam file=\"$(find navigation_stage)/move_base_config/global_costmap_params.yaml\" command=\"load\" />\n    <rosparam file=\"$(find navigation_stage)/move_base_config/base_local_planner_params.yaml\" command=\"load\" />\n    <!--\n    <rosparam file=\"$(find navigation_stage)/move_base_config/dwa_local_planner_params.yaml\" command=\"load\" />\n    -->\n  </node>\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/move_base_config/slam_gmapping.xml",
    "content": "<launch>\n    <node pkg=\"gmapping\" type=\"slam_gmapping\" name=\"slam_gmapping\" output=\"screen\">\n      <remap from=\"scan\" to=\"base_scan\"/>\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"map_update_interval\" value=\"30.0\"/>\n      <param name=\"maxUrange\" value=\"16.0\"/>\n      <param name=\"sigma\" value=\"0.05\"/>\n      <param name=\"kernelSize\" value=\"1\"/>\n      <param name=\"lstep\" value=\"0.05\"/>\n      <param name=\"astep\" value=\"0.05\"/>\n      <param name=\"iterations\" value=\"5\"/>\n      <param name=\"lsigma\" value=\"0.075\"/>\n      <param name=\"ogain\" value=\"3.0\"/>\n      <param name=\"lskip\" value=\"0\"/>\n      <param name=\"srr\" value=\"0.01\"/>\n      <param name=\"srt\" value=\"0.02\"/>\n      <param name=\"str\" value=\"0.01\"/>\n      <param name=\"stt\" value=\"0.02\"/>\n      <param name=\"linearUpdate\" value=\"0.5\"/>\n      <param name=\"angularUpdate\" value=\"0.436\"/>\n      <param name=\"temporalUpdate\" value=\"-1.0\"/>\n      <param name=\"resampleThreshold\" value=\"0.5\"/>\n      <param name=\"particles\" value=\"80\"/>\n      <param name=\"xmin\" value=\"-50.0\"/>\n      <param name=\"ymin\" value=\"-50.0\"/>\n      <param name=\"xmax\" value=\"50.0\"/>\n      <param name=\"ymax\" value=\"50.0\"/>\n      <param name=\"delta\" value=\"0.05\"/>\n      <param name=\"llsamplerange\" value=\"0.01\"/>\n      <param name=\"llsamplestep\" value=\"0.01\"/>\n      <param name=\"lasamplerange\" value=\"0.005\"/>\n      <param name=\"lasamplestep\" value=\"0.005\"/>\n    </node>\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/multi_robot.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n      Splitter Ratio: 0.5\n    Tree Height: 510\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: \"\"\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.7\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 149; 0\n      Enabled: true\n      Name: \"Robot 0: Global Plan\"\n      Topic: /robot_0/move_base_node/TrajectoryPlannerROS/global_plan\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 0; 0; 255\n      Enabled: true\n      Name: \"Robot 0: Local Plan\"\n      Topic: /robot_0/move_base_node/TrajectoryPlannerROS/local_plan\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 0; 0\n      Enabled: true\n      Name: \"Robot 0: NavFn Plan\"\n      Topic: /robot_0/move_base_node/NavfnROS/plan\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 0; 0; 255\n      Enabled: true\n      Name: \"Robot 0: Inflated Obstacles\"\n      Topic: /robot_0/move_base_node/local_costmap/inflated_obstacles\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 255; 0; 0\n      Enabled: true\n      Name: \"Robot 0: Obstacles\"\n      Topic: /robot_0/move_base_node/local_costmap/obstacles\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 0; 255; 0\n      Enabled: true\n      Name: \"Robot 0: Unknown Space\"\n      Topic: /robot_0/move_base_node/local_costmap/unknown_space\n      Value: true\n    - Alpha: 1\n      Class: rviz/Polygon\n      Color: 255; 0; 0\n      Enabled: true\n      Name: \"Robot 0: Robot Footprint\"\n      Topic: /robot_0/move_base_node/local_costmap/robot_footprint\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 149; 0\n      Enabled: true\n      Name: \"Robot 1: Global Plan\"\n      Topic: /robot_1/move_base_node/TrajectoryPlannerROS/global_plan\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 0; 0; 255\n      Enabled: true\n      Name: \"Robot 1: Local Plan\"\n      Topic: /robot_1/move_base_node/TrajectoryPlannerROS/local_plan\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 0; 0\n      Enabled: true\n      Name: \"Robot 1: NavFn Plan\"\n      Topic: /robot_1/move_base_node/NavfnROS/plan\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 0; 0; 255\n      Enabled: true\n      Name: \"Robot 1: Inflated Obstacles\"\n      Topic: /robot_1/move_base_node/local_costmap/inflated_obstacles\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 255; 0; 0\n      Enabled: true\n      Name: \"Robot 1: Obstacles\"\n      Topic: /robot_1/move_base_node/local_costmap/obstacles\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 0; 255; 0\n      Enabled: true\n      Name: \"Robot 1: Unknown Space\"\n      Topic: /robot_1/move_base_node/local_costmap/unknown_space\n      Value: true\n    - Alpha: 1\n      Class: rviz/Polygon\n      Color: 255; 0; 0\n      Enabled: true\n      Name: \"Robot 1: Robot Footprint\"\n      Topic: /robot_1/move_base_node/local_costmap/robot_footprint\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 10\n      Focal Point:\n        X: 0\n        Y: 0\n        Z: 0\n      Name: Current View\n      Near Clip Distance: 0.01\n      Pitch: 0.555398\n      Target Frame: <Fixed Frame>\n      Value: Orbit (rviz)\n      Yaw: 2.73721\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 756\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd0000000400000000000002090000028cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000002540000011a00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004c0000028c000000dc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000028cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004c0000028c000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004fc0000003efc0100000002fb0000000800540069006d00650000000000000004fc0000020b00fffffffb0000000800540069006d00650100000000000004500000000000000000000001e20000028c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1276\n  X: 4\n  Y: 22\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>navigation_stage</name>\n  <version>0.2.3</version>\n  <description>\n    This package holds example launch files for running the ROS navigation stack in stage.\n  </description>\n\n  <maintainer email=\"william@osrfoundation.org\">William Woodall</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://www.ros.org/wiki/navigation_stage</url>\n  <url type=\"repository\">https://github.com/ros-planning/navigation_tutorials</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/navigation_tutorials/issues</url>\n\n  <author>Eitan Marder-Eppstein</author>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <run_depend>amcl</run_depend>\n  <run_depend>fake_localization</run_depend>\n  <run_depend>gmapping</run_depend>\n  <run_depend>map_server</run_depend>\n  <run_depend>move_base</run_depend>\n  <run_depend>stage_ros</run_depend>\n\n</package>\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/single_robot.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n      Splitter Ratio: 0.5\n    Tree Height: 485\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679016\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.699999988\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Value: true\n    - Alpha: 1\n      Class: rviz/Polygon\n      Color: 0; 0; 255\n      Enabled: true\n      Name: Robot Footprint\n      Topic: /move_base_node/local_costmap/footprint\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 149; 0\n      Enabled: true\n      Line Style: Lines\n      Line Width: 0.0299999993\n      Name: Global Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Topic: /move_base_node/TrajectoryPlannerROS/global_plan\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 0; 0; 255\n      Enabled: true\n      Line Style: Lines\n      Line Width: 0.0299999993\n      Name: Local Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Topic: /move_base_node/TrajectoryPlannerROS/local_plan\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 255; 0; 0\n      Enabled: true\n      Line Style: Lines\n      Line Width: 0.0299999993\n      Name: NavFn Plan\n      Offset:\n        X: 0\n        Y: 0\n        Z: 0\n      Topic: /move_base_node/NavfnROS/plan\n      Value: true\n    - Arrow Length: 0.300000012\n      Class: rviz/PoseArray\n      Color: 255; 25; 0\n      Enabled: true\n      Name: PoseArray\n      Topic: /particlecloud\n      Value: true\n    - Alpha: 0.699999988\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: false\n      Name: Global Costmap\n      Topic: /move_base_node/global_costmap/costmap\n      Value: false\n    - Alpha: 0.699999988\n      Class: rviz/Map\n      Color Scheme: costmap\n      Draw Behind: false\n      Enabled: true\n      Name: Local Costmap\n      Topic: /move_base_node/local_costmap/costmap\n      Value: true\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 0\n      Color Transformer: FlatColor\n      Decay Time: 0\n      Enabled: true\n      Invert Rainbow: false\n      Max Color: 255; 255; 255\n      Max Intensity: 1\n      Min Color: 0; 0; 0\n      Min Intensity: 1\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.100000001\n      Style: Flat Squares\n      Topic: /base_scan\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/ThirdPersonFollower\n      Distance: 43.5168953\n      Enable Stereo Rendering:\n        Stereo Eye Separation: 0.0599999987\n        Stereo Focal Distance: 1\n        Swap Stereo Eyes: false\n        Value: false\n      Focal Point:\n        X: 0\n        Y: 0\n        Z: 0\n      Name: Current View\n      Near Clip Distance: 0.00999999978\n      Pitch: 0.710398257\n      Target Frame: base_link\n      Value: ThirdPersonFollower (rviz)\n      Yaw: 2.82039738\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 723\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd00000004000000000000016400000274fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000002540000011a00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004100000274000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000274fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004100000274000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004fc0000003efc0100000002fb0000000800540069006d00650000000000000004fc0000030000fffffffb0000000800540069006d006501000000000000045000000000000000000000027d0000027400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1276\n  X: 2\n  Y: 24\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/stage_config/maps/willow-full-0.025.pgm",
    "content": "P5\n# CREATOR: GIMP PNM Filter Version 1.1\n2332 1825\n255\nLZͱ|[(9ͥƫۊW͢z|Ѿ˿ͳͶcj͈X͵糿jn͋niͭ\u001eyx͞mѭnͧ&ܹͣdԭ6Ҷ+\u001f9Vޱɬ<Ꞵ)͖ꈛͶGF\u0015M͎ͳ\u0019&\u0013ͧ͘Ι\u0012\\ͻƳ˶8Ĺͥ-\u001b\u0018|͋͸̈́ʹ͛y~Xͬ~ʽ̈́i̧͉O.\u0018ڭsiOBbʶͼ͡jJۺaͳƆ`敇ІG͵ױ؍̕颶ܱImͰэF]Y&aͥͿJ5\u001f\nv`s~z隁ӆN΋ןFѻu.dⴿc͵tr9ͮ̀ nrͽ͹lKBa{~˳ղsçf멡âЯoi͍гť͕YͤS͙[醧0CDemoF\\эs綬|~׸²ES/ʤzPT$ʉ̀s3\u0003zaƺͯn{.\u0019y{멬һѦ]ŨCąɹ\u001dՄ|i|\"{ӡfǓ͓voCmѵūȫͬE]ɱ9̯і*ͦʚiS>3\rTxJ5\u001f\n¬̓lW͸;ʹƪx\u000f͇M׈$Ͳ?wɐͺRͺW<@ٚͮpͽCoF\u0011\frG}j(\u0010:^;f%\u001bFr3?,\u0017\u0001\n-MvȰ͓gͪͨ͟Ⱦ͝ub͹͌lΈr͠zοÖs͹\u000fgC˳\tg͆ñ.͹͟cͳ͔ͩ?ƎʖD\u0011̟tb̳.o$l7赎n\\ƍډtmO:$D\u0016sq\\F0\u001bTwV?=z_uNrͅelYhUkaa]K6kzhܚLϘqҵǜ͘B͹ͼk͊grͷ\u00173E^]ͨ ͙漠똊m\u000fqhW`͎ڵ̈́Qv|\u000e]]Kiʵ(pa놯jfVqyůy|mFE\u0003\u001d^L]V\u0017>3\\v{oijZrF[­Q{ۙξ{JӃȝsͷɊts{x\u0010\u0006͈b̵ͦ͠r޾Oϭ\u001cF'Q͚ɩ͑g̘\u0014}wNQQƑ\u0018cӚeͲ斈幵ӸÒR\t$eA{źVA9\u001d,ݵ\u0010a\u0014*W\u0000D7zZ[ˤͅexɰo{x\u0003hz`{g|هwQO➷~Ѓ(ͻFZx2QC;xsM/䗪մ|^ٟqe\u00129/n͋Ў)RݺͶkw͖p͡e͹ȻmͺdNy_| vjǽϛưͯ͋iɹͰ%EHSkǷ\\sjwo?謡b@؄OԤш@;Ġd͒ұҷ4#ycW͑]G1ͿS>(Xmu`Jq\t\u0006\u0014]lWA+mogxbM8\"\fTpHG\"C.\\\u0012\u000fLѦآB͒Vy%۽Ł\u0014ҙͺϦkmͧͧhH̀Ͷͽr͠걡͇a̎NӳX6W|fgY\b͚XF`C\u0007\u0010+Ew<T.BK,dnkdJ`IVW7\u0001\\\"\"+=RF[ZV=l$}m>ͱ͡F΅\"ͱҚ຃|tģͼ~øͳɍIfʈȘ͆ͳ͠_]ѕڹͲØߺ֘،ҫ{IڐSݼ\u0001̈́dR,1\u001fbRΌ JĤňvBUTA`͸ʦS3ȷJ厝ũ͝k邨ƴ;q˩ؗأ͡¾-~ڢ~aOcͽzтW׵cλeͭTt3\u001e\b\fAcFu\\ͱzReȗ{M2\u001dnf \\ͧiͮ豦ԽΜ_ͥ]-ᄩQXzۖ|ͺ͡}͊Q͓vͫ~͗P˵ĒK\u0010)о؃ϟͽκ͢\u0001͜Ľbio_ͽot;k2D᳂ܢ}eqlٙŻ^Cd۫iNɫd?ͭ*}Ͳ;iK״ͮeͮ҇O~=\u0012(D_Z͖;̶V0ͿmuҧA:bg?Î_ʉ?rǢͿi\"kأ\u001dڶ,l6͓Űͻ()rr}ņٹƌXɵZq̬o\u001a\u00105f=o\u0011\boX\u0001bY\u0011d8ͮ|\u0019G#\fDWwaBZ'\u00024fdN9#\r\u0006\u000eͽͼխߣ͌«遌͂ÿͶ¶vدפ)ʧ.mzǥڳǻީ͎ߨͻ;ړHoȄq\\F0\u001b\u0005\u000b\u00199r9{'|aqt4ybVkwͷĺǳ͚n{w͵^N͋ͣΟ2\u0004;Ͱ1tڧmol}ƾͷ\u001ae֖ǬڨТϸ#Aڟr۷ʨ̅\u0002RmL*>%vVr\u000f\u0016\u0000\u0019l'8W\u0007<oyͥ\u001960ͻfkGMĹͥȖͭe͛\u001cZ~9{>͆͟BԽ\u0016ͱ͎`cí͹͚c͍ͼͷތk*sܸ쪶i4Fƿ;hӌ?Y`!ɴؾy<V\u0003\"FwxoͦĴ1{ͤVͣ_\u0004r*U͛ҽ_E_K;4Z\u000b\f'ARgXwyb\u0015~Չ fvpsdgx\u0014tb͕&XРͨ\u001b揋;nLB|s紞Qxh\u0001qSZ͐Z͟Ԭͯ[Wͷpqc^g[ͶjQu<مv粄꽾ͶꯛǠRM·Z\\ӌgl\u001d_ܖsȢx˹ɑ%@\u0012tTzͼʹR=Wr͸-}¬s/Bkƣdp\u0013+}ЯQXc~ܖ\u000fq|uǂh\\]͝-\u0000/;ՙ̆؝ͳͬԓAPͿ͐k\\ͣ|hxͤ\u0002(U4y\u001ePô옇;s\u0018{Utܱo̹ͽͻ͕sڰ~͇ro\bR\u001f͎ͩ͜6̷umL7!\n!ͬlqwM\u0006\u0002\u0001֏i͊drKld\u000fe*Es\u001b\u0005\r\u001bf~hRxreeϔͷͺcyxdm؜Qʷ7͹<Y\u0003ԻͅwڡN\u0000B7R/\u001bpߣ଱筹ǹĥ{F|45Fs,hNĠoǷ͹]ͯ(a9\u0015\u00003؛륔&VͽɀRͦU\u0001V&5~KƤiwѿ_G;Z}ѱƲwJ\u0012ϡˬƆPKͺ\u0003(2(,>ͦ{\u0003ͧ͘rըil;QsB}Dvӑ\u0002OݬͫKkbͮԩڰW׻5սDL\u000e\u0007\u00054'<Er\u0017߫{ͰP;%\u000f9˝gȾӷĺotӵ^xZ\"oK\\إˢ\u0016_\\͛͐͢d;ǵ@W\u00072Z˻}S\u0002ͺ8Yтňo&͘`}k/8sWR`q͝$ͽx폩ٺ͚Oa\u001fƮ9p(ͺDnͿ\ft#\u0003ϯp몾ߔb\u0014@돰дՃl\u0013\u0001lP(NI$\u0010dO\u0003'ƢKǙwkjӈ=6_l:@YP$~nC\u0016\u0000귱آdg9dbʢ`8>Wxj粬zu˧ۑ}a\u001a媨tzf`oͮM֑GBϒvMo\u001a޾ZoHɍT@˵92\u000b֭ۢeLWodt㯚|H\u0017αJ-|⯽˚iϣj#ƳWͦѴ\u0017\u001cQxܘRͫ1Ac'͖urdʁ~оӾ\u0014\t|թ;p%\b\"<59r{ǚudr~0㊣<ʹ\u0003ȩ#ͳ㕸~[}Mi۰K͖剙>{B͒Ȧ\u0017͓+Fw9͊ͩ\u0017t^J~qL$=,srߒ}͖͙ͬuWȝͼʾY͹oƑʑ⸡ͮLQgͪLh\f\u0013.hƛrNZtD.͵fyݽͶoͻͿu͔\u001dEsҡͽm͵c}\\ݨ^яXZͦK ͞[\u00071=\u000eͧͬA7iӤOݿڨ͇́tE[`l{|ϱ\u00196A5t蠪ZsVaMD\u001dsͼĥͼඖw\u0006l7ntͱ)͏`ͥǙͯ ʞӾϨNyͷ~͆r\u0014rn4˄\n8棥t͌h/\u00152oUY>͊>ͥݦͣ\be՟ܒ͵Zi͍wͰ}\u0018̈́͝ͼͨwѶ5 (jЇͷ&ΠHߍbDڝ@`Qg<<#o+՞\u001cu:Mͭ7ͥuͽ:߾6yYͿ#٧`eBeSֳУێ˷r^өk͸i͇3ffPٶ#L(˄$q4꾩޿;L객͸l*ʄ\u0014µ?ɩگqxt]̡H̪jzQ͝~\u0002B&:͠DzǠͷ6ڮG;y<\r镵֮`\u0010cͪpұ;͢\"ͮsr`͞r\u0005ȭ\u001b♬Ll͋ŧ3̜RϝYjͶRZ \u001cX蒤͖jڸͪͣjȨټ;͉ذ#K(mQ٦>ã˜wAܛr̀pͺTҠ>\u0011͞`Lͯ.ԙ{ͱ]Ͱ4ͽm°o͑\\\rLͫ͒ʢrͶ[aJu$\u0010ͪvT˲H);yҶjz5͆xcϰc.b̓߼z?\u001aM4̎Lͪ͐ڸU\u0017ۂ_̅G>ͻҪ|ͱeXƼg\rA\u001b݊\u000f篟ˬʹͼe(k\u001f̣Qͳ¢ğ͉М?\u0018\n͗mɰͷzo栕෻jy\u001b'\n<l\nͩǽͼ\u0012Ɍ\u0017Pґͺred\u001f֟1THͺg̀Wiβ඲\u000b\u0012ͮHT@`qykc͈\u001dpƲ͝R͠qŘ|c\u001a#'\u001fͶȑq?)\u0014Ρq˷spƹǯ~\"Ϳɥ͟GyͻbfBœ\u0014\u0019\\ɞp=Iy@g봯i9@ͨ.ƅ}ͷޛo͔P瓰|\rtp[E/\u001aH͊I͒Iͫ@ͻɕBO9C\r\u0002\u001f}͋UrVcRm0Cڝ˾K~\u000e\n\u0016;^͍ͩ(Mԅͷ+͒̚(\"3HXfuz߽͡f3\b܎\u0002\t\u0010zconxIvmǾVͼh|Rb͍沦c}Sͅ?>u\\Ϳ͑͗U\u001d#8K3`UgXͳ!ҿuPvby]nL=ٝ̀ͿcD3koޤ5\u001c=CxLϸrtwuŹ̈́Y><ŎЭ׉OT\b&Z*»͵|U~ͧO{Ab8ͭ{{\u0015ľ+d̀\u001bͤgd2ҟqf̝\u000bɡŎ⯹^\f8ͼ:\u000e\u0013{Iܤ\u0016Q͵˦{GuMyw̕Uy`\u0005\u000bAh暻՘K\u0000Qͷd%,٢@gͦĳ͎jpqcK|oySQ\u0019\u0015YbiS͂T\r\u0006hyZ*j'ߚlR~̻͋͋\u0018ͭҐʹ\u0015;͎La|q:ͱ?#\u001bĪηiͅόͯ͗\u0004ͷͤ2嵰͗Kƻ왩z仞ƪ湺S\u0019Үʿ\r}\b\u001aBeͪL3=ٍWB_T\u001cCĐ}gQ<&\u00110$Sf2͹\u0017cflUGl͚LS\u0001}Б͓mYRf+<H\"x6]\"19O_N|,ZY{q{\u0002jNͽ\u0019)Tģ͋]ͅdOͲ֤j<=M+\\v~h̩jwCXϽŷ\u0018¦ךiˑrП͐sͨ9έʹҡ}xͅP奸QjTJK[&p602ͅT̶ô肬Q綋XǄD͑H⢐gY͗Zۚٶޥۯ;dܲQ͜4͸/7ŪoS/ͧ.걟̀fӰͷ1%ЬwDs{澿\u001aͽ\u0013wɖqԬ|dܷͪF>ͶS^hi4-~͎E͛\tǈˌͪ\u001a͌Xg\u0017uVѥ\u000ers+Ͳkrڤɽ跽v_̾\nڬ͸нæʻԵ[q笶PЊ寎z\u0006P͵4g͞Qą~;6S\u0018i͸\u001c̺Κʤ͋r䌛͑ܤN7͹oڨ9nw#G5\u0011jY觮e\"͹Ƴ׳Б1Lԯ]Ftųt͹Ѩ3Dۧsy4͖8OuM̽ռ9͒~͒vؐ[ƞK@ͿϠ5x˽͐Aص͠IͿuIii.߇{ꌇ߬ͽlʹuH\u000bٚ`vkS2~͵͈ⷵVͷڤ֭w)4ۧHͺ\u0012)\u0019ݱ͇\u0005[>z\u001erz͜<ͿmͅXps)ε\u0002߫Bٿꞷ]qvҀͱ-͛͞WïGz!\u0016_☚?{d,Ͱ\u001d+{͸{q\r͹㵂d;fߏþi͐Kl\u00135\u0004yx͟@ɲpzJLyt͛mѵ;1̦ͥ?$oͯκ͓f▙ͼ?d˺͢?Nي݆SFamOͬG̫ͿO˫ꩧ̈́z߾O%ድͨJ_q|Sp֜W΅6ۧѲ)͔ӝ`s;ϐȬͻū}ꆯ\u0018ǟlIsͱүԢcMͶ͂,Ȑt釐M=ܭ|԰hjԅͿm͘eЌܪͳn?[ϵ^S9]\u0016\u001c`͘\u0002LֆϦPjբ˺ͳ~CSѾͪ6r\u00065νJ˶Ϳ=糾h*+ݍİ肆͊ͮhͼ\u001fjUÖͭ ͉0oZbˎx7Ȁ\u000fj9ra'pܜ1ޜU_Ϳl\u0007Ͷصssߨp朏㮱{ǱZbʥuP\u001a\u000bX:́/Ϫ?Z?\u001f@6\u0004ͿP\u000fŬڭSתY\t&r͚҇\u001dz֑ͨZSսʼ>\f0͵TVtڶԫg^Ҍ{ˮT$ݝ!Pssh̪R0͹!PO^ׄͬ'a~͜SfΥK8E1y䱙n37{߿܂ο^{֩-͍Y6ۉ6Cʤ~v5<HͮqLkͺUy]gG\u0013͛=I[uۇkK`\u0016\u0003e߳m5̾\u0010ͯwNͶVbf̷ɵԛ۹˰BmuzHlahٮܺѻ߼ǦQͧޱOʹ{\u0012:ǩQvwg\u001e}:d#ف˘ڹw;В_ƽYι9u.$ͻ#ܷ͌N3ͪ2ͳӌ͞\u001aSp͌'ŽѤ͉ɰ\u0012ͽHN&\u0000VeTͧ9s͑zlv}Vվ;.ÐݨתѸͅ'\u001aMͥ8\bqth=ʲ)!\u000b\u0013ԙ\u000bD˹·䪹]\u0019\u000beMͅͯçcͺt[\u001cUݬôֲؽڧӾϯ\tԟOSᄏzd]H¹xЩϦ䚌ͬ\u00033wAԠͣK$͡xz`uܸ/ͣ|V/&VGdx>^1~ܕ׿C;\n3֤_\u001f\u0003/[t\u0016$\f׹rVG@ʏͰSdͳx՘͎ZپW͠{nͯ/ڟ͸*k$[HϽ\b͢gH\u001cϜe?Png93t4Ba͹\u001d߯ՠI$0;^oQ\u001cwbGHmăͿɿ뵕޺;mgptdP͵΀y$_yҫHр*Y68B6G2ԍS]mѻͪIͳBZͫӝIaŗCEu͏O'}g}Wϧ}f^H̛Qķ֗̎/͹(9D!MaOپO\\Έʮ͙JzJƍɖ-\u0015խa˯Ў\\اmҢͤˮKbְ̬F͓Ϳ\nG͖͊G2j͡6řεP˲Uze\u0005͉sz컠ʴߩڕcєaNPÚȰEQ߼քkBJ~>\tenTӝ̹́͵͹Io\u0003[ʊ\u0002A{I{+S\bŵ\u001cƦ\nן축rYX譺rxrit=qz[Tͤ$r͙kͽͣyOԬscB\u001ed͂\u00010ͪͿ̬lOlbťɫͷTʔf۶IkaǸiӔzM\u0011$vv^qLcq͋?|H![y[WHq1\u0001\u000esxVSz{wp̵ƧÖÿ󹆫\"Gziͤli.晨[矵NƠb6\u0003f_lӵ͚ObúAͿ\u0016̋PͲ֌dͼ̓JվۺçǬP֝ȵڼjSsӸi̬f˾͢8qהԮ«ԳQ9=ǻó俥g\fǏ͸;Tͺͽͭܨ-wͩ\u0003-\u0000\u0019Gι\\YZў˼\u0015r#Ǽ@.\\\u001cEfe\u0016\u0010}͝pɴѭľȱб᠗صњrϻi\u0001EʹXYg%a;ͽ>n\u0006צ͠Ohşcz׿JPͽ)kMͱIÖvT͏Ҋԩ,ɬxīˬƶ̎;ìȲʔɸŜxbyvۏ\u001d\u001bǳЫ]?nͽ_Xɘik&0\u001b \u0019~hR=7ʴͮ窋p͙&bȝ\\cϻ-nۖF1nVAG}٠|͙riùʚ{sήؽ4ͩ\u001cLݯӳŹЌĬcrQןdX{Y),Q0]ҧr_x\u0011,]Q5K-::\u0003\u0015\u001c)b|Jì;ҕnXdz\u0014VtͭͅͰͽd3C͎jé׻̶̀ͻ}jѮ袥y\"፽(ƟܸڿtnͿ\u0014橪ͫɳǡ|_?䧴扎ye^Tzz֌Jԧޣbοb\u0012ڰζ׍ߐ\u000eߒ@|§+BkҵĺH:zs{ڸʖkXZTt{ŗXZxL\u0000\u00181Bzkи߶jpѿceԲ)\u001d\u0018摐߹ͲbeǛHe\\t<|ڹiݿ/{gΌ೽2YʯF{|γ`ĖŦװΫι㽎dЮںɬDگM2!ͥ씛/1㞎氭ĘͤĳmȅgӲlғ-Źɋڂݰ͵۾ٰ״̶Αؼ塵>QڲGyɴё!ۛt鲤۲Ǚݡs~ܮøݲ߫ɰȮɶpȐ\u0019kuPͭǜͰқQfM͜媚ʑzݑѶѳԇөѢۗ豩ׁ\r`ڹwkksa\rس̓׏͖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\u0017ͪ1^sͪZyꂑlۖFYʹ{mⱷͼ(\by̯q͘q󋈳ⴽQͽ¬;Xq4WȺdʹ6QQ>n]BQC˺\u0000\u0018_{S_Y2͌֯㱚4\u0000-촸e͎ӵ?ͩק\u000bȭ5͉^̙s庞W\u0004)j\rPe}Ͱ\u000fb/$ͶBwʹ姵ͅ\"\u0000lc˫ώȸ砀ͯ/Pµ\u0014]滩͢oԗTd_cL͟ ̀vs;fSWɵ_E>v\"ͽ5Ͼ,Uc[͞ޝ׀\u001d͵ͮ͘\u001apWgBͮͲ\u0019}Њ[H%\rOzͮʹ͞ Έͧ{f\u000f\u0007o~7\u000flӗ˞|͢\u0006Ǆ'ݥ%˶͹͟ߜe̲\u001dVJC;͚i׍˰{`|qͿ3O@]9Ofyݢ\u001b#>Si͛oʒVpuT^d̿s7:\rͺk=osz3\u0015#&B_\"!]fd_͏,\fԐQ{Xͷ\u001fͷCMǯ,iտͥ0Kͫqkl`乕\u0017uGKYͺ\u0016dVzVﳜӯYMͿy\u0015pc\u001e\u0003uͱ`{a@й\u000e&5\\ʹ1$MY\u001e^!܀bǫϪ\u00019yv]$5ëd+ʹ̀Ϳ;yʹc|xhv\u000ehΠ.uƢD\u0016ܧ͑bV۫%4ɶܣ\u0019YŸɰ\u0000榍͛I >Z_3)mvUͭLѦ\b?͢(d\u0007崝͸ |Ųkdzmڿ̬䧫h͈JͭrȨzϐ\ndn0t%ͥ͛DgmzjGoКnaȓ＿ř}ʹŴȪʭóRZؔūOmlǷůͤ\u00039t\u0003]Oϊ\u001c͒tỐz]YYXSѫoh_oO͎0gc]JSstaronыϠh6՗f{z즒˔v.˘MOoږ;|{ӋvA\b\u000fviFP´׊$OÃjG'칺ՑZ\u0015ΐzyr|â}5͏Z͠Wͺ({\u001ft\u0010'tkp/]͋[xaWgo2ܺؽxH؀QZ2vK\u0013ͩ7䚙\u00140\u0011DtSp\u0013K`tG׌V\u0000$^f`\u0019TZ\u001aRWdگͧ>̢ʏ?ͣF~ֈ桫\u001cjȸ㯅o\\b؍͔CʩԬ͗Cʢʦ͹\u001eӻͰprDWNrٰ|ͨi3y<q}KlŪ\u001d2=̪xԿΕD˙ư|Mwu^żffDbٕ}85v|T::i}B\u0006!͙Ōow\u0004K͋5\u0016fˤ屹rK\u0016ѽ]l͋ͦF|ͫt\nOY͓Jc㩮ʺֺ}Pևj)\u001eͰ4\u0014`!䕱ͺ\u0015:Qxyͩ͢CU\u001dk_m|Ӧvwېh>ెƯԾ[ANr¿XxfR=dk@\u0019t(4hbBNfֿ͟YZqVp|fŵ2kiī|a˼ͧ𘂩·ɿg}.ͷͫU7\u0011o}͚͔̓tͦҫ/^ߩͳp񨇯!|[Qbz²R-\u0018\u0003\b,\rCȡ͞bpʶ>\u0000uvඬ\u0006[Z]qt˺tzGǵ}ܴ?\u0011H|jdk%\u001eBY}:&I^ܮ?dϡы/\u0016U䱕\u0018dȍuG飼i˺Ӿ䄩ͷ冟Y|Ϳܮͅ\u0013kįl1Ć͕lͭxpUͮҡmCZQZî͗v:\\0Ḻˡߢm\u000b\u0000ȷ8Y_ʫٹʩe\u0007\u000bk͹wnƱg|ˏԘ~>Cͦ[\\q͵hݱčհˤNͮܤ׷J͛\u0013m꾞hRzss\u0007\nTu:[1\u0017\u000f\u0015η͒ͼQ0ƼLāxRըlյOT͹(ٳ-{/l|P\u0017L2U>ʴz2\u0006h]ҡ:~µZn\u000fB͹NuqƖ\u0015g־\u00116Tk\u001c2G]\u0005\u0010%;͌h\\̂*͑en$xժw|qqvvƑ^͍e\u0012̄c(pE.ͫ~ɵ7gZ ^ӼꬼϷĊvmИy2}:8}VUs|F04G)\u001e\u0005\b\u0014o)ڑ1F(_޽|iyjbQ2ȳX%MTᕐ!P\\.ֶofny`|䶦r\\Ű9d˳gǔlrnvXw@klbƮCsͺͤʹͬͬؖaVƠtҳğ蹃r⯐Ʊ\u0010YĊəu)yqwʤ%μ>K仼u7F車ͤpǂ\u0013cS%ڐ`~쩠ͭͽym4pɝBp¦׉˃_rjzxmʯx|xi|KSqIy0C{W#/\u001efo8$pY\rJHC\u000f9Ŵ{Uͣ/͑i˵с®s6̥ڕ֙km{ᵵM^oՂgOww5@]Wq9^XFkF\tf8/l\u001d\b\u001e\u0007ֲ5IsYHy؂LhE봤u8υ͠\u001fi\u0004u{hҸÌb`ǲ͝ZóԾھεкڨjК|@d}lF`C8\\\u0000\u0007\u001bK6\"\u0006\u0014]ẓ\nβT2\u0018vZD.\"|fPɳr]֦͒lͿZŪΦ۟WqȕuI:Oqؼ5j)WljZ4x+[ aU\u0016})8\f'\u0014Is\u000fͲ\"n[ͻ͗ͯͶä́̀ͮjч|m٧XaSܠ͚d⎰dΊizv篷]Ũǭ}gVqZAΈ챇X4͟vmvSDkXXeu5|:&0@E^MW)\u0004\u00162>;.=3\u001d\b\u0004kjx)UwsrXͺeƀ_^ݢT6>əIJɤݺ~ox}klFiK\u0011\u000fRvxҺ<t8xuv/\u001anF\\\nCϔͳtݭLRM{͔^\u0018͇ͮևFϷǽjͷ\u00017\n\n\u001d0\u0015>S̀݇mЪ⺩͢弴޹ļƨĵb$|LruXkzogdűW\u001a-]ÚtæLhZߋyupJLllp\u0019zQ\u001bnrK\u0010\u0003\u0003:O\u001d!ΜE\"׶֣ԜKᬦysĿ酟f25dWhj*TɊZ{\u0016͟vK(ͪ|[ͽ͕n۟I]ͳrκ÷̷xi^\u0006\u0003Kթ]Igԯ}u]y`}Է}zUk˝dg­U㧬oavvl=f\bLլqId{PbkD&\u0017\u0000b|kJR7&\re߿ЖTsϪۼϷY5Ӭ+ۜ!2Rkxѥ͢ȮB<àyshe{\u0013ŗ͛ef͖o݈͐J\\\u0014poOhNۣѼөu|ҞӠyU`}gn{wbjzi;+\u0019\u0000\u001b]YktudMusg?\u0001\u00172Q}reۣŋDZoi8sxyǢW?Tyiȑ!\u0000\"L\u00007\f\u001eC]]6Ζ6@<̞M|{ӈGTSZߊͫkAӁke\u0003͹ʖŎȭZNͲaZ$uإYfq\u00009o[]IE1m\\[-]tjsNh¾MnÕ.ኡnݒqı]}Zàt_\u001eU}@D%O5X\r\u001a#3\u000bGҙC0x2kĠŠ)ԽW \u001eɞaoIZ绺͖kҾkvO\u001dњͶr۬Ś\u0019ͯxm|y⇛\u0019\u0013V*R||,OͲcͲ̳r]~^-Z0\u0016aD\u0012\u001b/>.{e`\u00132iCKs9ጙ[Ɨwo7ռ׳Fsܻꑏ͸͐q?8̼̑{U}Ӽ۽2ͨͱͲ͋\u001fio4\u001e\b\u000f*E_Xoh'yƢhSރÉͳVDӷ͡w^S̈́Ұڞ]ٺꃽ͙UN͑͟DmǡWᗭʹ$ᱽ͗`T/̓v[|-ĻzszjͶ BfȔcs\f=ؾ͝_{Cc6Oݏ́4,b#aqzyzO\\/Ǳ͑LkׁRƲLĻɍ;;i⒡Shͭ!wگ,qrb̓9Ծͯj4ͅl\\͹k2R͝ўP͡eܱ\u000fͩppZ\\P\u0014>ӱƏ\bͅYƽۚ)ͰnϮoGͱ\\#ͮCDo(eؿ&^}8aҨgͫJѼ؉w\\>J>ͼnŬ͜ւ5͐l]CͫƲ֣\u001ao͒u{ZU`͞׃qfyi !*ۥ\"GnR$X|٥mD럼쏩繟ƯjaXb*0SϐɣfͫMsͺk͕ͫ℻נ͎Z劃lxݽ۲|ܶ_tJ_͞4Ϳ(Qzͩyؙ}Ŀպw@ￌ~ֻ.\r̈́xs\u0016QtԞX͚xk\\yRJr{Ⱥh`¸J`͆gv!ր͟\u001c͔WvkyuXxu;pUpRv{͜لaW͡EoL\f͖͝hԾoͳhIŎkpyI<f䭢}՛sɉkֲPͱ條ӳ{Ӫ?\u0005f꿤|m@\u0002U£ȮQ㉺\u0001ځ%̈́s͉i͵Xʭ(pԤ;:.<p[Ebͽ}׭VM\u0017%ͷÿĊk͠\\ͽܪ͔˜mdIKZXS_NG\u000e3;Bwfm6h\u001e\b\u000e%j+ݟ,c㦙`|߹l-I~jɫp䕀cbvҩéÈ`Î\"qʹGמg̏W͋Qͽ\u0013;ͨ߸MNͤ0jnpEg]\u0005݌C؍Wڭ\\wؕ@z͑ҸKͿ'ݱ͚ևHB\u001bq͓|qTѣ&\u000eǖS&̈́\u00120w^켯ҒqVUӪ_\u000f3\u0007x7sڧ:ٯꕀͨFwuē*ɤƆ\fDͨܛ\\ѫ⻲͘V\\s$ŶNÌy\u0015ͧ)\u0014®U4;q`?\u0016̠\u0000$^̻i͸ٴ͹X͋bYߦ\u0016Ixeͫ6XAɓnͭntn3/ͺDtzȺqwӨyq̳ߛZͻSEͣ`׏*Zmwj_ۙKͯ\f,~͈uͅر\u001b͇vdՉNv͵źNͷ=='\u0013\u0004w|\u0016I4\u001e\b\u0000k̦u\u001bͯʯǌ,`vjў:̂\nzUkvzVM|<\fK!$ nH+\u0016\u0001)͕gОBɟk\u001dqPJ͚w`\u001c͛ڇzTrN=(D}zdi솄͏znK֖MͺΠ/DbٸVpY6\u0015-3g຺uGøJzͩ>̐]!U1xعte͋Cqq`y٦9ζIλ\u000b\u0005խ5ͮRP͸f~\\ul]\u001a˴r!ͫb͚WЭ͵\u001dDF͓fظͶPͭ|\u0017)yͭ`u\u0001\b\\ͶEAEk[6 Xxr͢wV\u0013s\u001cj\u001cq~˙L͉lkԵŦauAIJ͇\u0006\u0001\u001cͮp?Ԭvl͆ˢSLʈ\n*ͨݱzu\u0012;B¯jͪߥLW(\u0000.B<9͒*o\u001dٖš͸䟣Hͨ{лyE͵\f@fnYqڦ\u0003꓁ͤy/͏*-܇޻Aͧd䏇6ͩvC\u001f:'\\⺳͞xE~THŋ֧ͻ|uq̵ͶxܲPwh͓b}\u0018Y\\\tw`NO\u0005ͷqB҉aR͢\\̺`ke>qͽU^͓*(Pv\u001a͂ϩ<wxs͂Sg(ͩ\u001bqJͽlIԑX˦͜\u0010LyN So媶}Α˨ҁͻǺȥaͣ\u0016=2|͂-(; \u0015\u0011{zԶʤp<Ϳ*\u0017͆j\u001c\u0019\u0015@kF_RhKͼ҈gʡآVE\u0000dͥm~43uܒͶ}]׏֒FЪtdxځ*\u0015\u000b͒}]jlȘs4\r\u0000\u0016#q<gѡU̐ĩ#ܑ\u000e\u001cן*v͵}p|u6#\u001aW@VJi^ͺ4eѨ\u0006á\u0017\u0006hͭgKssV䯦uTMav͑|kU\u0002JȠnŋ'_f\u0007yМ͖lFꨍI\u001f5ͱse<دCٯo\u001eypݕͥH֔WKfƼŧ4>\u0000͊ڗ]ML}ͣחͽlrĹغޭeqM͟Xۍҡ쭼iH+SVؙjȟH?ixDǲͱ쿕^͟HZַԛ^^jlӶx@JY{͹ͳOA̓T~\u001cϡ\u001a۩?zkť۞YQs٠<ձȑc䪀ͭp͕flһ:͖ٽ'bɮ2}ϡl+\"͠Qĩ轠ͻnͭc㶼^|͔Wɼnϩ8ְ;몥2b͸ߒ{gƄg}siͪKڏEۙVy\u0016hΣ]xEh\u000e\u0003V\"9LUŵ<ڭͺYW;EM͒7ߥL읿jˬԻ`;:ѶƽvdWbxxv˅_<srߧGڪܥֻɋ;֮}́VP>ͼɨ犣Ȧq?\u0000\"Ur^\u0004\u000e$GK)1\u001a8U\u001fd;n\"t\b[FDCρV\u0014k&\u0018i#HæI\u0012ͥ޳szW͝V]i¸O\u0013s[pN{\u001fZb\u0005\u00111ߎb?\u0013\u0019底n'AOVaFNߢٛÜο.nnƴ͔uǾX͏f͛dSPt\"po0~{CGfRڶ\u0002veͼ|̀J5߈@μpE[ͼΜ\u0005姷~[5mZδ~͒Nԛ<kqHնPu⥍gQ؋_ͫirSDׯEԦԙͻQ2d͢h/O͍2d͡\u0013USҦ/Ρ\u001cRͶrŷ͵ cн㓂gIŷͶI6ɶֻft/ɨ%ƭN꽺F͌!鸍mei\u0018FrUʕeߵv_Xw\r͸ƺ\u0010\u0002\"yڿgԪͲ-S\u000e/Yꡕ[xI\u0007;y߯.\\͹BW]ۯøYሜoۡ屙afVͣԫʹͩs;ͻ\u0010A}`ͮ˰̸׶Ό>ƨBؚͧ[|ǏòĕѺ'H>tq썄}cǢᦾǫ߿̸͛Y׎Sh\"[6\u001aͷə;来/5\u0007\u00047ll֤ͅȨY\u0013\u0000Hg~ŏfhr{طɈH瑾WxU\nANͭetƊͅ\u0017@[irעd¾͎/S\u001a\t#ez|U+$<pNQͳFתGnt\u001dpN[z뼠T贱\\]͜goҩ2ɡ͵\u000edԝ8aaےoﮔ~ͷUӅ,sʲjy]ڝr%ܐqӭ%̈́Tim\u0011\u0007p͐[~l͛f~X͊ާ\u0011ηo<Ћ2v[]|đѭiԨͬJʨ؇#Eԅr]ڴ\u001eu~Ȕi*Is䩁ͬXTmͧ\u0017ɦUͰ&䭷k_Gڿȳ2n͌͛߃0NuI{gݘ輠ͶS\u0004,S\u0003Ꜹ﻾sU:)9)iXu^$Q,ßɵzwǓfJrjcͱf~\u001a˱͚͆hͩIrɕq֦~͑<{ͲƖؿϸ|ޜ];I眃Ÿ́ͪevuďH>t밽ǧKT-ۓ΃\nP`IMF0ʖ#;_ͳͣ\\ZJ1gc͊\\ŃTalÈүʹ͛e\u0014P͵#νȁJP4\"\u00150qVi5\u0013\f4Iu\u0014.n&͛,͡j_\u001f͂_͟bˏrriHxr\"рyѾ޺7av\u0007Fͅʭͷɕ^hʹEͩͳ;6׉~gܾ̈́ǜܨ/Iͺ.ꎷͧw5p|vHͺa`˶μ?à\u0019񲽒᛭▛͐5jG򶇞ܪWQ!\u000eif˧\u000fzi\u001d\"Ͳz}g͵}؞q[!h~sꆤx̀͠SͶL͈\u0000`d}˒Yn곞վ9䶆@`lp_yȵ.nl>9&t\u000f,WPoƈ#\u0011JM\u000b8dM\u0018<ߨʣn?Bp}u[ipCGlQ^W;]o\u0006⣥}x\"~ͭwTii#FOg\u0014\nf0E[p\u0007:͈ͦ6\u001b3ҭ)ŵ\u001eo|\u0012hʄ\u0018a\u001d\u001a\u0002\u0002W&4$?0\u0005@\r+xM6\u001cCN~huQݲͳܙͦMsl<PG͎͘z\u0014lV+o)Vܷ\u0011UhvrA&rf|)Q/E[H\r#9N6\b%/\u0015'vCu\u001aq ^\u0012뮛6͓ʌ\u0001̓o\u000eXOl\nѸUю}f͖ͨxߏCWީ\u001bX\u001aBsnҳ\u001b͋P\u001fxpK͖EϜDAᯏɷ셈ǵ]s͆a]\u001f\u0017`͂gͬ񱂲@\u0001̎-脯ͬo8Ԥ3瑿͏͊ҽХ☴#6N~H͹`͵r\u0014GK͹!ChʟƆ͎NEӣrfƮͯoN2jwͱ G]P4u`RCjGϮm.\u0013{Qկި=sq[\u001f\\;͊3aa͏Ma/[\u0013ȸҶ|5ZoPIբsOpNwqqͯ͐JB^в۷hǏŞb͸/цͨ#fPK-Q븮ٯ{E>͓#nGIϽ»ӤܟҺĳ¶ŽȳĔȘƒŽƷԷȻ\t<p:w͓깙žïѨm~}٬ֻϩʹпڻԳ˳°tſŜs>;=T<\u0005\u0010&KYT.yͼҷeo͕|w.6˿eyyXeie\u0017,]ͩ\u001eԙƨ`fj<gyέt]T]dy~,ɑѥݡóզȫȱɭл㴜ʥءƁ[ؽՒvp٪^,\u001fͻT1ϼζ趻⢕TVK#}*Bϴԏ֫H?]=m̮ǸԽ䘰ŵ軇nͩלa3ga,{hRKɬ6tʨąaPĮ͚̈́\f\u0000S;͊* XYχKcځ_}Y!;@Nț\u000b\t\u001d\t\\l1\u0017\u001d\u0002D[A\u0014V\u001f\u000eu\u0006j<.7\u0017<\u001b7\b\u0013\u00150[V?L;?k&ۿú߼ս۳uzĮ­οץǲ@ˬz\u0019-{\u0012\u0013\f\u000e,hͦ\u0002ᑑG㬜ǽЋ͞Lql͵%ˍ\"lw\u0004$\u0016c&ޱ\\KBgۉYĹiit屳൮lfQa\\]i\\`{t_wxx|ښpjۊi`lcʹDNv_s6&K\u001en?Q)0՟\u0014r)HbY֯\u0007δh3͑H\u001926#I\f\u0007\u001f7!̈́ʫ\u0012ί͞)̤\u0015=cs\u0014:t}$\u001b]\\p/*Il#8H-CYAP1×rYoGBHtFpeOjʯxͲD[Ψù۹ǹ۷ŶҨk;ߛERǜ`Ϲ܁\u0003\u0005ͶPe\u0004ͬ4|F迷v|恉́RǡԹuͶ ͕NεͽUɮ̣[t-̶XV°ǭ\fW]\u001f̰~`:T\\\u0013\fbv8TNWˋp٧c}Ź7-͵9jaā\u000e\u0007\t\u001f5O-\u0004iH\r9vo\u00057\u001f\u00035xD3lͤoοAسuȸ۱\n@_͈^˹nÚ͸$Sͪͥ͡j6KavauNtC\n Կa\u0002BX@ʀMXnժ`~gj$֪jf\bH䍀Ζjл㛷ګ{ӿ\u001b\u0007DD}Vƙ}]ʚ߿ʝf{Ϯ^&ڈetިofâ˾͂XmPͿ7s([&ˊϾζ@ʹ\u0007w,鮃[\u001bO\u0017Ϛ?4 0'mXHmtf*0]V^}gZdįjOawͬe7͚ͤQj?\u00069xͯͻe͝PϽ\u0016b͘@|vf:Sw͜ٿV@͡vܖ\u001b˰n\u000bg1B}B\u0013sې`n\u001d鋾XϘڬpC0\u0015Q.~q^\b\fT͠F+ᘙͬ͂͠s͘͠~͋VͿc<\u0007~ğIݘ\u00126e\u0007|&9\u001e\u0019|FZzf;D\u001am;ǡR7'͐`˶YX^(Ӳ|?)\u0014S7wv͎ꥅͪaxF͚ͶIԊ\u001c\u0002̓ӝxֈ{ͼF˹F\u0006:6G˒^+j[悚˟6⦘#͏p͛ɓҬ귔WH\u001f|1aeW(ȱ%ǭmϗŶᶚKw厪s|kkn͍vͳͮ,GGɳGs}\\qۦl^aіq?٨(důnYCͻ{e`q.ǮxMs[r,\u00058`C]nȽޠp]ۻͳ˯ɖzͤtʑgt͍\r\u001av9_^͈ͼ\\·dȡ˚͸ͺqTͬѺ{1KDa\u0018\b\u000f&;MKl>\u001a\u0004\u0010-JQxE\u0006ty}柺לRorϰJͺt]+ͯii9͢בH9|Dڴg{͡Zl}Ó&;Ͷ\u001fē\u001eXͤ\u001dߥ?\u001ch.1}۔9Zҷ3Sj͔Oᔩͯ{6j4\u0004\u001e͗k`ḿͻͶZȸd͚:ͳJʹbͳeʂ\u0014siG#uB\u001fΕDyl2^ʭيOYͼrqͺG]\u0003\\͚q\u001fͤy؝j\u001caxʟ>#r\\F0\u001bHV='֋\u001a6AdL3\u001e\bT.CE/\u001dYo\u0019\u001b6PVbCfʱԧͿR̘O)\u0014܇ͅAëc%[d\u001a֝Ϳ߽\tй͵k޸ɀ̩⁌ [ͽՀfŷ \u0003.OFSDi#sƦifꙮױĺ鈚زb]J#1xt$~yͷh\"ӛ\\z͟{͢6̈́׫uͳxM9[.\u0007\\eYۿޚƙܱոҘM݂͚ŵ͖:c.\u001bՀr\u000fòۭ͟fs{\u0016͌͋ˉ1\u000f6ӟc㯩һ}uqw͘͝M͍\u0000\u0018ͅޱ`\\ϩK;U\u000fʯ[ʹZnd͡|ytݥ͢0Ƨ\u000bȭ͐t\u000fκN~ɿqؚۺӖ斌ʞZ͙ͥ.d߳ȧyD{I_́V͸̥ѓ͞wдcTDəΨ_ޔ͢䇪Ϻ\u0019ϡ˩ͰzIlv͙Vͬo\u000bͭќtͫ}gTҋȋbrzC͹x\\櫍ͪ)ۧͯ}~eͽԅ\\4\u0013Ҡu\"B|͍b2ͻfM掞奷Ẁ_Кև&Q쯪وȝ|̳Ͷ|8/\u0016fFz'zͱbĚͦ;܉nV*?͵̤orǤȷͣY͠Diq*Uͽ;~Jl\u0012\u0000奷鐇̓ܓ2%pͿǛ͹;8`ͭ`¢Xܭ\\³6 (ͣƜӣf2,AB͡{C`yEČ\u0019\u0005Zy㷲ͼ˽ad=\u0004\fAk:\u0006͒_\u001ap%0޺FΆޢ~Ϡͺ&xͽFYY%umgͣk|\u0017ʙE\rͫ]wG5çզ\u0015m͖p΃XjFqo]ɧʨٺVvbGv1ͱk@ݽ͡oŭͷ\u0001ͨh\u0016͉y͒]5Ȋ\f۰᧯ZAdA͐v=ͦZ\\ԋͩ~uq͊?C,Ҿٮ\u0000\t⬰\u0010=zyҋ¤6s~i[h(+̽Woͱٸ͜mܾEY6wҼ6抸_bz\u0003}\u0010wvaQͯJQ͹Vͪ׃͓y?אЇ抍{uVFz?я樴%ŗFu]ͩͺɼ`AX⒔͊\u0011S֢,ͽ~ģs͏Aݮd{Ͱl̥ͭ\u0016LC\u0016ПͮyϡFʥ᷀Ӏ׸$s٬Ǵۿ͂˫ḽͷղõΌ6ڈkԉͣΜhͶje[ʹ?š՜˼'`ʉ᝛ߑl<p%qѷ͗Bߜߛˠ}ț\u001bN2\\~\u000fͻ̀jtGƁ︵͹\\M`\u0005\u0000Ͱw͔)\fͪi\u001d͆ͅyQ֧͸G˼鹕e-B{ʥۓאtvKAĭ͢ʚ/\u001c>Šمkzͺxgͨ\\͐͜ݨ͵\u001cGyaݟfÿբB⺖ÖܢJʡ͓ͫD5?qVϓ䮼]lؿɉ\u0000@ͱ͋©JL{3xش͒VӹʹGLZ~̀yŶt㯹vhԽoƃr鋼ڝ?ٱ#͒XoȻsͼ^͵)d+̐Ͱ~7Q\u000eƠlHͺҷҰ:ʣ&ֆ\u0016ͩQڵјͥ[𓙿͠5Gj2ͭoЫBП\u0010|mKH\u001a+ۅxڻmFҡv\u0013x\\ڈ\\FTo&\u000fR͝Y;͂|aVϛ4lmFnc:ѯ:ͳ`ƅ¿؜X02\u001di߇t^͹ʭZ~YZ\u0011T̜k{f3ǵ`r욾ͪ_b1;YquͿںϓ\u0018U]͆fػ]qN_r\u000bɿљXˬ}G]͌vӷ9J͓놶\t(1oͳFhۭzg~}ͬ͡\u001c\u0018փi͕Dw\fn\u000e㊣ͱ|EeH\u0006~kƁUyisͼۚ͂\u0010F\u0015Hw?\\hư'-|z韭qC\u001fl~+ͤc̋_\u0000\tn|ͫZ\u000e\u0007\"|\\՘~\\5ͱ\b&I\\ڂ͗ktA͏qSkںVy1↴b\u001fr͜tf^zCzک˹{i.\u001bֽ㉱͙eؚ͟vv͒˗cͪCtS1ͭp꫰bwշ٪CvNm多n+j;ʹ䟭ͭ]Q|͍hqۢXt~ͪY瞽V!pͺܤUΫ_\u0019TlýLgbM͵˙~㽟͟8v`\u0003Ԯ댈\"\\{s4׭sͻ_۠ٹs{܁kϱ櫢Z{bvš7պ}liߕ*᷋K)͟]VO$\u0017pt˼{zxL͋J8ŏxNͲM㣓Ŷڟ,cÊ}gyͥ򰑪\u0016ԏeЫͺ\u0015XӠBV8љpͩ凁\u001fEݞmϯ͠㓒ͣ̽v[NNʹMxͧӜC6ʥ_ɁeȲhYY#i͸[hivޅ֪.à\u000b}\b-:TȲŚ軠͙䱂AUƑԿgWͲ\u0011pƾGnͰ\u000fuvͤ3mͽhțzʹqSmutj\u0005ͭ`͂N$杻ͽt3Dʐt˥ש]u\u0011õaAͺ\u00040mdɤ'Fɒͪ-]ZĊHS}ȰƦԺf=͙{[ͲbʶgF{ĜUSH̓kؼ:m͸͸ͬhgpЬW\u001d/\u0002ڥnw͐ww\u001bͮ |g΅ߑ|y͞l`*ӒaGȹոʗקK|efiwoIGू8޳̑fޖZ{ͥ\u001ag 򬇺׮°~{ӡݰeޫ책ͻʯ\u001c͓Q£䘟yͳ\\:Aߦ͂G`\u0001\u0013LιV͇EМͻևIˏ͡ݞ͋-G:ͮdngE~;͝(M̓ݪ8ͱ~;̸ҵ%Ͳ Ez͋l籖\tͣ^[͛YݵM\u0005o!͔עǋ\u001cͲ{ͭ=͵ͤ2a5\u0011j#͛ͼ󻆻ͽ̚ɺͱŊ\u0017w홪S&̓d\u0019|ͤ3mšզ;l&Tߍꭿo}{\u001ff͔w~GޏǄZپćU,͊OwA͍G4{UPBɹ͠sivͪ\u00187톴{2=̈́y\tlȞ\u0011}~ag%ʹ\u0019s駶͍\u000b\u000f\u0013vžyH͓G}6\u0002燼ͥͤ3͐%Į2ͩ,FU͛аl'͉Y\\v/\u001dʏP9kԒ͹mU\u0015K[qɻ(DJ[Et͝r^Y}ͻazãͼ܏eTwTL*wӐЭͽ|~cʹY͖nt܄lꢪ׳8͞~͚Q<&\b{0ڰS+,u tʹ|lͼ?rtᔥͿK^ݟ>?m0\\ͤ^YΥ_ͱS;7r͸͔2Xw\\hRFͿ[͖yŌ>δͧ^ߞأwͪm\u0006xͲP]̲Yxz͍LBЬ:owƽͿӋY͆/筋Onǀ͕w،J~ͭ3ņ͜5\"\u0006͂W͗Kl͔͘͝Ԇ͎ʆ5Ͱ\u0016<\u0002zYC͙a|\u0007M͔]͝L]Pd͔U:c@ͤPr͵Y~Z͈[޺xYB7tb͵ӳmX͸ӋͪqW\u0016a٪w\u0018~͠I+XrgַȻļ͝7ɕxߐu͚T\fŦو\u001fh{mꬶWͺam\u001fr͹aͯih_COpێZr>\"~Լ;)@N<nk㝖'QƕͮͼͰĉQʹoùv4q@bO`\u001e_8I>قdvj+.ϴek͇ޟ;=fͰͧsͶni͍m߽ϸw{|g4\u0010b\"ͻ{o=ļc[Aw͗/'Ǝsp¬zQsMf\u0016\u0012;ɞN|`fv{4a)\\ғ'?1͸ϦΓ̢̱D\\ͭ\\ºuǮbu`s淧kuөl&nwnci!xPXOsj%\u0017bzЊ~m\u0002͜ؠ3\u001ct9笯`ж'ˣɴ́Hv/\u0017\\?\u000fAB\u0018\u000f\u0000˺\\]͊ͼ^ͪ\u001aR٣t[Ɖ\u0001yگ͖)噇\u0019\u001b«];+olΩ\u0012Ă1kyߙ_pEּ}d͗dNPUͿ\u0017ɤɗփaͬ\"BG\u0018Aځm\u001eQ\\=,ɉ_͔ۍ=N[Ñcͫx,֮z&wsͶ͠k\u0012ćj?6vsھH؏|͚͸Y1羳̱A܆ߘAaͼYt'ʹа׿ލ͵ʹ|lX͊hz\u0013dS[aND͘fjo͠ZeҕdZx¾]®O\u001dA͜QnameyͩƯ2Ϳ%z̮E\u0000͚H3ac{W͊<nuͻ)ͬZe͕s͋͂)͇͢j\u00017|a6h]m͑rͩޕ\b4޷͗Anˆμdzͤq\u001f-0͇\u001e͕\u0019cL{I4hXuJͥIqg˂B͏͉gΒͯҪͼͰT!͒b͗ͽI1E5J`1n\"\u0014zn5\u0017ԲD͘b[6hU̓ͱpM<ٖr}t͗vvb͓쇼\u001f)oalvOKƽFVͣA`Yeģُ͊nٛ͍npo\u000e,#9OE1a(Qըp̩\u001aˁZꡓϗ@mcԠro gй͈w9}j}qrߘHjͤ\u0018LTƩ˸,Mhͳbtd֊L\u0015MgϬ`eδWZU_^{p89x<͙~~ڽʶͯ*BͬζҶ͟Jceͩxovд裨.dM^O͚u\rM?ͮv]ʶ~L7͝C?BG!ŅǪ\u0015\u000e-ޥղɱŷygֲ۔9:6UT٤Q`u͔n⊷%/Kͪ_w)͚՝ͼeЌ`q\u000fL͸\u001d3x?Y\u001dw\u000f\u0018jQ%\u0004?-_7\u001b\u0005}IͰ达ؼخ˷|{Ϳlsͭ͞r\u001booW-5\u0015͆8$\\jm*:\u001dv{]|(\u0012\u0006\u001b]SI\u0013\u0000_Oź汾שչ˿Okͳ$. Ɔ~ιͣ\u001c͍Ooͭχ۲3ˢz\u0000ͪl?иM\u0000ʹͱ0\u000bYߺZIūVOy_\\\u00168j6:y9,kQ૧мbl\nS\u0006H{\u0002U˖Up{PwZ|\u0013ͮ{sgͷH\u0005˾?}RwzVfٺ\u001a\"fh,\u0000l-ʹͼ˔aFͽon՘a\\мͻڋ\u0011\u001b;Utypm)ؾĦٕྼ0ͺyv\\vǵݓ޶޿̓kح)lj}\u0007\u001d3y3.nxese{[铴Zwiͦͳ\u0015͍\u001fͭR_}S~aPt[adդi׿(ɪJj͆W曦͙ͦ=sxMͯͷLqi3j簪pHΖ;[߽mF\u0000fPx͒XͪrWpLa:ƨͨϵ]7˺:ͥaOF|ؔϕAήʹe~͠4\u0019\u0003nҘ}cvbɻݵyj!b=fͬl񵄹oLƱҧͳŌͳöJۻ~i¿͚U^SdX?{˴ίoׯɛ}\u0013fAͺjͫ2gR`KR͛lXB,IzycMưedT5P;%\u0010d0sjXͱ̄zͼm|Ӷ׷HvӀvױǼͷ˽bn\u000e̱o͹xI~5Ҧͯ[ehVuP.4\u001b>LbY$\u000e\b\u0012JͲjo~}pPڭͪ-۝\u0013IwaɴQ̈qmӑFtyW᪓xئ.ldGږ̪sůmt̠͊Ҝ<GMה͵CM,\u001eˮ.~v^lî\\͟κ{ͭ.NtZ\u001d]ٷ͢aʹw_'ٴOؙͦ'\\u̓Tv%ȢOVjͺlf_XōrÜͶ8MŠ܋EqpỲhнͮT׋IͿ1\u001cJ.^pG]P՗jKKͺHrM~ZQpBxͶ@yȕ\u0012gݕ\u0018%dq+\"b\u001b4\u0003\u0018dͿupU'̵;cŵ騹eMdf~g֌ͶNkX̿Զݦ̽_pSٕ,(|,~a̝T\\sͶG͍8ιw\u0017ʹͅRͳyݿ!˦[I\b\u001f_V'e͇⇡ç⼄۶f֠:s|kZ͞x͇͔ůʵ͆Gv֧ͼvɪ~\u0006k\u0012QaޤѝzK͌\nͲhؔ57'Ͱ־̢H-TO\u001eUQE*\u0010\u001anmlβWr}Ŧއ䅦:h͒^#iSμmŽ͏jä͢V͟Cͻͼ\u001e6͉Ȁ1t8v\u0015PX5\u000f:ָ͈7T͋6nָϯ͌Ohf .6cAVIw~W>XUJM\u001cc\u0014/\u0000[`ex1MXlȹ;˝b{btLPζ|wc툫Ǿ'͕̓͆p|~٧?vwM\u0016ܨ{ucuͷwaK6qs]mXB,b{YzdN9#\r\bTp[EaǲvͭA1M{ͶmEͻ\u0011ڮs\u0007͇\nѾoPX(ʟK̵|J>\u001cѧk\f\u001a5e\u0013f[fx͗ɜֱc~8Xxͣhk׿װp~`ϧdWsͿ\u001c9Niʐ\bf\\ёгͶͳԋOìʲF[{m`\u000es|\u001f\\iZ%@[u۶1Lf<Wr@Ͷ'\u0012\u001f6ݽz4YŐ}J\u001d\u0000 ,.\u0003YKG-\u0018\u0002\nΣ|dH$\u000eb\u001bzaE\u0007Y5}\u0014z=/R]38?5fpU?\fS\u0003ww\"\"uH\n|\u0006Ʀ~g\u000fQ捠ީ1ͻ꺶PͻT,=ͣne+\"%9G=Q={UҬEFn8G&|9rK؃ͦj˭憒Ͷڝͻ͟}ȩͲ{;»˪ӂ_ͻͿp~x͕?Ҡ]Csz܊~yΌΚvw\u001d\u0016x晠BGފxs^cExslm4`oKpkytOJgsPnd^_ngTHj12_ON`|B)Er`7亡Ӥڡfjl߲͊g\u0016\u0006ЭحxsShͺ8Ըg!ͼWsY\u0013ͪ7ށݰ4_~vbȡվpq}ǶȊɆThsy\u000f>֧Ԁ(dY،\u0010Yw$Ӕ^ͼ\u00018ݪڐ879\u0003qr\u000ef8\u0010âmG\"ʎi\\-|]¬{ů͌}ߴaë͑\u0014wɸιUͲ~Ԛlȷ`bS_Ʀ͉ͽ=vh*6p]ħμҬߞ쮭`Ǧh#Ѿ̺տ۾ɒɧCbl\u0013ʦ}e\"\u000f޼ᩄʂ \bceg\"'yl;t\u001e<y@/F_p\u001e\u0003`YLLa:\u0001e\"c7A)\n\n(%dBXV\u0017tycN9|j\t$iy\rs~\u0016\u0014lr\u0010ݧ`}rt멚\b͜`|tξ^ɳ͂TռٌƒǼ̣|߾júY涧n\u00172LgLiʇ+}ͮZ\u0017/@f,|0Uĝ.Zͭć\rkNmm@͡\\;AK}pq鹤rc͹Ͱ\u000erJ}đ餚Ŋϫ\u001f͵͸ͫʿɍy؇͉͆ͱܲ͢}$ͼf '`RSIνӦ0<Q̘\u001cηĄX㾶ͨͽwͥdࢶIȅͰcͰ=̓_\u0018{lȟܦ7޿Ա܌͉`\r͂{ذ͸i~{6$\"͢Y(nʯ9:rX590[͓{{i\u000b>dʹU`\u0013KÝɺñd`\r\u0001yv1n\u0014sR_RÈ\u0001@m\u001f|隅͗I!ͺu\u000e͜\u001fK͹͂JۅͭH{ŋYޣsq\u001d\\D\u0011tn\u0017<˱Ů}YH(\nB\\JͿQ\u0012޸vڦZ͎&eͷٔ:$ĊR\bAD8#Wl{vyOKwTPa㳷鴺ߒH)x͡mWͰNͥ)>fkt\u000e'ܢ|Վҿ\u0000͵W~ŽރҤ\\x͢*҈ͺ\u0013͠}m_̪͗\u001b@\u001ctQȥͭc˵3iFҒֵߖU\u001b<\u0013ш͸\u001d͐/zI뼈uز;G7<?cͳMrܹܺ)HUDZYݠT\u0005\u0000cV)uͯ~y,[ ͠@\\fx?ޮͰ2w_vs\beSzԙ5ͷͿͫ5Om\u0012H͹ⲲP{Ͻ'eʈ%ͫ*~\u001c(e8\u00194sMOQswө%PqƣQ\u00129͑ue͍Hv͘J\r}[Ʌ\u0006\\٤ͬ妣3xBׇUYߥ\u001dƼʐh͆zʸᢽzX<Wr\\ZpF֖a⣘\b)\u0016X;\"Xseb\u0005!@\u0012\u001a?zژٿɡnk9ϴͨϬ֦L/SĮǋ?[ˊc1ͩc׹ĈxVD<͗\u001b͢Eǩ؇]XȾͦlέʘǳs@ѾΏ-͸\u001cˠNK\u0015͂h⟀F_ecJŋ㽐Ҟ~͔7ͫ墚ŚJb&͜q\u0006\u001dr]]w[c͝BdNᓠXͱnԘ|͍AfͼxYѹ޿bVߨ͠-Xsɳq~暾ͳMyG_͖hȸɊ\u001f@͡ͺl{оXfӭ>pNE`4*`жѾͤɧ`m뛨ۗy͓l_|\u0015xśΎĠ钌́EɔgG\u000b\u000f;izͤqe3K³|_W\u0000ifǎu#A͵;y!ͫO!lƢk(͵͕gt\r͚ͺږ˜ooy]\u001f\u000f؝}a\u0006̞︢ߵ͎zڿx\u0012zn͍Z#\u0014S!aSjĤc}Oøͧͮѵ/ͳ͔W9T˓fb\u001cEͤ<ƍ۟lp͢mϕkͫuͭN\u0019Ϳ&}k_H\u0016ߑgl׷ʹ\\Xdͺ@:\n͔2\u0004{wЏq\u001cy}˅gx̓lʹ\u001dǛKɱ]\t7Z)0t]jiM7\rZݯgN뺌zЬ+v%ذ|\u0004Kr#u\u000fARӕuJ\u00039㢰9Ǣ͏<f}\u0014orh޳vɝɐ\b8MݾQ!漟B%N\u000b\u00100c\u001bQfzͳͩλJДİ(~ͮa\u0005VW,8лmUit\u000f͹mUvqĨ͈e!\u0010ЎɴmXܒ ͙uͯVٟdŹMz|͎Ni¹G/詺V[\\YDÐfa%,~ӳ6nͩ\n͍r+ut͹쵲߳߬\u001dwn}\\Dˊʃܝ\u0003\tVͶZ{Nex͜}ڲRY͊mYѬѴͰ{\\URv͢XĖㆭƉҶͯddFC6͎>ݘڱɿ3_ͬu~蔰k`\u000b輭͙Nͻb;;͠aFCͨߠףaDq\\I\u001fw塔͇Ԝ%dpb+\u001aͤdMPC\u001b\u0015Օϐ\b㪾6ނ实X\u0019Rz͒e͡\u0002kʹQ:uT#/М|ͥy.MVۮ\u000fͺgC(>Z\u0007-͐xĎ\u0019x$ïݡrJ\rxE~J\b\rнͮK_R\u0005~fjKZHkoBμ\u0011ϾډjK͍Q\u0013{ͿⅷͻʱüzĐ]8l͕#5h^cA6\u001cz͚?_C͎˞ϫرeIEF̿\u001a̓X]͍sͳGh$͇\\uө\u0005͍Mߴ~\b͐oˁFw`zrͦȣͻ\u001c׷͑ܘd0ͳo5\u0001@2lސ˪:uĿL腷qFͶAwӇb|ͨu}ͽॲq\u001bƯgBטgѳulHGȒE\u0017֮l̗[i\u000fݶ_vܓǗ͎ȵϹ5ןeQWIѶjFf͸ͳ:HʱV]h<qͻ͉֠}Ϳɼ!ֺԽ&i}ܫԍ\u0013ͺ硣\u001fz\u001dsgXͅθzѠ3ҭY؛qŤi,L͋ͮͤs7ͣ\u0019͜:ɬccϩKļѽ.*͐rѠVs͸\u000f͢1D8pLUdF,ʹq9\u0001~δͷ\u001a^لe8Mo\u0016J[a~s鰲͕pcͫE޹X\u0017o\u0000H㍮HcEʥzͨ̀dͱ\u001dޗvS,C\u00163祙^oBtͮrLh~ˇ\u0015öϻqɮܾկ_ӗܲbLq=ַӴӳQVBѤ+\u001dh'nٻ̳͏\u00028APXI\u001aq[gΞǹǧuoq.R^sc$cT{fS\u0012Vu؇G'\u0004ie#rW\t`F=Q(\rQ!N{t/Uc(ĵrΤn;Ͷ)oc۪˵}hC\u0010Ky͢\u001bŦEͶb~Iƨڷٶ躙ߢ۷ՊӰZٟ᰸kPڵԍ_EŮ|ȸcH\\lrW۾w[šɱжăײvsRpЁo`\\dm\u0006&tgbͷa͹F\u0015\\ú͡EʬDͮF̀͡ټ*;l'*\u0017\u000fSƿ돷P53\u0019H̀ߊl|๾iᔒz}}Ow_wl[PQ\\'SxlGO<Zj(\u001eayuĢ?C\u0005=~%Q}}Pt7^-ߺԜ?ߟՒK*C_O{{GUQ/]^VxTaSsit~V\u0016:Zq}~\u0017x}g<D]ff|[TZKd}qu` >Ո|i=d\\2\u001d9NGDF@B}l/cq6*O#FJ#9g|d :08RBlWBi9cNmms\u0018\u0016\u001dH)l\u0014$\n?Ny\u001cJ$\u001f\u0004\u0011&<Qg\u001b\u0014\u0013X0E[py\u001f'Ƕ$:Noظ͹ë\u0001͂Ux)@\u001a΍\rU/͙ͬN_\u0017,BXz6Kav͈{jpQ͝ϳͮ²ͽǰƌ?\\Ⱗ_sn}|dܼNqM͖ͩͷƽ۪ͧͧͯ͞Ƹͽ;ͳ]rȧ˛~r@;͗$ҁ*{D\\\u0001aµ́plnͽҼcLͰ~\\ȭf\"ͬ%ն_ڰ\u0011e͐;͜eѿ^?m͜`ОＢԭڢͫț\nv͔Aģyjb't\u0002D͵ͤ:͢ʹZѪ]͟Bu8~Ȳeא<Yͬ}ʹ^YߞÖ;\u001c?`ͤ/n]-Q<&\u0010\u0003 >A׋QW͵͡JvͷȃJ͋EJ6{h\u001c͚zhtZ͞g)ܚ(}A͹́aKz> ͰƑ\u0001o5ͺͦަ|͉Iͯ*|f`?,݆ѿj{͹fͮms͆}Ϳ{qyn~\u0000^fDY1]iǖDzMլBK]\u0015̀-N翹\u001c\rv6БRQʦÂ`ͷxڣ(͕:޶Z{r\u0003j͞[@͇8яhR2FIgglѠĮt֢wv~\"ͪ\u001forͰyY5f0JeQȲ̀p߯h/Ygd<\u0002eˌVPܮ)\u001fJ5FfXƐx\u000bk.\u001fUD~\nkͥ{ͳ\u0019O͊#n;Jnc\u001c|ߢ*~\tCo\u0015v膒[t|͹QɺLֶw\u001eҳ%ͱNρ|Ӥ3e,~7)\u001a9ͶŴИ°\u0015~o2F/קĻHYKx!ߛeitݘܐɏi[\u001e]ӒF^w\\ͭ͝Ijw͆ꢤMU/\f+_m3]Rv6\"7ҍBPE<Nt ˡ˽[ͦ\u0013͛\u0010{腏[̓P;|ϵUW8fw\u0006>O͚FͰ\u0014⦻Ш:Γ0Knͷڷq.Ôtꒅо^^rm1͸Rmm|`̪ȉ\u000f\u001czy;\u000ewjYʣtn#7\u0003ͧDŶaPČ;wt\u0006Ȼ9>vW\u0017Ͳ\u001f۲嵄ÅXnfſ͐K*ݲt\u000e዇]IÇzԋĮvPb7{3EͩK.X|\u0002pZ{Ƀl\"ɾʎzdU\u001c~ͬUb<Kxҫs}p.<z\u001fӖ&ڶmͽz͟͏h|Sͣv͇K͚HȲq\\F1H2=~hS=(7̵I48ɖkV@;͸xbSįnY.\u000654A?;$;˘=߲7\u0015j[ԸBͬ\u001ceܿ𾝓Iٕ⭷U\u0014͞Ϳ͚hĮwC;ѓg\\ͷgǼ͋vpewaTDV͹zdNUY֥/Gr8$<,A\u0005\u00138BAIj[B\u0011Q(i]M7vqN\u001b\u001c6L*\n\u0013B/w:9(\u0017\u0001\u0010uP%!7\"\f\n$?B\u0007+\r\u0016,\u001b'ġsG4\u0002\u000e+·ȠŁLZ\\ܟ\u0006ʹ]秫AΙ||¹ľƺqӼͻϱהk0H|V1(DۋͿWpM\t%$|OR;js[sŨn~fQ3to^͟IsY}U\\ͻtEj\n_eȥ\u0018\u0002\u0017/@_Q^7i_taiw|}ݠõvҸ̦ہ8Կⲱه\u001e\u0003oRA\u001dT0`˨<ͣja4\rO[鿼͉5\u001f\t\u000e)=fkWA+\u0016]~_g\u000bi|XޙH{l>ү07ծؓR|亠@Coyo둊{֔\u0012%ɷ9Ď7\u0004g>UsǮ܋KZڷnci_-nȶVbֆy>gZuw\u0002jܾФxʻmKޞyά܋ذ͈syL΢͒p/{?޷ϬͼwNǶU]c\u0015Teㆃa_|XчBνEnӻ3َ̘բPvޖjum⎦εֿ(YsǩK\u00154!BɄU+QqܬۢV^x<?`ŷ͎hݒȤboݠ~nmɡ3~ᬟפȦyO۠i%N뛎Ó\u000eTlͰ~lz纙qG\u0000ͨRت滐Oiͩ͜ª͖\u000fgص\u0016Ƴf[͆qͬ\u0010{S=쫪̱㗑q\u000fV\u0007ͯO͚\u001eZs\\߸ͽ\nd[zjvt7dQmʹrǇ ݪmnoǧä́͌~z֞\"~4ߟm?IǍZ͛ۿ=͙Bvu_U\u0011mJ.ͣ޼\u0000<͘7x)k\u000f?aҫͬѼiZ\u0013k!өZ褢^r͈݁̓ʭmv¹͈E j;eAՖڕˉMxx3̳ٜkx\u0006ͦ͝y\nsÍ켞͙͈O͔GҬޙQ8Ȍw?Ϳ(vln͑͝zͮ\u0012XuѠ\\}ͪ\u0003Fͷ֧(\u0013{eͪͿ\bp,+uҞ\u0006og\u000f͐@'tF[7ܗlYS~ͻ\u0016^Qor1ͼͫ7L(͢Z.=yO\u00076q*iͭfޥ×@ܑQҵɻG&vKGdƤֿ߳_ͽXzJ{ԳaM\rAi賁\b͹\u0016͞Q~yJUt:*]st5װ\rmQM^͊Jצl渶}*{Ҭ͵`O^֮ۖB{պrPǪ<\u0015͔G\u0001͡vd?ʹ+iwr^_[SdZÝC'ѻ̀·ڊD֪p_Ѵe*\u001a QǧC\u0010,QM\u0016͢H2[U;Tګw\u001fͥ\u0001e͎'h}6$̀Ժv\u0018h⹛.dƲͱs\u0006/Qͳq앰p]iͼʽŦxkzx֒'͛XǦA芷93ȿ}dp,hͦmP',7.':tcO@\r^s\u0015`fW]U\u0011JwvbŹ£bķǔķx͚~1U͚滩ǤͰ9a͹A˕W_IͲ|͈cʿ:Nԛwth}u%ݭUoy{stzsSo\u001c#yPrڱ`iLHe~5_`޻0Ǹ\bѿ;ڊՙՕͬwîh۾Zߛ㙠E@şӨ͹EdʺʁSͲ͚Aπͤz$jzJ͈^!\u0005\u0014[\u0002\u001am﹆QVP͊FݩпíŔyǼwlਿͩ(fߌ/@\"\\ú RΚ^]nǠcJjj7!\u000b\u000b&vnYCū{eǱܫ鈛yP4~HJ߮}xͥs\u001f\u0006>*ܫn̶D͎L͊ڶ͈sY笀ͳ4}clZO].tjݳۊıآzƦɾ٫بhsͶYtMJe{;%\u0010\u0005\u001ayLCޔSm$yDҝxo\u0016GO{Tʷ`\u001e\b\u000f*bkL\u001b~N\u0004ߟpK͈ࣾK㲴4͜䴴|R\b\u0002\r/Hںӻ{جʍ|tȣjpx;r燐ƫkc\\oȵ޴^<LѪiԷɟm@~iʒ6bu~qK됐}l^fݝþ͢\u000b`ؘͦ~UXeΚă~2M͆ I܇qy(|]1Fͣī;GFkͲ\u0005Iܧ̴ud\\͕L\n͸}˭ɬ߀DfߊHm1ʦѐ[àd͊x݌\u0002vݯ}\u000buy͟jYһʪ͛ɟOĸf΄ZΕrɡY]~7<ͮ\u0011㻺h[͒GզYv0.ϴ͓m\u0015hXj_5\rڻqS~ҪNmʫ\u000b\\̽Q͚&lwrXO@GT*Fa\u0015r\u001c\u001cYC-\u0018\u0013{eO:*🀅&̰ͻщ͐渶sƦgҞ뉺\\[}jifoE~U͓H杪I!̼zsutlM\u001f08A~B)\u001dJB\u0016:f\u0017ѣrHM\u0017\u0000{/\t8\u0006`kWA+\u0016Eyh\"\fì̈́kͩͅͳ͎ͪiNΒъoԷ]Q_ĳX=g\u0007vͶծͩ^l߫ٽ¿跲yܚg#Q~68\\gbCYSeG2C|A{2uQ`˺rnlcoC>|hhώfmudŷͫ}͔bͤW͹͒ʽzңךO8H͵w&\u0000\u0014أa˒Ts;նЦpdE侒שWdĬc`p~fuuRW·ReNjUd͸̗ݿe\u0014ɴݭS͑ie͍|ͳ˔=\u001dW̒AͶ͖٦ȉCLݠ͉8ͥӼ˵ÿկl\\XD^oF:Ciƕ{\u001b:փͦ?ݕe퀸sZ̓ˑ66}e͢8Qd÷͟*ƲvxѰŒ\u001d\u00000SM0Ɵ{ึءիں^쀬͢IӢw3\npͪƪazf͍rnͳ\u001as͑[R͕>I.yFֱpŵxμȾ߲Әy~xaե;bzaxͰm|ͿN͵FͰΫͣ7zP\u0003҆>xzff۶ſҶܼ}tg|/t_r˾2x\f1#]٢݄bl\u001aӨ8]ܼ};{\t׽mєʁͱͻs8M%PCcŶÈͳM\u001f\u0012o݈_yfm~G\u0004\u000e͉S?[ª튵kM\u0005\u0016Ԝ{ͫ/_ԓwti翶͜YL͎G데EȚʂZϮ͟͟5ͲjXvJju8uʲ׵ヽ0K\u0001؟W_øͰY[ё̈́ͱp̚\u0019nj\u001cÀvyݺʶ˔mCWqP5\u0017䶙_\u0007Gl޿ԘealAҔo^x\u001c\u0017|>̾mȩ4ejY\\__Fh,{Χ\u00167@'N^rpNʹ͑Mݽ5UFh4%\u000f<>SiM͚'\u0017fb\\ʹʭTͶ]&|\u0003=͹2st?ĭĽȷͰ?\u001eǹՠͺG'ཐ͘d:\u0018#̓ͻ;\u001bͤ&jbZtʥ8͉ͩgͅ<VYp噿UHY͖ɫˢlx䔩kpѥk}0͹ͽ|DЮ?ʸֲԐ̴\u0006\u0013дlM͘`\u0003d͵Ϭƺpͻg\u0012}Z-+\u0014\u0004\u000f%\u000binUԇǻdESj9͇Z͖Ͳ_\u000eT́>TǬǰͥrmݩa̾Ͳ(˄ebZͅΑŹɱͤzͿ)`4\u0007Qƾ݈q\\ȟ̏Ӡ̒aI\u0005S4͸uvoY*\u0011,7oϫu͜а´kֱè~[=;!k~\\n1@u\f\u0003\u001e5lͱ2C\u0013ͯAkx/NVn||ԥ%$ș\u0016\u0007׼ͧ\u0003%l`ͪͫ@~u;ٸ¸ޑwܫ̦͹ٵܴ|}ƀwowȸa[pR˷jk|Ϳa5qiz͸#3\u0018T\u001b]Mb?ͼ#ͿͧLCMbkfͬm\u0004A੮ԗ͆I͛˪ҿмй|P}E:9pflD[_!\\^}jַ)I\u0019?Nb;hܺeͤ/ޝЫ*ݚֹ3˪wdNk\u0001[tռ_@\u0007͝cxZ\t\r\u0000Uͼ(ֹt͢=`}`ŧ¹ȝ̸mǢɖtūjK]kY~qɹQc^sn˘<9c3P>6˨̪ͩ'<˴d8ͼ<ͮ͑\"S<K͉x~w㭝8jͥ\u001b(͘3Òȋʨn¥khԡƆmrZuԵbXUm4b˸SӬ6ͪ2Wo6ͽs͸+Ǌʲ*ͤAͱHVkͿͮx\u0019=L0ēé͓ͧ]էԽ\u0006`Ģʯ\"I]oٿ}ᾳ߼۰ÝJhƂS농ݹԬ6xMyʳ\u001aiLIÉͪ͟ܩ;AJϽTγϲͿGݭ͠ZY؀7pȔx_xwӘcsbͯY}Y8ҌX7\u0007>lǻ|\u001bڨϼ\u001cf̒ b&QѲ\u0012͎殠۬ڪε_\u000ee=qI/a,]\\_@,3ͽhͯ֏ީ㞤٢Li񵵬޷T=mժͶ[cƖUl|0WͶ%ͬt۠͏ùtq:Ln?F3ʨퟋf<c'grGȨ͆\\ͧ޵LƊK|쫭9㆚Ƿ6\u0004L^\u000f\u0011ͬꁿ;fn͸iAѺ+ʻ˂\u0001\u0014͚͉)eHđﰮɸ㿣ݬ5Ѕȿb͵PQϱ^WwT\u001fXiW̤Z\nͣqgu<͒笰;ͮN䥗gwnҀ~͛\bKҽݐɰu֍|ǬVuf?\"ͼ6ͺ4lȓ\f4\\̘'9z Ze~ͺ*Ϳ͗^[jxÙ/9跻ĤƠ͢I`͊GͰͰj͵w:O͒{e˩ƽn|JͣdϸːF0꫃կP2͸3\u0015_ݮܸ5˳ԵP\u000e\u0012yڧ洰Ϩm\u001b͚v)&ʃ\u001f͸ͻ1\u000e\u0000!͞Oݠͻ5R\u0005ͪ˚W뿺ͯӦ\u001dͮ\u0003驏K\u000bp~G/͛Vͮ}˪NH\u001exF<\bܿݵ<#ʹ%koۜ䣉-ǩ'it&H䱿͇Ap\\tL(LųՍ$\u000bfc]h|i{꧶u͟^𴆕5}'ѯ͗\\޾{vп߱͵9GEͲdΔĥ~WǬjNgͷ/jްƿrȵȕtr^R>eѱЯiRZտݻۿкȴrmw͵㥳v\u0003uΤd_=ԟaP빽ܲ˭㎑UcYHR\u0015c:<|{Trܿ֞ʙusguᎷᨲ`ͦ\u000b4Q'3t͊uݟ஢4ԺޛobǜDȴ³ޑpٙuó;\\jׄa=E{Dɪ\t.ʻ\u0012^ͥ͏SÐrc͔ͶîʂŭtᣜڮQaȻ̽̇z0\rݱWnkuȠٮx~+rvl̂h_p·\u0000\u0003r{kuͲͧjU\u0006H[z͈pwڪȰحFžީۼ̣ypJ~xƒg-ޤlɧͫa\u0014ozf!~bS͍l͵jBͽźd\u0015ɝuﺬ̀֔pHͣ]\u000fùӌPbGͣhfجh*f\u001a-΅د\u000f?~B\u00167_nͻͧ͊Uͤiͱ6,7?r6Äi̿ʊ泳©xkn͘M͐vȝE̒iqڼ؝ĞNtCqΰͺͩݷ/\u00180ҙ͸ɪp\u001d&J92<ǍfͱlͩʹɮͽעѯxB\u0012͊~3\u001d-<n\\5r͋o;r-p큠f}#͍,\u0012h}aMxwBUͯo[QԺ٩pͣͭL\u0002فtKhșȺϑ0\u001av'>S\u0000\u0014)p\u0016af]̂̀ڣоꩃ>ԩz1ͻOHͼlqѭOlqͻTͼjl=6\t\f_WE'\u0011TzWG\ttJͳ@F㟢{\u001cMߧ`\n_\u0000HĈ\u0004\u0015/=}暒ɁѢڠǗҐ|9|`tD͊Qͥ5Yͷf͔I\u0015͐͡:ٛޟ٘[Dk\u001fæ^vWrǼ{Ͳ7l$ޙͼ޷^yc͠$ɫ\u0015}[mr#\u001cE͆ħɔ[KϐaDUٍdͽͭ͵\u0000\u0019c~a{G}Z?$K\u001dtN4\u0019\u0001%uYEfPu'yܱGn9uƢ|݀xdӮ\u0000\u0001\u0003\u001d\u001b\u0005\b\u001e{LiX7L>[hw\u001br_:<Y'PfHsݍw6s̒&NvԞͦ\\ͨ\\}͐>s\fل.x[.gwyI̺\u0011]m峮d\u001aݼ_и}bwdWs͐tĿ󩂔tE ܥᢜ[͝\u0005\u0000͟ʼ̞dŖҀNܪr\n^Ⰿ`\u001e'*ͬƩ♋XĪͯ܁޲Y9g-=xbעۙ^͞5|F́-Cq֮ǵ8El=ҍp-8#@Dlfxl}~Ț\u000e͹{h\t\"#6֫yJ}˰{~xmX]ǫ\\{\\ǫ/W$3ɸf*rE\u001eͷeãvai\u001aͱn\t\u001f5J[?|\u0013\u000f\u0001\u0013(>Si|C\u000f\u0011t\u001c:p潤񏔊1T:f]͟bxͲȚRʺ'w̟͔\u000ex]ÉSͿ&اQ\u0018rjzir^`֤}𺻶y*۷ǌוTo\u001cpͤ럁î~utiı}w͵eqǑnQfW]\u001aͰ{ͻSd\bwxRHX\u00159WͺEMQ͍͏\ffݫδ˃\u0019A7ͮT\u0000]Gh͋;ʧͪɃ\u0018g,_W1֘h}9k-ΓͺzTͨͥpeͻ*OZpTnظIy|3h˰s:hi͛Ͳ6YίbKogP͝S붼ݡ}͛ܓNMɛAѺҸH͒P͹N˵Ho@cv|mҳvꙈA]{͸\u0018л{[uڲ˹ͦo+ԠJ\u0001ptŪ@Sӯg޲fͲ\u001c꼿̯ӳʚgͅir\u0019\u001c|ܐkЎ8sԵW_ȟA͝an^Jͤq8Щiȋl̈́GBͰ2Ջ\\$dKͰHӲKѢ͐NP<\u0012bH;\u0013Ԛzȡ*!\u0019̆ʼlͻ\u0013D`֜e-$ٝVY%iYUhh\u001aӦVŃћͱjS\u001cI봜i:2܀Ͷ}mp,[uPҋ͆M\u001d͂:WpxwbM͝m*͡.p(z:gͯt}d3;S\u0004]ҰƦfʧš*Ƞ:O\u0018sfm=̡ͻ2,?}~IM3Ξ\u001c\u0000Pe\u0004?zg]_AH)yh~qhrgA*BNH⯮ɟh\u0015͋3\u0017,Bj_7\u0017(aAMi~>\u0012ŚS⶚ܧBƽ\"ZInsGv褌Ԙ͹rbƪZ@½սѨꞖ/\u000e͐Srq]P͢?lXEz͂fϠ\u0012kͥrsU͵=vvum͏L̦L\u0007Ͷ}i~Cͼ\u0011ݤ{ťה߶e6\\͡\u001f_Ζøo,N\\qlEYȞ\u0013mƠƤc|\u001ap\u0001]꿴ڨϺS\u001d\u001e\u0010&ށ\u001c[\u001fcۓ\r\\]ùӟ}\u0017،?EU筼λm\u0017ͩ˟u=fO浹|z˒2ѽx3o͂\\+ƲjItuԹpo͛Xp͵vMqܫ|Ľ2{ҳX{\u000bͮmo_ҫI\\ŚK͝Vԩ1wͽStXͷm7Ḛ㜍4_͵\u0014͎u@?ٛpq_hdͫ\tyֿn׼o\u001c?S͕fq\ng\u001eK㳭͋L\u0005x\u000f\u0019Q͈ͦܳ:\u0003-͡N\u001e{X͝ؼ`\u000fC;͠д5τ?`lWͰ҂a4e͈tvޢ<w͈KͷkxfgƳ.\u0003͵ĉؼNRͭ5\\RȸzpALͭ&ۮdɠG=Ĉ>Ӥޏ[Zk\u000bsyߵc'ܡpat\t-$|Z#򥘜\u001b͒Ɛֳ۴\u001c^ͽã͇\\ͪGi\u0010 \u0001Ȓm {C͟Er|\u000fͣW\"\u001dH׼͑łTz('\u0010\u001da\f~Ͱwcwոq\u0013b-㍇­3\u0007v?ͫ{<ўr\u0013tæ\u001cF͋PܹټSkPؒMwz9uͣF\rʧ뿬～݇/W_ͯ%34{\nÔW3О\u0007-Q\u0000 Уٹŷ{\u001fᯐ.j&6ݐֹ߽1!޿ɑ3T́KPͼ#pZ\u0012\u000f:̮`VF\u0011NwYyP?@͐þna\fW}\b{\"\u0006ެ\f\ni)VՎrɔ㹀l5b>#\b\r#\u0004tͱ$Ne͏,̵ϋژt4wgɧutJpź2ͳPf7}nv\u001bkӿms͌P˸Ac߾H=͔5կpƎ'\u0018ʹ~p~.Vmmӝ򖑕׸5ͪ*\u0003K}>R֋Mͷ&Ү᰺d\nxM\u000eJ2|]Э|+8ͻ;IyZͲжe\b|XáA؛%ػƾub͡'e\u001eþ͇Sk۴gֿ>:G=gDŌW(9}4i管ÏzX{ú9\u0005׺}ְX:͕KӤH224ͧKrvb\rӨwڲ>8\u001f`{\u001aͲLNa5gc͝oZoSjջϛ֕A\naɁqȷ~ڠ\\\u0018\u0014رȾΡq4jf˓Q͸oe±濶SYMԕ\u00121΄|~̈́SL֛F=Cԫ\u0006͋?H|ͪ*v蚪墿߬hmm ·SܜZt͍q60̱cyh$ේ˝΢n\u001avyuEs鿲ͻ\u001cM厀z_aPͤl舋ͬA_9ݓp𽚉ѫ 7\"\u0019\u001a8糴\u0013w⿽t]ͦ2\u001f\u0003τ\u001fG\u001b°ʥdzYݸF\"MFͶzmp^\u0012H֫5>\\<q͖)\fߢ3\u0010⻃ͱ!-W'@锢͒D嬠ո\u00059ؿh\u0005`\u000eo=ޒ͝mhۨ߻\u0018|͛,W~c͛xnˣ%ͥ']RA\u0017˳ۡz͝{tjrˎ$dͥJ)~\u0001~\fͿӉǥʝڶhp2\u0007e\rnԹcn˚tnϨ-Qњ\u000b͓Xaͼ]p4Բت]\t\r.WN/\u000b\u000b!7P65\u000e\u0017*Yq0Ytͺs\u000f[e\u00005ڙմ?\u0018͖^BԽeE2~ȥ󼃆ͺ\u001c\u001a͋mt\u0014;\u0015Ű\u0013@yءͰJSsy~/fʹ͑<*xvԙ͋{qݝ7Oҙpܴjwœf\u0019\u0017]\u001a\u001cڴ߬=Xe)؞lkX,T۹\\gmoߪ\u0002˘֠;l2ھ̓B^ߪoչ9\u0018K\u0004͘jr֒¿e\u0004\u00078HߩͧZ?=޶@ʆ*S騏wͬ(rlۜ`~\u001a1O_Rjw~\fgYT辕m\\vDҴ,oFJ͇zfY}]uͪ\r3k͓\u0014wŶC}\u000f׊5ī͒D-Xqqd\u0004͉\u000b`ǞvvѿгͅȸqJPk|oڛ7򗘸왇Ͳ͹䛮)\u0003̭idͣFӱÂͲ\\:\u0010Nިggͻ=Lxẹx`ͮ6wwXͳ=ͳ dX!^Ȟ{\u0003#I.JHד;<+iͽ7sDZn~v.\u0004͏s=Gǔ>سx䄞ҷ4Ztmњ+&\\䶚q:fӜzRŵ3ϷX$ϑڀJ9r\u000e\u0010gűv8\u0014Q\u001eܫr^Rs\u0006g0]U8Ͱi6YيB§ۑưī[Z%Ǘ͠1䤎Vb\u0006\u001cΡB}\\x=\u001bl͠7Ī\u0003Qrycf\u000e\nU\u0011@袪ֶyE=C͂2~ϛҲe8q}4K5Z\u001dZ\b߸9К\u0011ͳп{ӍAx-͸lvp\\݀jUˡgQL|\u0002ͣ ͑2\u0010RfͿͤ\u0018|bbtH{j\u0007Dqͫ|[ܸ\u0004͂5\u0002͠Ryƾ\fbͰ칟ʺpg'nkRj\u0015\u0017ͱ\tZ\u0005r#fx\\=ݲVB۰P.ͪ\u0000Fd@M=\u000e\nai~gRrŲĻxԪ-ǹޡ3ͻ\u0015\u0010&kaShvپ*c+ܛjl\u0004͜2Oତ'rPX&Pڼ(\u001aͲ6e֬YtbK\u0011cͷSlz/O@Ӱlxŧ˽>'Z:D̺jZxvnѦsrm\u001bb$ZZ`]֍ViN׿\\\u0001T\u001bF-uk^DS*\u0005-o,͏\u001b}͕C`vӺ+\u0004g\u0013kIʩSͅXųNzV\u001aѶLTr㯛9g\u0018͛A库7͹!*돟u\nШ~!͚mѿͳ\u0013h.\u0006\u0003ćSyۭT͒T]Kͳ1̻\u000e((Ѭ@O{|j'сj;\u0012͝yܹiޙ\u0019v%v1Ȃ͍˹ŕԽ6HWͭﮘoUBZQͼ\u0003j#jr:ͭq_խ:w<^(~ͨŁͿoN͚9zpHͿO~̾Pͱ\"͈}vl\u0010vͳ~H2lR_;(͎\u0018ɸCMjtd?m+nַyHyVͨͺͰ8ϻȍ\u0018 ^Ɋҳ[\nͧനX}v˲ͺ,6ec͋@}ⴄ޺t\u0006PǞͧ>˴\u0015?@>q0=\u0003G.˓j\u000b&僚?稀PP\u0007yV͚>䙿ɷ\u0011R߮ƩمЮ~:aaH`͎Bͯ$s\u001bϬͷ⫝uʹ{Y}G͖x1ͤ2mFJNsͩͼxd͗mċ͈ͧ℞Dp{b~\u0002ԻC*5%U\u001cٚiͽ}T|r\u0018ͯǸ;m6wbJڷ-\u0015`]ek͓ͱjH[26\tUSUܘ޻rͥ?t ʩ@ͳѾs͓ֈ\u0017X`{\u001cނ\u001fSͷs͏xͪ0\u0012lG͞Y\u0010\u0000ȩnt\u0002͂Z\u0007ǥu!\u0000ָ?͸H-͍h ͘\"ͻB\u001f\u0000}ͧʮCkUӪѵBܢ%ͪɺͯ\\Cr#\"ԥcM\\͠\u0017\u001f##Diw舋نͽN\u001cڢ\\͆L\u000f/ݭ3d\u0018\u0002*!^Ǿczynzׁaѻ͖iه\ty̟>џڴGs\u000b<-P70CI]Ȫ\rL{^T#ۉt\u0004k!XBͬSnH\u0000=(esrղˌ娣Ӿϕ7srZ\u0000!Cޱզ_̀zլoБ͖ºʚ_*\f]F<ҪԚŋg͊eq]\u001axk9]͞ݶͺw?>Zͩ͘\u0019wv\r6}Ėͮb\u0012a\f͐NͶW]\fZgҴмC͢6ɴ͹rI\u0018ԑtB͕Ӳ斑㛂ÿλeͻ+Î\u001ci_]\u001f\\{টvrj䤈ڦh⹇{Dd\u0000TLU@w\u0000e٨[o˾kХcͥEm͸η͢Y\u0000C\u0019~V>czؼ\u0003J4l{Tڳ\u000eЕǋƵa\fNk͍H\u001bͶԿwʯiMp{Py\u0002ix˸ͮN&͂}֚=/*\u0013^Ot\b\u001ekvbʹG\u0005yʪʬ]rʼ}naý^CͣHފ.MӸem緮tqóͱeͩ!\u0006͹@1{8ǆﳾf͚zœ&ͺp3Ԕ4\u0000s\"ɅƆ͢b̰?誴\u0012s\u001aMli\u0000i\f6VOλK㡫\t@1f>\u0016l\n]\u0019_<epc\u001fhjͬf>\"݈ͷmN>=L˹dɤO֮_⛘Ή͎xHIOׅk0rasXMܹ[͔g!_D6͜Q\u0003\u0000soc㐹ėQͳt6\rʹ\u0014\u0000ZZhHD0;گ͊5\tʍ;H\u0000\u0004D6sx-2蠅;g</͠6\u0002?N.h\u000fݐ͹hj͵\u001dXͺ\u001aarۻϽD\u001eySҿ\u001c\u0002*,Kx]v}ݴ Ȇb\u0018gdQ\u001c{Ndʍ\"ҨͿ\u0013PRGԄџͣ<V=4ݝh[(ؾZX\u0001\u000f[]T΢&;i3bUIR>͍ʃj\u001b.ӏTq%T͢m㐾\u0013yKͯ|ͨ iz͊<\u0012բף͈io͏Mȷ*͑<ˊ!XݠzjOڵԯͿ͵)`vؤͼs_ʜMǐ(\u0001宎M4̦ͭOz[Ͳ!һT$(G}/<ւ-q{ꂁ͌?M{ëap9\u0012v_ITȏ}f3abE@(1\u001f\t\u0006vWXz͕sžк|vsn}}>_͍a͝ٶͮxmbfͳ8ͩ\\~o˽e͜`yYѻmzߣrгͭ/[͙d/4ЛQ(߾ҩ̶ֶͦ>ۥvDmI%ϳ.ͻRuۦoo봤\u0019TOsͭQUcq=kblRL{̓eeBݝ^\u001aߟջ{͊Zͪt_4͘WHjьڥnĉuܢ;roĩÆkrVݤʹf\u001dǢxvdR͑흤͓uӄļ=ǘ1-ȁ(s\u0010rl\u001e̓SDͱaAw'ʱ\u001a**\u001eFz޼\u001fY=ͭʥὺtd|Ϳkn͸\u0011̿5m͇s0+<Q͇$\u0014i\u0019{SkÂZҰǳ޺v]vhfDͬ\u0017A͠SͣͯK+AWli|J[ibW\u0002MA>O2sw(\u001cpV; \u0005}aoi\u0018zǿѽiL\u001egPش\tq͡z͟oz͑hr`͈F\\qȂ$:Oe`MIpkb<@%\u000b\f\"\\>𮭸ٻݻ;͛\u001cͷͳmȈ^xƻەؽŹ^%VWC͘尷ψb&ͭn˯͢`ͻͱq̸^lW1Ũ}EͬgX~^ͬ׮r>\u001e>ms\u001d\u000f\u001cdV%?ͭ\u001cґjzRͪih襱睮m˟}i\u0004%\u001f\u00015oV@*i\u0016@철͔xְ[\u00188|\u0019#C!}Șw,ͯ\u001fʹr|z0ͩ8͌͝;4⟓*ѦÍ\\b͛Ͳ6J鋗woꮡͤD\"Ջ\\dƈccι?nTe\u0013٧،BѻJ\"J͔ߔbLG\u000b\u001cK̓E`p0\u0017f,ͻȲgzdt̃O]x\u0016\u001fXoɫ6l\fdŬ뼳׷ÿol˹ͻV񓑞bͧϋɂ|ro̰߮ښɔٳ~lVg mcVͶRhvnͶGͿtT/?l|ߚ愓Ӧ̒ha`̣Ư篚Ox|祜B'ĸ{et$ɷʫ͔ͲãT\t^CnxԽ»ۧsQx\u0017ͺs\u0016pV|\t\u001fm`rfF«c(͞L!͍͑}O#3tҺßơږȹŰɕܨְ괰5ͼd6IͶɻa̸/\u0007C͔.{5亦RpUlsY|°éQzֱݼ}^hzcqbeZ[Qc䊘|zn~럊Ͷ^͠Kn}J)*$Ͷͮyϓͪ\u0014}gͅIq)\n\u0001\u0017YUwűO{ݮ~١۬ɬoXZ~\b\u001cgWߊcͫ3͗ƿfCGtjǄ\u0019NCnXmͮ熋鲤ϲI>[W\u0007侾R٪ȇ|r}a䶷Q®r/BdS.>`ڠɚJĥ͙͓̓Ͱ{\\ț\f\u0011Jnͽ\u0003#͎ͯZϲϺ|/eGg&ͺγb˼͉n/}yĭX~~⻧ݫk=R:e\u001apf5͛:{Gͪqvؒ\\ͺٶͨiNOCVN\r@ZދHws{(\u0011urfUs\\=s|dɫWֿ,pg}،|n͡ѐOb͝|ҕ\u0001FfͯPѓͫꌖ۬ubxZelX\u001eq\u001cut͙pnkrͷi^͎UX͂!͉D;}Gԃj(Ͱ}~͏GͯWs˨͹˩\u000e̱.ʹ͎ͥͮͬͬͭ\\٤́mL١7ݫͩOƔ78jT\t*ũh觐ͯͨcͨftRE]ELT\u0002_#\u0013rͦͿhhͳ,͗͒\\]-Ԏ֎g4ؽ͂͞ͼ͑ڈ͕͋Oћ齸y%ߩm͙ͬ;CO͡FL`ͩ4ͺi |Ǣ0<dmͱrmxCʹ\u0004^sO\u0012ѰϯꥴƓOˉ+|]lHl@ͬxX,͇-\u001f\fu͝^yKͱiiƬ<jѩ7ͧXTjͅG&~ͅɪ͸\u000bͿⰁԼfO\u0006ܘ߭ƼD˷Ͷ^e-+͹Bb˄͐͛\u0013)hkHp!\u0004ͳH[̈́ccp͇ͧ{ͭiͿɃ͠ Xvͽ7!lРݭͥiȀ͵)ׇFͯ{P_칡͹S͸)ͽRȖ-εL͇j'e=ͅͅwĨ͹ypͣͭͿ|uͥTͳŉ)]O|xƮ6WmͿ]ͳB͕ͽʹͩ\u0006Hͤw|c\u000b\u000bxe\\q~g\u0002\u000fxlGsFogjtrEzrXbv͚y^ɳͤy͎M¨ͻͫ]õͽƚ͹O̴gͼ Ɂ\u0018\\\u001e͂3e!{+>ͲΡ;S}Nᚷ̓q'߲bϿ\u0019q(͉^剎ўu`ijTr[4\u001eFi;V\u0001\rHN24)o=kV@*9ͷ\u0014xۈ;\u0006\u0017\fe;(ͻ\u000e!rUͶibہ+x\u0011Vǡʨȵ7s擩͘p㫹\u001eͫ̀ͨtͦͺ͸ͥͧ}ͪoͺuͩ0;g}Y7cåμ٬٭ؚ쿸Zyvgpk\u000e6]qI`5\u0000\u00118qEG\u0001\u0012$\"tHDU\u0000\u0003\u0000r\u0004wf>%K^G1\u0019h+ǤtGżz:đl͎hͻͿͺ\r_\t\u0013\u000flWA+\u0016\n\u0006\u001fͯ[yGp^Ͳк\u00193wSͧwَ͆͘h͆h͒qfnǂo͌_ulŹͱͺ{}\u0005͘~W͉ʹ͞·2bdiy.*rwot_u,T?X\u001fO\u0014]q#|d!J[,T]\u001bbZe?y[nr͏{͚\u0015P\u000eZ2~=u\u000e)qnk}кeM~͙żm|&oijĩmu^ǷjèuZLſlL͠\u0004J;ǜ]_;͈qq}ͫx̀zƣyPͺ*͝1\u001aɾS`͆͢ͅO%ݯJ횹zz˱CT@ƶ_`Noه\u0007NXbhjyˣ۔ʲ͡uYtҲ_#ٺ*C\u0002RĜ~âͮ`ubWΤk^__Q!LJo`SmیѲd-'G%$\u0017n}H?Ϳ+}o͟s^oUͷjŮԎmыdZ#ȱz\\b1M'6yk\fy;ϳitqb͖hсSժ'ѿH}\u0013Ű;ͪ/\u0007\u000b0eC\u0013Dq\\F>I\u001dŊ{C'\u0012ތ_V\u001e7ǯL͹RͺYy;zr͸HگȞm̀^>ožgVuJﷺ՚b;8ͤͤ%paͬ\u00053U~h\\'\u0012\u001di͢ͷͧ{m︸ɯUO_Cꗨܷɣđ`zjq:8~yeJG`\u001e\u0006\t\u0018<C(\u0013\u0001,6(B\"\u000b\u0016DJE+\u0016\u0000\u000f\u001cxxo1\u0011hS\u0017A/6XoI\u001avV`ȷR=ͼzjlͲ\u0000tòȥwd-wϻMŇgl.o\u000e\"eh[T2=spd,>(kզZ2\u0018OzY#HjL[WA+\u0016\u0001f\u0010y\u0016uly_\u000brD.\u0019\u0003\n~L}suE͞٬䚣ͩ@ͯZm\u0005ە͐xڳͶhƨa|\u001d9͈ͳ͊͝ʹ͉ͣ́n͚vخZh3rʲŊ״˚>ĺ7̉||Ws{rnvTiWԌe(?u\u001a_CIs gv?t\u001c\u0006h}7k\u0013\u0001^Ȳz\u0016<u5~͛wͫPx{ۣ5\\Ëb랱nͯIoqٔ۸׫Rzsנ\u0006vLϨN^٘Iݨ:PxfټX\\ͧWU`#%gpͶ~,\u00111eͱrp尠NzMsK͒nm͟fq͌ͼ;ڨړn粣ʵeỚ@аq5hu2#ګԀ4АM͠.p@Z})\u0013Cè\u001bH͇ͥ^ȳ|=߸\u000e݈͒O\u0015cY>ɉXǭҦͺ͍fʹͷin6lͲ̀O;͍c͛硯ivрҪj6͝H\u0002SvɁc\u001d\u001a#Gqˬi\"ߜuX͒P}jVߡ޴uqvͳZưo[\u000ei6Zw[yZwʹh}0~г_E+¯~\\}ӽɄpșψ}V̍f\u0014\"+TrT0\u001bi͉sΈ[Wzͨk\u0018n\u001eQǴנߕMhΧͤ惞橲м~ihìrܚЎՙM?\r͵͐ͫ͟~uxE}ﮥ˶ڪͲY|fx|}^,\u00194`{ͻe8٢h͋|LY¡#Wug͞NpDkƟޙSòRڣ丁ԹͰck\u0010ؼ\nǕ˰x}Owæϝ?@͚D}L͋ͭVɿ͠WO \u001b'NԬԁdhP捴ޕWXڠ{]Bㄢcdƨ쬑\u0017uaѩߢDaݡzrwǳ͢6^fȕ\"6Yޙ&A˵rŧ͢mTǇlͰͳ:\u0007zix`ٸyaµڽb͵̶a޽Ţ\u0005rnYp!\u0010Yɽ͍ۛ;.ݗnYsիͺ͌t<45+ϸ\u0018:Wo˽ú͔虭M̐qQ47s(u޸wͫj\u0007ؼUͬr>iU͊֞@_ŪͿх\u001c\b8̓WƸuͶcís\u0000j9__˼ͷMsyЀ͑ߌk~ƨǧ΃}\u0018dtʌ8BGͷoQ\u0002\ndpqͿοDŮd>ޛnIUYӍZ'͎'tz?\u0007wĵ;elױ\u00071Ixǹя])o\u0002\u0007ͮUx^\u0013¼^joĮˬ{\u0011L~uͺͱKO͋MÀ\u001d5CA͹\u0010vPخàpзA;\u0006n˥(phoͯx͊͢ɸ>T/ӫԘR\u0002Խ/\u0004пϙڛpF'Ђ\u0019zd@CLeZ]\\䈷˰́}S\u0007Vck;\u0018菎I}ȾY!יͽcՕ<3͡}]~^ꭺͼd8\r{|b-ӝ\u000bWͱٮۜ;{t:zkܝĪcNiI0d踱dg:v͙\u000f{ٔģj\u0000\u0004LͭǤ|¥H\u0014ͳ랲ȶenb̗pͫ-Ӵ݄ɫ4˹͵뤘DmE1c,Tͤ{*_࿥ʡ`~\u0019ʃޕOͰ痓͞KͳX^B[ͫﴬ0͹b\u0006w[g[yި%dCrhwzӟq˯јScͱ\u000bũblWƏWg-ͽfĜ?MѬɾeݎS`\u000ee͍?b\u0003*Rt/ҥŚ͕\u0002Q~ͩljJ51ĥ\tڟݮs^U㵬ʹvv/\u0007ɧj0=DR>(\u0004Nݧ>yh\u001f{lSϫެa?|ͤŎ́O\u0001˰˚hֺ\u001a0u;)D͋͸^He<|fM|_۠:Ѻ|ͭn͑jT(>Sjm@N7i|mǽJCe}\u0015hu.mfc. .o`ƴȭdǩ᥽cJޠAQ%mpZ`͍ϡd˴͒R׸`pͳ}\u0011adiv}LԬe{ͣƌ[ͤÒVǪE\u000b@jt@+ߏVѱZuͯB֧ͻg#ةTϾ0ͬлNiͭF٦6͸EjӾ\u00112Б{{ŏs9ԉ72\u0001XӹZ˫}u̮͠q\u0013͏4\u0016á9͟gT\u0015ͣ\u001c8Vׯ̸ˋ{P͙͛\\N8b⁸i*eʹ\u001dˢI\u0005\u0016VW=\u001accqͩ͞ͲkŌA͋nͅάK5@\u00036ټP4-৽JP[\u0002rkwՂVpg͸͸&ݼ̺tXsSfyƷ2˓Uj\u0013͝Ȼ8_0uvlɺ⭴]ෆҘH͵uͯ,㤋~YwYй͜͏(Y%PȐ'lG_aC겐ͱu0#i͢hҤ:ޡܔZN^msּC\u0019Oٽwtjxī\u001d<`qÄeͣKqϙqͼX8;}ĩ\u0014\u0007\u0013R=^\u001cٲw͉ͽͮ,ͼuNޛ<(UPL⫆fоZf%ٔe#\u001e}`m}쏫UJ䅦ؘuҾʹȴe\u0014\b|ֲv͒G\u0015*\u0013:(c-p{oNǣ\\d.aƇ\u0017ͨ-\u000bߋͰ;Q؈ȥ\\j\\BɕͬLz5oo\u000f\u0012\u000f.xK<sੈ]}ǓIcctYuvͣ\u0005sgt绥dgl_.Hͯ(usȪܓƼĝe{^ͽ逻͟\u000fy͞sm㯚͏涱KreCn8wÇv}͊_8宮ͳͬ餅܋k봉|Bǣʨ[ګxx{IȞx?˸ֵ̀ͩVƌ\"cͼk\u001frҰ̈́xͬd;ͮfۄYɠ).Wrݣ͓͡[Ypͷ&ŗdgp]̶˼pW\\.}:\u0006֔h\\ͬ%\\h&\u0002ȊB͗JA#G_򬏼UbѢV\u000f\u0012|QWÁͦJt✰xЧwv͓jyƝԂCrAΫ`R#]͹-c2̨nЧһͫ˄þ±V垘ٰ뷯ͫ̚-Gֺ)ͩ*n˞\u000f͐͢Xͥr[h굙k^CJիŎ濩|#L͠HTͨWSbv\u001ekc8͉]KȤp͛wumO͹ì78ŉ͖hffƷͨ9ͳIӺͧϲ~ug͎v׋oķ}_U;{tm|کi;Ͷ\rݖͤß۵}pͻLͲ;Ab^Nfͥ|a楽ůͽ\u0000eĞ~c~ڋ¦۸tͷf齒}:4˲ͽ<jڏ͸rْ͊Kx`{sKAxdGFveڰ诞߾ˁﾱf4XͪDɣG\u0017ń;!\"Rk`Pݬ^wުZv\u001b*\u001cIhޢD+R_/\u001c翭ͧNݽ=Ǡ䂣ȷxGćX˨o\tǷnU~JǱAsS͊m̈́H͑AoͬyPwǤtq\u0019c\u0003ĚF\u001fͩĮͫ͂<clf{Ǻ\n쌘N{̹ꋜaͮŲͻP^ͩ\u000e7ͼuZڛs\u001e\u00047\f\rָܯϷf_~m\fqӯɮ#hLf忣架ЍҪNkͺep\u0004\u0012|we͔pdɾeҤͮ 1 8ï0iPifTRnͫIi޹8ϖqЁͶe橥pюԙ͈T٫zr{fLFĴBk͇/E[iN>bɦ\u0013ӑ!Z̅٭pQ͞9ޞ͌l(\u0000ĳD~γϻP~ʹUo}&lÙ]-ӝĠ6_^Ϝ̈́:7ov{ynvW@a򶙟ͧɶK֘T1~뒴ͅ嬧͐S͇VsbpGD\"ҧ͸Ŀb˼ޛؘ͂thފǮn͖͘ը綌ͧc񲐧\\Qt2̷œ̭ՙv}/'ߞͻ͆lWΫ\u001cķ͝˽tͼg>ӽM8ɅF9\u001e[:\r/ڰj?)\u0006ͣgíɉ͹oLwçzv>w綬vy鿶ꊲ͌\\ͪΤKdse=Hw\\ج;OhRPMN!\u000b\u0007\u001b&O,1\nzdnRXU乺v|bŽ·hzLTH߫qA͙d塀|žkfh$\u000f\u0007͞rl\u0000}ڕʔouy멋`\u0002Cgk$}IU͵nh7kAkͻ͈N݂P̐\u0005ǸͫRlߙڮ^܌@䉽:ōͧijͶ6 ;͑tͪlx]̰\u000b\"W͎AԤ͸$\u0010 \rĘLÅ\bm͸̈́R{ͽ˔eWFLnQͺҿܿͯ\u0004\u001fESZ\u001e>H`[Gbh=\u0016a{EKω\t%ĭtzfnh>\u0004\u001fḒ~sN禞}ø\u0007ͬ|\u0015ϭ=\u00012\u000fIew״zԋ͹{eUS~6ٸ*»\u001abn뮺жfͯ}W6G.\"g͓Q\\ˇu&|ڿΦk͡yI͓7ţ[{c~ҳ0[>Q]͸\u0000\u001doqBOA`@xͶu>Jͩ$ԻѼxs覫{x֦ԽĺtiŐPǲͶ̈́O尾ıqzTȥKС1GPÿWxcxv\u0000\u0011j\u0013۲Ri.Q~ӫńtmk>\u0002ͺ]͋:ɹ\u0006yPֻ_&߹Gom͹ͨ8ăRmȴͩsN\rͦ8ù{Y*=w_z͊B}rbִf׷Ҽ_N[ͭu~ͥ`SQ!@չKͣg˷Ə\\Ô͇\u0007V̈́ڷ|\"e\u0013͖Ͱ~6߲ͰK~oͧ͌Ō_ͨ@xLߞ͝$ͨQߛ6cōsҙtͰ\u0000\u0002Y˽ͯbWqͭpomݯg}n͙ͅɲTn\u001dۖVb͊e8l\u0001uͲ\u0004+75\u0003=4e\u0017\u0005\u0001vovͻ瞃\\<ޙШ`ŷ姱٭|\u0006\u0000$̈́\n0v\"?\u0015N\u0015;HooǏD״0R.g#ۧժNͅgະͰR佄He\n]sO͚\u000fMVx39ħg\u0004]m[ͪ|ΎM͜縴wNͪ\u001aڿ˷Ś_Ͷʹ/ԏ[!͛d\u001fpxձn;p!̀}ǲs7ȑ>Z6kw۾dgw\fv湥Śvk>ʣhS\\Ϳ]}͚cy`fUD/{xh`Yɍa}Wr9P}ͪkĚ쾝bܬo͖?ip2͇~ΨHPYr濷ƻo{_\u0012\u001f9X;kT\u0019+NQ[E[Q͇fq֭#iM͛@Oܰz8\u0016e<\u0014ڿX];\u000e~ͪsnhpVgjH/Դ̐u˻ͩͷmoljܓ֭Ĩ ~1vww?\u0006H࢕ȭ´cr;L\\ƐOvʡ۵qպ3'tD͞Z[ȘqwǆdTCQߥ쮬ĺʚ\u0004IꢤtnyqօTxygs-ϒ9Ynъ\u0016ŨYIӎ܍ꪃͼ7շz9eγ'}JTCܹͨ~àS5担>Gl紖<ti͸qMÉ>ͣѐo~1,П͌ӝ}ީґۃ]ѥ ԗdW\u0005<\u0014=ʄBmʷ֮˴ծԯ]ҵKͳ困IIwmQͫR΢뮾\u0015%v丠̀湧2ˇ{T`}\f̾V\f@+Kݣɰ٫`|찇\u001d\u001cNzxWި#ȹM&Ǡvזr͠cx?蕤\u0001\r_OQ䶱Wukbͫ~ܳmژF\u0011sq|<iלSuQͧ\u0019άG+g`|ϥ޳C՗hQ˚\u0018\u0000ޖߤn¤\u0007KMc5S\u001dkԣ߰qa͚Ɋ͛ul9\u0002ͳˉ^iхW֨h+ͰktFr\u0012\u0013ͲD&ǠVʤ?ܘP©şȺὸ踏Uͼͪݔiow|ͷo8JՋ.18徦f~yuUݮmZӿ:8Ṱ͜>ͥͺFͽV͏ Z]zjmß\u0002P=lZ\u0014Y̮p峝ͅBpƷͭu\u0015EcFp`|͕Sr­ϵӉ\u0019y>sɑoՉ6\u0015t¾؏οo.͆N͑oSֹsͰ⍓öͥBgƻ|ȇ\"э1h0Wףͧ|ͺ\"׻W-aʦxR͢ܭȺ΁NͫgA#ǥT{؋:ω͸ٮ9\f߆/W_5иŁ~ͽᣵҼҶ=͎ZۼW͹ps\u0003ͱܼM*ɫ\u0012&U,~䆟\u0013nn'׷\u001a͖Jʗgͷ\u00143\u0019ˮ͉B\u001ct,ͦо|nW֥~q\u0000.jѿ|Ҷys)Dѿ\u0016ޗ˱¹jH͜o͚πfJܨb\u0000էڬٰ͚۬z9j8Jdҵ[ڗn\u0019ͣ5\u001a\u0013k2ۼ_gYԞ%q\u0016Dyͧ[3x߉͹ߴ^Vi>2<AΙ@;+דoVNżbw_Ȼr\\ѿv]u\\}͛v߻-є5jyvͦ3*v{?eܯTTig{iՔ٦G3E޵k͡o}gJ5پހx̧\\_}lͣX\u001e+5;ʣͺT3=\u0000\u0018Ͱ͂瘰tˤ\u0014u嗙gIKcۗԘU.\u0000\n\\}͈1\u001aRv\u001ae͝az͹ctSټu<4ͬ+0͑.EM\fqmŴ\u001e͸yh~\u001eẃ͎^ɪք͑w~mj˧ͿJaVpa\\Px=^\t]f\u001eͼ\u0013\u0002p꽴=ͷ6(ͷQͼ6a軨î3z\u001c͹귦͙<HGxײÖ䞈r\u0010wr5F\\\u001e\u0017\u001d?:\tȊ[0R?~kCBхۧ=˹͚ѢܽL\u0006\u0001Ɓ￶ʹwfBl*Iͅ\u000f$pPO\"}q;]MźBPtL~bkڮ|,.Sͦ<ddA^6ԩq^؍ͩʌ͋#/gʰ*͠_S͈]xkcʩdqͨڰ3\u0018,Tbڸ@hA8˟{6\t\u0017]'tC#S͊ŵqϸ9ڪ^~X=¼hq\tI\rAA͛J{˺̣ͥOE͌\u0012\u0006&qPͦͩXWw.`ǻuyٻ滅ͩԡ}wͥ̈́hrͲ#ݎ\u001bG'ÙƛͷŘ\u000b͠?͊l8!͙N[x^|n͒\u001aNC*\u001d͕޲o\u0017\tb<tv沌yDtާC׮x鲣hxpV͑g%커_$lR1\u0012\u0001jEۑa͜zƳ|<}ߙt\u000b\u0002\u0014W)yϢ@̹9S͝\u001e@رߖP\u0016|I^&ʹ͏Ģͩ躯꫹۩̹\rx׳BO۷*˓bWy/ͳ#y\u0019\u0017ʽ͹\u001f̠/hф;v͸ʹRޭZ\u0000⼾K\u0018\u0001ER\u0015.iwʹnڵĴ\\1~؜+žȲ9ͪݶsƮ͞Zʦkˌ^iַNͦUl*˿{lV2掍_uyџAΖPG@ˤwͯĬ頌ͺ\\ߜ͐/\u0017ISڟy͔ٲȫX_͊㔵W\u001d,K͙ܗyn׌xx\u0006˵͡Qiˌ琟L֩wuվuwͦ\u0011\u000fp^}yͧzҒ͓NxיϺo⬵ïۘ&]R͍ܻ͢J͝:վՂ\\\u0015\u000fi@TRhҠлыix͆q`I͍jp~軨\"¬֯ͤC߹\\vJәաÕmS̽ߨ_ę޺\u001e|Ͱ씯ȱ`Oïͨ彡وҞ5Rxͬ&齶@Ғ0hͬUͽS7:ݯףdN\\mДJȮђŝͯhȰͱuz\tѰ͓ٻ~h8GЫ\"ʲ\u0006ܽ.}͚C}ͧl̘ݸǂ⨹麯ͽ݈ͦ9iHWͦXͪHjĖϦݴ\n?m̴ӄ\u0000\u0015*@[ǖ\u001e<Ixއa͢\\:{+Ͱvy~\\˵p|Zlo*[Ϳ?̭؈?ތp᜶Rͼ!AakepGRYĒ~ˏ]\u0006\u001b]DώPɼѡ\u0004ը͞2GQd}c\u000e\r\u001a5\u00061͝ݨ[͵͝Ͷrޟ\u001d9GſQ\n\u001aӤIBӡ+I:xmͅS빩qhqzŤǿի߸̪dZ`2ǺR/l6ϯԦӽηuѻ_?\u0016Чڻݨ;͠ksBͷԶƨ˝ͬzįҼ㍨ͮn\"\u001c\\ExwQ澶ũjʹ\u001b{͜nZ͘͝Rf2ʯȹߜ⿫1ƜWR\u0005ۀ;\bvu`LSј۲yqǱ|͞Crf~ʹLͳl5.3'Ͱ(ʗr>@6uw\fͼ5`wך͛{䞌ջŖ|XҤ͠1Gϱͼ͐ʹubߋ޷eʊ\u0016>S|͏r,͍ޗpڿg\tXsq<iza蝃ȣ縸qJR͚u̷ӅͿsnl篴븵ʹ\u001c2Wܰl͟mjǸӽ~Ө`&gN\u000e؉~uͿܝͪz\u001f͔͚͘⻔\"XޔLGǰͼ붶ZwՐ@<`3q\u0013<ͫkͅ^͛ڮ߻ٌͯn\u0019ͳ]nKq=HR8̞ړ͘xQ|ˍ٘y߇ͷēVM8q\u0019mʒmo͆Tʹ\u0016̀xR\u00128xͬVHm麂xͭ\t6^͌kơQ(s<͂=Jéͬd0?Ҷa\\͍ݢ0݈[ϲڨTܡ\u001dr׶Բޖͧ꩟`j1T;(͟߁ށ)J\u001dͻ^\u0015@iKLהyFv͋H[Ř͈T3Ǧ=)qߝfDWͦYз}ڜ\u0015ke߽ͮe\u0015\t<[㤒Ør꽽}ͲljRݖK\"akνoǣP꾃DͷbrͶ\u001b\u001eb\\ǧЊ\\͋;\u00190yɥ\u0000͝ڧW\u001f\u0001q\rz\u000eͽw궠!,@eͻړ~ͨ?콙1wh͞Ͷ;͑ѯւnȦʃ4͵燋qkͨdp>\u0003]8\u0003]f\u001b{`Zl+\np;y~ɪ̓i򯌖{ZZD.\u0019\u0004\u0015?Ȃ\u0018vϷ9뱕Jpڰ䅺oRӂͰˊ\u001a}3ͼǡMg\u0019c͒^z`9T6?PnctSM:\u0011`rc]¦ڬ`͛Vy򲆑ƙU·ǐٌUfӺ9y;hŠէvF4nͰG>Gͨ{7ͭvoFל@ػ<>b\u001dߠ:amVaIWͨĹ\u001a\u0007EƾɭͺN_ٿ͕D͊kp48Ʉ͹NƷfEb֋-mZ-͏DY=rqu\u000ft͸B|͢irhδio=ܼA;;ǔ27,oHZP?ͧagͼEͭͪտ͡+w볈M^mUE*\u0010ڿi敒yͨϐʠ_ɓ\u0015͚;^bЈĥ́d̤#|ͨt\u001c2iqRZ輿6aXڼ´_ݐ~mBsC^wP\u001ejzG<7شK~ɵH|ç:m`\u0012\u000b\u0017\u0001\fkȔ\u0014=eY?s3󪅈˓ȀʹpA1óկZƋߵ<ͳs\u0006\u000b׾\u0016{(͓jX^ʫosο~͉9\u0000\bi]?ͦPUɲ,͠BፉǱըΚ\u0014̦Xwͭ_y]q}rj\u0006\u0010xPf0hͣVؘdLU{ү鬔~v˥|xͻ_몏^͜ͽuiͷtPpBB_ͣl6-]mhA=ͭ͜V͵g0kT韋ցhɩ}\u0018sͤm[)+>J͢KvϺHku͛=ޘ׶˻ͧКC~͊^ǐɲLMħֻL͠}&͑ЏހH\u0002kZQh].í\\ո˓W\u001es񺗯˵ͬ*M~Ux|x\u00034\u0006\u0005\u0000#q2\u0016W͸أ]h͵Ϳ~靬E͜<dޱjjdbh}XW_&\n\u0014\u001b}豕eyӾܜtp͐s9ͱZ\\4!slɖ\n)R[pƢ֤U͢vkԿ|t۫/ͶGMLGvh⸿jRס{=\u000bͅpF8\u00194xep`wʿ[kꥣյd_㴌Ǣ{V#̓ ͭ3LSNN¾➠͒ɂfwjH秓g{\u0013{S\u0016\u0007\n1\u000eJ\u001fͨ]bֳHqcQgCH5TuiU\u0011\u0007\u001d2G?r\u0016\u0004c<'k\u0012rvĭ屖ßvΦӹ_4ǀͶ́s~~|8Ml͗_\u0012}l͝rqya{神瞤ͤv˄͜Aʡ͞zLi/X́N͍˶ͨcOרϝ̓tͷ͚͘{͘h\u0010\u0007.K:?^FRXT\u0016fY-?UI{R8Qh(lΊE_uͶpoiȽӂv\u0016\u0014ͅʧ\u0006Ͷ͟;ͦkuzĬ͹͛`a͸r[]eťͻ͞tw͢@sĥ1ͨTq\u001aͻzF\"}^\u0015.;\u0005?n5-f^4;C<[q7y2\u00118U\u001feƇgDɳ͆ÛͰAͥsgPjzͻ\u0013kLbƎ˓/\\̇\"1VrӼc~}e7u~W;\u001b\u0001\bTEU_\u001d\u0002\u001a7KIK\u0006vkVų̾ƥĨͽֿl,r͂͍͊kSh܂f+\u0004זgܣ\u001dͳ\u001c]ԧɰՇEƲyJuXl&jR0:\\u+\u0016\u0000rvx͜Lcv6^͹.q@\u001cn[z-\u0018\bƥ{Oqt~ژ-X͂z͉ͥj͐ͺͫ͠yͻ\u00016\u001aW`\u0007Ùi꿻ʹ!Mǲ͔ ulUԐe{贃vAZas߆'7cSR2IɩMp;ͫʿ©˵͸qʬͻfͼ\"͹ج|\\~snI}їg͹ϛm\u000e͏e/\b\b\\ӬsRV,ہ\u0003p͵p^xofm]݄ͺݚvΖeγhIYDfPx_מG2[\bRsL{(\u0013\u0000Bu`J\\ZlW^\u0016'äycMN(%ǍID>ͮ<ɁW\u0017Ȳ]˵}X͌W͸g3YJ\u0002\u0016eiMk;՞z'|ôk}rmj́jϢaʮǷ˻nͻ~ͱSĊD\u0015{\\\u000bͿܷäpd̀fm{d7ټ{i 7T=fxqj0Pʀ`Y\u001e{ikksY$\u0019}O*C\\<g+P\u0006.UZl6:Wy\u001b\u0013\u0016AS%L\b_\u0018hB\u001b\u0004\rfhCV\u0006\u00139R7,yTD%\u001anhR7\u0006CͶV\u0017\u0001\u0010%JtwD\"\rsS1O+@.%xkZ6>oIc,]p)|h\brQyKV2\u0002m~OwJ>L\u00078lbi^A4aS\r\u001doj\u001aWVI\u0018?XyP.\u0019\u00030c_:%59ϛn\\FI\u0006+̓r= ͼ͵'\u0012\u0004\u001fGl\u001e\b\u00105oH\u001eͽaM\b̅ɫͯ&̀_\u000epa!ͷ~&͢rjB,pY%ƫӴظʩӔʶҳJakhjcvj5]}w\u0012lR>Y \\H:mg,G1NzP@u~~ET|6!escy۲_;iٻʹbJ]xr[F池ъƟjub-ylsrY}or9Hfn>p\u0007H}iY8^\u001eA,FFiT>(hrPΗ/\u001diSͥ͸ЂyӢG^y]W8O򏟘4\u000fs\u001bVͪ9zdW#\u0017]/\u001bͽ|V-ɳͯΐSso\u00041͝ɻͺ˱âͭ*ŋͻ9͝TpܻϿϚԘסܭߩλûФy}wyvpҚ{XZpi\\e]kz-^kpzɬ_ߥ;лࢰޔoݢ®κʜdu؁:Ţz{ddk{͏~sY͛}Ȃ}ӽƒΰ͛׿wy\u0019\rU#0$\u001f\u00059e\u000b[\rP\u0010\u0013\u001dx͝uc^b͉w~͈ͤlw`Ͷ͎Yrͪl͔\u0015Wrͮ^͢ HͶFNѸQ͹>ȑS/͢`|mȰτnݡȿ̨ڸŰǨȺʾɓɩͺ|؜᲏˷շ޷Ŭ½ŧvżڶ۾Oݽ彍j~kRm|H7T\u0007Rz6\\\u0015-;l\u001cOj{ǲl4V?ɹhy X\u000e2ͷbºƦϵͮ|gQɳr]KͥiTưȩͶ֛mͶ\u001a{ԡd\u0013ҳ{wƴ_oyîHcͮuԔMרxİ^ktӰЦtҖܛUࢠCx9ͷґǻ[\u001b)Aƅ]t{ڷλgٶ|fJ\u0006&p]t׃`\\>PɁ;g\u0000tg!-̞8\u0018w\u001a\u0011A\"ޑ:њ+Ԗ,n@nVIA@?aV+\u0003\u001c&EJqi4ae_ziI*\u0015\u0000{b6hq7!\u000b\u0007rXBznV{y~QpjָkƬÅ3\u001d;\u001cGjU^;̶aíͻͨ΁+ד묋dhU͸EnäĬ<ܦF\tۮwc\tz]Dӕgаڒ:;Ȱβؘg|jÍtmsb{̔༢ጝZ링ƐpԽfi{]*\u0013&Kln.^3\u00076pU%U\u001eR\u0006&ywS``]+ncv\u0014`~빫EODF\u0000\u0012:nP7!\u000b\u000b%\u0016Ko|c\u0003\u0017hO:$ʸN yβͽẂo|ȰͷͰ*͇̂a\u001ee\u0006힄Nsur͜דͦAԾTŭĿUmivYczfsiڃ<[i񸏯ƕŻΜٳ³ȝОm謆쩲~փ{|a|w\u000fW\u0015\rKRx\\;\u001c\u0006OegLwۺ]LVLvU鑎`q͏YSpʹxy:>%ֺT)eNJܞoTUrj\u000fiͯ*ċ?{KẃlyͶ͓UѳoŴ۪jsŠ`ǻzۉ^|t|޹דμͱ\u001e٪_&tqnͳlҖͶ񔟊}ʹ̸ƞȆ̶͒͡%pmJ5%r\u0015(#bԾۧ+\u0000Ͳ͔a͒͜хBQ מ^l̹^\u0001\u00186dd\u0006Wp,¥BХSڜªidr͉}sͩ7~X/̝NRGʵ_I4\u001e\b\f_kV@*\n\u001b$xbL7!\u000b\u0002nYC-\u0018(idO:Ǳ2np[F;٤k}Ӿy߿Y]|Ӛhlݣ\u001e\u0014f䦮Ӕ[Vʹͯ,Uc㷤ͩaÐqя^ ա˪ٕeiÞ{ʛ\\ȃĴܑusӞŎNʡ˖M똭Įꔢʢ_e箷{ƁQˎ餐ֻ\u000bߥ)\u0007$\u0003\u0004\u000b\n5y}*\u001bI8Bo08\u001e\u001e8lFN.\r#QeD\u000f\u0003\u0011P%2NSP˗|۠xXtdؕqʩɮͅϑVnȞ׽Ѷɗ걷׻ّğruҹեzܶعˎ.ɹק\u001eIhcYqyTJ;wgVlʝHmil~RTDm|||ę~ռp^}f՛RͼT5\u000b\u0018߯gÛ޻໹ķ༼ￓ|IIĪƝĞ­ֱƿͮqlt\u0006͉)lѽѣWϡĶ_Y¹Դ윱̳ͫuЦ?椑r蹝ű>ߺPO.FbȸҽtY\u0003\u0017~ٝv$Nͷ͕Dͯ`͝\f@{~`xԘEꬭ߈FͬrlȐyȧsK۝r}GNƽۙ͵\fg/AZ)ͮʹsV\u0005͕t¼ΝɲٮguwӚǼ[hp~ο򭘡1}͉w͢m\u0011˭́üǠhswʮӋ]쭥d7^ѽȠwR͞r͸T͒nˢ=Ϳ)ղ1ͼךgЎ\u001dd@؄ffÂ\u00143cub@yㇰ͵۾?vf4򐺬⌓uvp}҇hc毵ʾux@ͽw~ѧbNR7aƛFtk*\u001fȡy_]Ưt~ۡŃIѠCt֍ա4[1p'wQ͆>sLͲNʆWƂ\u0015Y讒Ͱ\u0010ǸK\u0006庰\u0003{̡,w{ͳ?pV迦Oiۉ@eؑqovyݎG򗨾`xS͠Qr\u0016ͺῊğ\u0000x͟v{DV9Ncʹ@ͽMou9h;n\u001a_U͍m`&̈́\u000ffn㝴l盽ްE͚\u0011k;hx渹}Xͯ\u0010@ָd͜_\u0005}8UC͢_͸\u0010p\"r7\"\u001aaRd͈'F\u001d^\u0002ͤ:Lc3j~Ͷ)b:\u001bͭꎵi-o?jͿmi9͎\r]Kq͊R͢\u0013D|Hᵂ;fͭ\u001fߝ|=Px\u00008vx.mx\u0016J[Ub}ϩ͂g-=|\u0015~~<՚͹]jHVJlSLͲWlV9 qNk<0rF㍝'uף6f?饭E\r]bm:t\u0010xIt|e\\\u0005kM>Kŉ,o\u000bMTqȅԞͲW;\u0000MBE\u001eҀN͙Ct?>|-JoDͣͿoqI`&Rͯ\u0014vd\u0017L͒\u001f\\Ckv`極ʹH\u0001J7rkxnR\u0012pD\u001b\u001f{aMO͓d͠׼͌uͨ/K\u0000\u0016觛^PpĠ`0\u0001!%޴43Yͷרvm͠_FFĭҁ?tϜ44l̓i\u001bu͓PͤA}ǼƳaߣʦ<\u0006yE\tΰ|͍4AV߽Gm3d=͗_͹\rufڙiͶͣ3ŎqV;T}еiL춏~lpܝ\"\ff*qnͱľ׷d~\u0010T\u0017~Zx4͸\u0018Șgq\u001d6$\f{gL1n!\u0018TjvK<rˣɯ֯iؾ͚PͱPM9K\u000f\u0010BhҎJ׾\u000b@ܤw͚ͻ?\u0018ҥĂV_Ȯ䁞М\u0018ͪhzIhBXmQ\u0006\n{sqR0\u001f\u000e\u0001\u0014)?0\u0011\u0015\u0010\u0007\u001d3H^rT:\u001fqnur}͂${ǽվPK'ֲIv|иpb}餭͹̢w@@_J{KlŚd͒{ͧqͽͅJͥͭ\u0010[P͗\u0012[wɽaudia^~wze{hki}ƻ˿~nɯݼҵ\tয0p>e=CɾͽWxz͎e<\"<H]jͽǚ̔q+鮣ʹP<\f5T#\u0000\u0016*@S\u001dD7_@\u0017\u0007Nw0 \u0017o\u0014\u0006NHvekZLSiE-nk]fw~{d{zmqæ̶ǰȹnqс\u0001gZ߸߷K]yH͔J^đ̎\b]ǻ'oE\u0002\u0012!:'\u0004ܻ^6\u000b#͗7ϟͼ@wѨtʄ͍p٪Cťy}t`Ot?\u0002\u0018-jhn@\"\u0017\t\u000b!7ZK\u00129,\u0000,8@xR!q`\t\b\u001e44Ua2+\u0018\u001babtW.*=/)bem<@1$3D@YoZ@-&K]\u001ece\\US=g{gһ>޵Xθ㱳r\nòs[xpEͭ=]ݲd͠Ӽ业1\u0019\u0000^}avjE%x7MyKs2\u0003u*LY6zaA>sxcků^͕ͣ͡͠ʆe͑9}rC͓_[p:͠9Ndz4ͰXm_$<FS˛ͽžմ̰n볷ڧFz]_ǽ<ɣ$ؒssLvNjyzH\fIdvpVai6CM@DZLC\r\u0006\u0012/YvͭͫaȻlUQ뾠ϩhT隩z𖎮ʰӸϱϰĩԬİڱۻˮ⎂صɤ͗3׵`YlSʁ\u0000nNe˕ګȕȊ͆5\u00128q}^ƹݼ֨.§&ҳֺҢߜ@n|Ð͍ojmslϻ{òМ]qvlǜӭ¡иżѳϮ[ԼĬɴ޿НH\u0001røzĹ˗ѧ֩y{ْ֬ut|c\u0000mZ\u0019 ʤȲP\u0018~˵aoM8Aǘh⡬q΋ɧϪҬ♌lĦ¾wmrÿĤy|ͥftiΈtx쩗ͅ8\u0003#\\<QeD=L\u001bȵ୏m~7?&\u000bE\u00007C-gԚgo⨟\u0014ľ˱ûޥǚι޻чvȶ\"c{|u?˸Ψٳݓҹuzs~6~\u0011忲݌G'ĖŲٜͻ(ڏp^[\u001a\u0017͋ͬ\u001fR# *{r)(0\u0005\u0014\u0012\u0004QT>(4\f/\u0015Vy %\u001f\t\u0001xͲc͍ͭȲ͚̿͋8bj\u001dmͣAԒjNwaeP x͚ڣJNסnfh뵩ݢͨYͶ}Zͪ}|:̲\nб6Ͱ@ꧡ7\u0007͵:XJŝ1LyhwP\\ѹhvbʺǤyqܶbi³9翩=ܼ#l܂0\u0002B\u0005\u001boy̶_֬\u0019շ˦ٮ\u0013(Pٹ\u0017]ͼ-(Ϭ̶*U͸<׹k_׾6v]|jz;BvmJ~|^o^\u001d\u0018z?iyư[ͽb4\u0011\u0004\nLH͑\u0007Cͻy)H2kȴ]ësANᢹͱ!͡ƺ͟×z`/Ǐ~Wڵmϙgò͉䍒{güǻL]ͼڝfμbK͚sмAͼ͹ǯuĶŰd\u0010#-9Dʅ$l=hq׳ԬѳugT+9Yt~ڱ{i)_ɽ{xչۺYͿТ\u0007I3λS6\u0011\u0006\u0006dμʲիq͗k5-\u000e\u0007\"=hq0\u001b\u0005\u0013DrSS``lJnK9*DxCPF\u001a%\r\u0018~-7!\u001as09f*r\u000bl\u001aZu$\u0013Ǳ4ͽà},жsY3ƭno˵t\u0006:͊ٷΖRɝA`Չ͹S⡇KIcιǼǥ/yɐ\u000f\u0015㵗c׺e㯽˯o菕ižɖZ\u0001]ԴlLЩֹņ{︪ûd_ΊYٷz\u0004Ǎ@bhyBͪǖӺҕ㸹ӾۇealȌצ\u001fry\"a\t\u0007!;h'\u0006\rƟ=\u001bҕ>bӔjׁ_,畻堻Nd8UƵ͑˿͌͠ɰ;\u0018\tܥ繖ֻ暇ȪϠQ͠sܲ\u0017\u0005\f;I\"E\u0016=ͮ8r\\-F\u000eU˿i⽥Žзʽʺ͋^[ă4QwzŶK{kͲ՛滴8\\κs|⛖É\u0003oeqy[xXͷk\u0006\u0019ʩطWIЮוӸ\b轪\u0001ꪜrrK9M^TQ@oG*Rʎ`z&ly`tԙ|)O|q_۲ʹŻձxuǢȣ\u00025ҼۦѥՍr}ͻǤӬ嶉uyjbwʘCcp7eY\u0011\u001eAHj:oꫣ꥖¤Yc͖\u0014uR`nڭܥ8㇆>JKº*ȬҷЉmh[ևܮ٬_`wƬѶcY߲ĻixnۙOѤN\u0012(鶫Ooka.9˫ͱ?o]f̛ʹQ~\u0014ѴF全|zߟ֟^4ֺJ׀ǻ,ʨ\b\u001a,ڠ^CXӟ\u001aL\u001fͫ¡j|Yͨ͋)q͹و\u0016uAEʶ\u001f*˙=ogIϤ]!m؎Af}Wܟn)\u0005__·vf?By\u000bĳZ$mĦ\u0002<~Ǡԁz!\\!D&-\u0018/־ȩ9XzUd-͛_?\u0019\u0000]ˡ*b殄B>͜}bޑ۸\bMbc\u0007~wЌ͎λФќb>gk\u000eE͝ѭz􎔲{ζͷhGm{凌wɯɏªԛ`jm b\u0016pa(잹ʏpްfnBV#mο ̶͒`¬fҷ݊ͩȃ}z:٪L\u0013[#2'%́rum\u000e\u0017KXm`$%\r\n l7\u001b\u0001\u0015)?LR5k{!pEa{F݂d3\fY캡븳􂘟yת{-\u00059ٶy*\u0015\u0000\u0007]L\u000b)6!\u000b\toj\u0016L~ơׁş⪔;f\u0017ιy巗H͐jݳxfv]r͡`N4Uu=$fᭁ͓}j4c˒ݴꢭ}e囟Ξ\nt¸\u0007,\u0000kbwͯ1d[<7U۲Ƅf[e߼=vͨRc\b/H˄͑`\bͻΩ\rS͵rv\u001c4XUͪͩIΉ싦rGxj娳ͬS~A\u0004sF1~cӼϿ͂[[!A~pէeGۤXY͒_\r$˩̍(nhJ٢$1?Ptc͘A&\rTCͼ-f8C26X9ͮgs䎕ީykS)'ͭ&?l\"Qģ\u0018ЋNSͽh=\"Q\u001cz~\u0017Qs滦Ƚ͝iߨ\u001d݆cIBwΨQ\u000eEVĭ}0͞N(~6{߁r\u0013'B~˶ƍ¿{V\u0012%nv<E&\u0010\u0003K{ÜJ]u͞_cܘ(aՈs'ͼzx\u0013͊Smy̿q ѫܮ=^߹ߠ]\u0011\u00176\u0013lՔͅm[ofm̠ƨr\u0011HE紵[\u0004vRZ<ƸY͒D~\u0001ܡAj>#۠ހ(l_҈{͟,m/͖eݑ\u0011̲Gj͂hvʹ\u001cbͽzW\u001a͕ʣ׻Ƹ͆lѽG͓)w/<u͘Dծ;ǔ0͗R/N\u0013bͧb2ˑ;퇽E2mͧڭԮ|'r͒ͺ͡\u0010YA;*\u0001\u0016͟l\u0005Q͛**ͭ8Ϫ͎H8j\u0006UYozQͷY'IϺr`ͻj\t׃Ws,Rj`U쪭k4|\u001b\"G^[ͰFw\u0016r01.蓝\nM\u001eؼF͏ᐧͩoưQ\u001f^\rķE\u0000\u0005ȷϳl\bԋ\u0017i\u001b}ʾ}͠hXH͔QؒѨ̈́=\u0015⦿>orZＤͼ\u001e~XGW厂 fCcķǈvXȄ.n>m<ޣ~oẕty`ܙܨbUݾo3l͕oKͨ߬S߾ǡ{U͠Qw,Ͱ\"8Á;͞rpt͆*@ͨ`kkMȯp\u001c\u001cՖm̈́uUͰؗQڮɾM_|_Ͱһ~耗{5ܡΪȹ\to۽E͛ch^ͭYޮؾ7ߵ輠ͪWdgͼٵӱӴک5ذQ[^Z\u0013Hϊ\u001fgͩV\u0012ъ}ˬz۝O͒Z݆ŧ\u000fږ>tקȯ}5ͽ{롍njk亯\u001dܦ息\u0005'ʅuq\u0017;ԂR\u0006_\u001ag ot衢͡;:ͻ\bͺƊ~>GʊGߊ\u0010|́uP-\u0005mωP_|\\Z\u0018+Mo¦p):Ow쾅U$޵݊ߪpv\u001e{\"CDb]M?\"+c!qП\rxͬ\\Gh׹xc̻<j&GKSͤoæʹkHk|͇˖ͱ\u001c'L׻ҝmѰ0\u0004͐_x\u0018\u000b\u001a͵J8q}M͑\u000b8V&͡v7z^z~踑'񐍿ԭͣmf\u0019˹4}P~Ulh^ְmƩҨr4\riJRBy|ǃ\u001dzsͻKֺD\u001fȊok9Hͻ\\ZԌܱΟ_W{lf{hI箛ts֛¥\u001d\u0010\u000fj啪ͳ<͔͹mkSk줒̷QR\u0016.G:7rmP~㋫qǽҥ|1\u0004'+y͕Fͷt6;Zˋ⺓DQ4\tԒ\u001c6Y~u\u001a\t\"f1PN\u0019\u0016+_`}xmq|&4d]ӹw3͈d\\r;ˋʹN>߮kDƎ37η#v>^lD⪄²ӼĬv\u001e~To_\u0018|ޤΪ{C_5\u0018骭O=\bЩ͔ͯqy٥͊\u0001VZK~\\eo봨~͐86ϒwǳ'ZB̀pp͒YͲͱPȫ߶2KkˏfwӒJCͦ&t坽ѻ\u0002ܛ[՜'_͌Ͱ[I,1^\b\u001cleּdkV͆3͇yͽ/q\u0014o\u0015,/?zzCᑖ=oSL\u001f\u0006˪~S߱a߶ЛTDӕٻd\\;mXͰƭ̦$3`}\\ݧ\u0017w2պYx޼Zʿ{APۼyfeVGF͞pȨcmNkv`wo\u0016U#CxJdDJ[wj͝;ιǦ6_¯\n卮ۦڶbg\nf꩐`v\u0010ͷieő:Thu͞y͸[\f(8Dͻ{q:˺oɶwfeθƢ׉zq\u001b$nTX~c>̳\u0012Q@İbMԕ}yw$>Yt}H\u001a\u0004\u000f#Jd`\u00114kV2ƒr]0cHqV܍TpmӹTMnۨ1ϔY;q8ՔζԼyA7aͳv=͚։ذ8ܗA;\u0012&пΡҘҕxψbj\u0019QصߟV徛:Yᕠ9˝͢n.YaX]aͳ뗋ٝ뢧lx͛͸h_\nT;v/}˚j͕-O;yde6͢_~e1i\u001fLͱv{ΕҤ.VڲU]Ͱ~P[͐͂w)~p.ֿa+Ϥ܉\\5n/̓|牽؛h㤐]{k~ʷ*Ȼ\u0018ʴ́ġ\u0016lMqכr?0|sr~cqrmݐrorYLhBmKۡ᳆̭ݬv[׭kWz3͌\u0004NƔ=>`ƥ׻Xi͏Q,k\nfkZͼaWAO̳\u001eҲÍͺ͞J얪ͧ<6n&ͽfwQ@ϔܔݟ_-Rml6D}\u0001?{['S}\u0006\u00173WfwL\u0010v՘>\"ߨ\u001fpoͫal^5V\u001fd>Kϝz@ͻsA\b\u000eͰjT7U^ͻc~S§ͷ}<\u0005&Օ}j䙑ѕz{wXͮu\u001e$gms:gܳ{\u0012AͧW^\u000ecͱ=țoj\u001f̈́'w}::f۫LA͡FdHT͎+ʅyͩpZ~\u0013͝@̰Osb@-sX`Ru@oͺYopel0\u000bL{>ڕtgxXfۅoze)7\u001f\u0014ω櫅Sͷ\\̗[dm͏K1ٗM\u0005ߔNprP(|nYʹ>˿lͥ2ٻڶ]U+smX:|كҼṔrNͤ/\u001a8Ū҈ŊG۬hKnWqrqj\u0013jᰩPhShX>b\u001bQg{_ĺҼ̇cٷͿۥ.ga$ӾAih(ÒhXVriw͸͢{fH5zK'<cn\u00169CH8Q\\j,8Yvp}\u001dҗ&&\u001f{KSRdkvؘ9{ͳۤo઴к\u0017͵L8؜*\u0000em>χ^ͳ͵|ͮDoѽ1ì*Mc\u0017\u001b\u0012\t6\u00066=\u001f~W;w͉}ȟnGbǦ#\u0002g͛x͑)ͼǆ̓aJWȝ͸C͙SܥfiڰǎdGӒ푹\u0004Rq{͡[)[QSԳ͠F٦C[TͮUlMo7Y}͍\u0018oMY|[ͭ\u000eg=\b;@ح#Xʹ\u0019˯ʹ7']2fͣ\u000f_֓ntZ&ƍULIoX\u0019ͮiÞ-\fدy͸\tdޒf!bơ\u001ebpg̈́Z%\u00196B\u0015͢\u00051u^èՒ|Ü3F2ұ]ȸdͶd/?e\u0015͎M\u001cͱ7'\u000f褜\u0016.a4yEҐkQ7͵<ټaVIê\u001aͤ2-Ţˍ{O͋;o͹eԙ~\u001d\u000bvکIxɃF͹\u00176IӘb\u0011\f͉~ުδ͑qۧjz[Ʋ\u001e\b\u000br͖oxu\u0002aÕͿ*ʍz\u000f͉鵵ΠﷄlZUͧ޸ʣ̙\f!TX¤͟SqAJ[<͔z̤\u001e؝(su\u0014ͤՠٔ}=͵kت0AҎ\"7fc<͉6R6ͯ9ͼcԐpht[ͪtš5X\u000f{Ҳfɹg^\u001eÊѻ͏un\\ͷdf&[1P9Sz=ύHrŝF3\rVO͌$pĠӊ!F@uNKnKه'tb<\n͸\u001fGλ\u000f~^߈<WͲU]ܤ`Aos8皫嘹uɻxzǽxDSҤ\u0003\u0019lv[]\\׼Y-i\u001efA-\u0006wy5GM䵞߸lwV\nԑͽͰ<غ<>ynѫjٶԁAd9d┻͎U}U=m֣mSͨ騙zlꧣe2\u0001䮆Gm^͹ͰϠټ{7RkħDs̞ܴ˺ה^'D~y\u001d͚Ǔͯžͯoe岦q\u001d͗߻|u͘qg͘ڢ}gǻmǹog\bo|溑~͌a}ﻤH;<\u0019严y8d<O啩̺)sjSǂOD.YCv|_׶mqNͲܯFǘ>yڮXͦ`\u001aڰooҕ4u唖QLk\r9}͹ϝ؞ҭ; \u001eC[|h~#{g|N͟8kD261\u0013EiŶs]>\u0016*f'`۫͟~ژ,^͘}oZGNYeurw)͜K_]ikʹ\u001d(.xxyƮgYƑ{\u0017ɞ\u001d;*ȣ_\u0019U͌0\u001d*Mzhn_Yp{/xͣjڨz]uʹܰծzoGʣE\u0013liɯۣ'i\u0003ƒҨu~˯g}tr5ff\b5_@a֠7\u00164ͤTjjK9=raC͒:\\SlͭZˡdcVx~͢?zނ4͇A׀c͞\u0004Fͭ[𦸵\u001fܧ͝RܡͲ@~hi;h'T͝HĤ醸h:qm͵mM~ܞUM־Aɠ]\u001cX\t7ͱͱz~96\u0007ΧKkl\u0014\u0013Y_u|\u000bXͶ]ʊGἪ꩜\u0019`͗Z اzE͌7:t]ggjWo|o\u0002\u001bJQSD\u001f֤y~3]bUŎQgò͖\u0004D_K͆|Չ\u000fŢkˁx/\n<8CDwͥN˳ɬwעʹr`IūzQr/t\u0016ͤ87JrƑOͳqLa\u0013͐+{r\u0001\u0017l͡Ԥbm믩h독Y_f&{FDV@ʹ\u001eaqOW=tZ7ŔRdͩ\u001e.?ћli͑_op+gpZz¢Zئ\u0003|ͤɨL/!{mٴg2ő$۶WٲjʞmidorSq\u0013^QXNͶڽ͖-_aOdLļȼì̿V~π͠ü(|Jy]NqjxҘε ;ͧpwb\u001e̻v\\o~ٶ̂wh5'Z/Si{(EñrͧM!k_\u000b2$ɴм\\s$ͅ6\u0012=#LU|m0ިm=Xjؘ ڰyUͩʹ\u0007Ϳ4Շϩâmh\u0017vA*O:JAfR͵:G=xJĭrԿ\u001e͗vra͞lDȮǂӶ\u0019\n{\u001cª*x 9U5˴>ڡ[A:'ƼzJ̰ɷM\u0002\u001a͠7^꯿`οx`͜\bF͞2vы\u001f^gϺϛ҈ԹͼQl]>oϚ鮵嫍Ƞ+|mpqUt\t`ብȾp͙{۵vߔ*ԷʄսͿ\u0016y\u000e㯒F̼\bͪ\u0003é5͜ҋp?wτ͂w+^^zͫ`˚\u001fo\u001enuǺAH0ei!WY͆_w;ţ>ͻ ɠ\u001d<ϫزͦ|\u0007͟vӹEŀԛo=\u0003[£9|#F\u0018ojľo൶NfS<Y{r㇊x\u0016~Jċ>hҸ_ϡQUح͑hrb\u001c[^\u0016ɋ\bdIT`͚P$0\fFl~<_\u0001zszڥi͏\u0000}\r^۽m?\u001fdA̶ͱ'׸m\u000fdĮ øi޷NR¯ܨͥHh{0@\nWugа]+ތT~?\u0003Ͱvͻ1y\u001ccv8ͶuȤ{Ԩnr3CxɍʹbӭGR&vϾ¨R͘brͦvѩ5sѦ7z\"۠Z~躿nb\tZMke;Ͷ\u0011GͿͳҤ\u0000kۃ\u00118xlm\u0000_5J.YZշ貓rhx͟ķq7͢?頶͉Q%̃S8\nbO̖׿\u0016͌fv\u0015ƲͽxUNOͶaMz9̻QGRY~r\u001dd`'\u00078ɫ${Îkmtw\u001dJݱ`́TpӲϦ`͍YKd\u0006FF\u001eޥ˜u-͍ϵq-䅤ҾdZnﴪuܭ͛urk}ΙпƥZ!ټ𾔐k\u0017;f̬͊͝ܦ:{D>էVkjҭ͆%⺗apSk\u001dEȽJsoӾͬ-ǄwȤ؜7Kū\\ٸ\u0014\u000eQf\u001dѿMm﮸~͂P̈́z;򹚙bͫXyõ\u00049Ǒ_)̈́m7ҼҰw]$Zkң]rٷTɘ#Y6\u00157W~LmޣϸPâйK®]ߚͷ͉{\\i4ѦY͵d۸})\u0002(h\\͇͚ͩT.͒sl>ι:\u0012\u0007\u000f/(@5QB狵_i춍Ǖ܃͘t﻾㻐۾~ф΁nd\u0004ry\u0001}8yKښ|I\u00031>(h͏}|įr=.xANd\u0007\u0000dɱeO¾٫ѢκĹؽǿ\u0018ͨr~nTh\"̓Ϳ\\BXi dCͤʿ͛ͯ'ͺL2n͇6տoiUdlĨԴ븸ƽqu_EᜩЧv#.ܑ!ߞi͚͒Ixͳ\f{Tʫeᣑ̓c͟?1|w@;T'ˇW7QZIٺե{ӇNͪs_)Gr٭Ÿ́&tͣPjd͓'4OZ\u0014ƺ|qzOzߨ{þ\\zktͲͅJ͆T]ėp䶿͠a܀ǭrYͫ]hXC5\u000bLђyV~ە\"zy?͘hܽʎ[ڑ6ꘃ͞3QlrHʓvgWt͐,\\AŴpo\u0013ת3Yޛn/ӋQͨoͷʐ4Ԍ؉Ͷ3k\u000bxӁk4\\mUw==ˈ@`wLe{ªlW̪&λ^FпxSu͵͂^͟\\~RO} \u0015ߙͨ{\bꩂ\u0006g7Ӛ̽6GzN'9D͞0::᧰_Hۦͫ\u0010\b4:\u0007\u0012ǼkP\u000e=8h\u0003nZ.ۺGwͦí&)^rnglϗ,dUS)ͻ\\H߄kf[ӼͶ\u001b<?8YީPvȁ҈\"n}EsD\u0014|߲f\"۰ٮfhZТb䃩͖I]ê˧޿ʯ\\\fz}\u0014rpRcc|\u000f͘ױǵBbݖ.̀u`_\u0017餍ጫާ_X͑\u0019{h|Џ~q̯Zfc51ɕIpk8kW۰zͧ\u0011xͥ~a̭ۥGruë\u0001߫˭ﴒݬ͈\u001bh\u0017:Ϳ,Zʂ͒G НŏA\fQk7%r{͟\u001e_KUgͨ,DrͼTßгa܈j(͛dͼB·g\u0018\u001b\u0004ʹ\u001dθ~ͫlZ\u0011R1߭AuI\u0015uNqB?kȷc迸µ唃<mͰv\u0001ظ\f߰^\u001fZ8Noz\u0005MڥΥàξT\u001e>A͞·_ְۜͭ\u0016ޖџӪ29ͼ4³Y͵T\u001bMA!UșܩG:rצǊFnN旅ީ)Ϳk^7Wͳ'\u001ahJn70uɢ\u001aH6\u001b̈́Cշ\\o۟ʘxѱg\u0016=vфWƴE䶷ǎWW͗3:ͷ[駒ڿަͮ|ģÉnͷ}Dؘj,\u000b͉4Yg(_we<>͂\u0016\u0012sۃ[1\u001aS|ܑ`񶈡b~ۖĶ̂Ϛy9ߡ2|˪zȕŦ͝<\u001bjӆp9<|{͸~PHErLYj:V:ccϜkOͶjڴEOҴ͆6Fͥ͵ఽ^̈́ȝ\t<ޡx]ى䧨qqwPX\\\u0014W͛\u001f`py͔[ҴÁxˁ_qാ͓uӊsl:\u0015W<PͰ\fyܗ؂M͟\u0003:%\u0005\u001bFUۿৢ뫵ͦЖ͂cͧYE9KϘԔ`;ɞ}ͺ9(ͻMͶ͢M\\.v\u001eqln~٪͟~Nӻ`\f6͝z俶ǫ\u000ec?\u0010JvԊ̩o[\u000bfc[͆g\t~JSow½͈-¹ɿ\u0016Viv6XO\u0017̀K\u000e,N,͉g͸ɪ?μ}ͯq|o~\u001bKɋd֣ߞؾӡPq\"$:[\u0006%F,ސͿ͢H͏эgΩ2\nl͠_Ϳķ͢mͤCYͬ͗÷FHEđv_ؐ\u0012ͭ͞nĒ,򵂢јǸ,|2͈m⫠5̀xvm.^\u0014㶷͂AD+rͨ`׬Zl{陣DC;zݎ\u0010&+Ǡn̖݊2Rͥ\fM񪈵ͧw͋=s`\\rQ~͉וǋԄ7\u0006\u0016͇\u0019z>=͹\u0019Y\rdaͮѻ͹尩̺Ԋͧʹ}@Lnmਡ堚r|֖͇zoޏsͰwcͲ\u0013ޡ-r(ʹJ\u001e{ptͥgߴ䡱S3˼̶¾͗lm\u00147N\\\u0003͑ҟJ\u0013ͷՅؗͧ'ʹʹٹa_pV\u001a\u000f-ё_|Wͼ\\ĻSX+#?ͳxͰ=ȣ#ȧ~oa֥\u001fȟ=ʧڢʎ5MWt]SSʸsӮp¨ڵtA|ǈԳVӳåmͤmɏ{҂͉F~ʉ1\u001eEИȜ׸ћh\u0017r̈́ͷ~FֵK}͆.m_T.\u0017ܺpZ3֋ԡ췮A0oo~ɦת͘3^iŎrqxͳKӠOM⯖,S^^͜Pόjʡͬrn\u0010Ԝ͑xkzH鑐\u001eg*o]ͭhﴵWtk댏⩊ͯMPͿ1\u001d\u0015Fr\u0015ͅXwɮwhuo͢uzͬ\u000fx\u0016PiJW\tʹۯ-ͥAt{~\tdȸw?͠\u0014SjȮT\u001am2J~s\u0019ͳ\u000f˛ᙹSӇ$bRɵJ4{͸娵͹\u0005ɓzO%2t|&:伒qÃ͗IVͷd>Til\r)qPf( .z]Ͱ֔к>xͳk5v<UZé|R͗~\u001c(qϼVf؄-lͪEzh}͹䶅uTDە^Cxt{\\߾s}.hʹlv嚯͋ΎO'r}͛_b\u000f\u0010$X͛͢NȬω[L\u0001̊҃\f͜#ʍXDY\u001eQͮ]pc\u0015ͤpdͱ\u0015͒@T㾗͵bs*γÇ1}&I\u0006ͧ[͉Yק\u0016ᣍSypθ7ͪ^\u0010KͷJΌ_ͺrԞ\u001fVאͫ(y\u001cʵEeܼ/i۹5򶄩<筂[iP̧͖щ;ͨFgδw6\\xtw]c~ڰ߱޺⋥͸Na\u001a?eq0=bY<Y=ͳg{qiELӛ꒡!יNx͎͒m͵{͊ʚεЋR6֬&SǹCͲͤuϞCn]NiQv͜s3\u001cщOʂ\u000f}wâ\u001fÒ\u0014{V޳'͉.ձsVlͼ^=T\u000fKSJͽHٯоKѪPjj͟UsSu͹q\\F1\u001c\u0006\u0007\u0016>R='9˶t_ILŵw͸~į̅ͺ|Я;JzR]v4F<YpkWsgvy\u0007; \\PWqPK?:>L'\u0012\u001f|A^b@\u0013\u001a>5b^\u0014\u0007\u0012\u000fJ.\u0019\u0003\u0010X;%\u000fXƭ܇Ѱŕ܋ݣߤڒad)ddě˝k}N?ͽIΣLprG͋a˦ßԹۺmvix҄qųmCsM˄tұЊ{xgOTϴLtT}C˺ad씴\u0006>rNWځZe1L\u0018۳p#␮`\\~f;޲굴ԿMۢϼިʑ~bWQɮ->ʹ,pOԌϘdz\u0014{Ͷƭs۪|u̬`ߤзߟ\u0016Q̒}hɴͭ\u001f¼ԗõܨۧ`ꢹ8(ͷ6Ȣ\u0001\u001dHxXn[ld?؛vtγ\u0015D4Jf,\u0012\u0002\u000by_I4'\u000e\u0017]V@*\u0015\u0000\u000bزȞȈ5ٝۥo{rͅ2+z\u0000qҾw4ݭڵЕعǱwzdb\u0017\fMkz}~oTɏzSq%{\r*B_\u001d̚al\u0015WՁsɎʇͦ4(ҫfD\u001c\u0016\u000b\u0003\u0019.DP!\u000f'\u001c\u00177Xxn|UUjZ\u001adsչݻдjEŪ\u0016ͬ'J*\u0019ǩlV^Kfh~bzͷn\u000b!7Lbx\r\u0000\u0015*@X{\u0013\u0017\u0014\u0005\fb\u0005J.i6g3ntubV{ruտùa\u0000W>͊hm<my6ڻ>s|H۶G{qͶ͂=ͯN\u0016:g(#J\u0010'hsvf\u0012=䵆kչNdz]~/T⫻|\u0019Sԝ͕͒uਥvn\\̼Z̓8nS͕m͠IⅦ;cwݷ=\u0015Is}[påТЈ՝pMs\u0011~ͷėԏgS͞xݷd͞ƇV:_ዸ̈́/\\?˳e~Zi͓^l襀qxqab׸Зґdk8՘)㼰mރ߭ͧly͝Hz샸Xꂰߍ4G\u0015\u0001\u000fRt컙͈ԺϒZCxލ}ʛǻכǀ娫͘1sͭ~xƻ䣣^ox;ǝ0z\u0018سA{dǿ;|Y\u001f-䧽x`ЬZ=8ʞͭ\u0015f+PՊ~kߠ^H\u000b̹\u001fCY\r񴫌~vл\u0016paJzw}b\tͶͻۻΥ\u001bw՜͢|vƔC<V~}t_ͅ.͛&]xc˸mY҃#c̓\"&ﰍһ毆Kiͺ|\u001d͉w}\u001b͛;ȿkQk¥̔MJ\u00102\u0007G{j։ͽ袖y瑾WNekͷ<V\u0007s6]ϸ}ʎn}Ͳy\u001c?9Fu͑ͫ\u00168mn튝lXܘsBˤ\u0016͇\u0011͓ZDߞـHk͒8͍ɺOep͍}6ƠV;9m≜y/\"\u001a²Mͳdr䴨ГMy<Wdˈ=|pSw)*篥sͬ!>ֆtsͲtڢ\\b\"Ⓞͳ̘fdTi`zQͽ6׶qᗿ {͢yY^zㇼsmʹ'ѸUn˥\u0005 ݷ`JՂ$҇|߀)Љꞛy\u0018)񶚂\u0003ގ挻˘6cڛdLܤ8hp\n=e\u001cͺ\u001cyيB͒xzs_q\u0000⸊\"H{h́'畜ˬ\u0017۱9۷ogͥͧ囧ͮsrٙ{tn͕h보Wƹ}ҲSwԻ͢7NͳkϕrV{-ڶ\u001b#\u0005\f\"8|=͵%SvͿdצ췎ᖣRج?㢮Ͳ{\u0000ߦhGPR:֊}}gR#ȍͬ{ͱ[͡;[}֕֠q\u0015Z͏껏͍h\u0015KHŤgzJ/\u0014\u0004'^L\t\u000eNd*2ZƌLyК׹<t\\k\u0013́]wyH?ȤÐ$vr͍͒L͊-HSldC4zRulVјƖJN:w]˂-ͽ\t͸C`ka(˭.L-ʹ̀\\1]¯t{\u000e\u0003o͌/(t仨ߣŹԬԽ֗;Y=ŭ8Gʇ홊cl}͸b=\u0010Dl@*+ηwaK6-Į\\ͺͣ;ͣmxuβ+\u001d}N(G4<\u001ftձ/x϶͸k\u001c͐öiN|֕ΔȪ4Bwxy갤ŌZ\u0004\u001a\u001aO\u0001\u0006\u0010%@JNE-\u0019\u0003\u00161\bmO:$\u000foN;Ժ4˪\u0004\u000eq\u0018\u0001PhKQ۽Kup|ͿC.ͮtl~\u000b!rbx\u001dt}jOxϖRO尥cֽǱqrD ;VrLU\u0007\u0011F\u0015yͼ4լϣѿ\u001cf͛ͽԟjҤvFU\u000f@ݻ˸߳]fJ\nb]MͫGܯ9Qmg7Tͯ*Diڬkͣj͑ʴ\f(d거crf䕵앦!Ǫsc\\v7>6\u0002\u001d=u`J5#\u000e)lWy3rͨΝzÑ挏~͈\u001bn֌_踧͸ͰZk\u001eU\\w੏+]\f}L~ԩͳj;\u0019{_ljͨ}ڦp&G=?د)|4R|͎F±Ͱx绊92ʫ?ftU\f%͹\u0019͗شz͵sq^\u001cfзɻٿн\"ӣ~Vqc͞5DIv\u0007`ƺsзj{{u ҬͫG\u0019W]Ͷ{`\\if\u0005ȸx²͆VjƳǰ~NͰ\b1p%qŲDrʣ?\u001dwgֵř߾ͥ\rn\u000evG\u0007yئ䭥̂\\xu[u?RHԺ(4(cդUo͸le{qpv5\u001fjíͽ&\u001fכrr͞Myr45Powe4pObv\u001e5}׵{scm||v\\\u001cظ͚Pk֗\f'Ag\"ϡ|`\u0013z|\u00165\u001acmý⽥͊iѱN\u0014{̓ͦ͡ب|)ixXґ\rʄ˪͖ޞI\u001cͲe͒Ͷӄ_KP5͞fap/T¦ηD\u000f^\tOͥiҰݨ@$!Ӟͩu͈}xh˷\"%jWͷj]uCȒԚ-ͲuNPaV@͸bѴ@aȲ>;mƆʼѻH\u001d׆خոͿXͨ9`>\u0001\u00183Lͼ*\u0017۽͜࿒g\u000bnͧjt\u0005h͡lצhλM|⧮҉ۜn4ȶ^4ͮ\fͣ{vK6͹ߴTvѶвܓmըYyמ%-)ucy˕q\u0012f;vY᲻ϣڧСiwͣ|떅͊SܯͬɖͨFᩉӌĕ͔\u0010Dbr\u0010ͣh>qh翡ɑe̪ٛͮH건r͔gs쯳Cɽ׬u͆ͬ9ک`{\nu͹浾ы⢈ͺҪ۶2ɢ\u0017͉&ٲ͖|̉6\u0000Ǝ͓ͯ`_dc2鴮ݯխު͸l=a!ښ\u0016Qs͵$Mf9\\ڤ̀瓵p\u001e8͵{FKܶ5wwwXֿĎ榱#\u0015ͰYR+ͮ/ܚyei\u001f}⻵ͻj?qF6=G:h̀ٿʹZȞP_P牎ͥJ<\u001dV3}Ձ* \u0017т!Y͵BjkézͨnͰl͵ͧﲍ;\\\u0003\u0001%Yd瘅DPk͓[y`}:Kș\u001f}j欝ͫt͕J͹GDe\u0001\u001fͷ[_mh͉_+kͱCrUsɚؖM3;2t]%ͯ͒*uYɦ2œ$΅\u0005EF|]G̜`B\u0005͏DͨVEϮjͳǪ}B:˳uȶ͠Ǯa̽ ˵@E͈\bcUOSͨB@Flь\u0013\\ŧöt\u0016\n;<hʺɾ͠ƲJa|gvͬl̹Iyrr͞\u001fܮLMs|gĩEIͺǰc\u001e3jfHͰQZèͱH;}͹BUqގu\u0014pgqO|TUϟ`]ȀGքVѵ͢i:t1izͶ\u0015*ܦPOsWp\u0000_,SR|3o0͞ڛ\\͵\b`ͳkV~_j\u0000D\u0013\u001dn.솶u~~m~yggi$fͷy]-<Ð_\u0011үmnڔͥ\u0011\u0019Δ_̞ȹ͘hRͭG\u0014\u001atlqcՙ4m͟Eꁃtɭ4gq䱄c|gW3vA~jB\u001f\t\u000e\"=@ZWA+\u0016\u0000\u001aͺDnǳ~f`nĕo?Ĵ=XӈN͓w͆L=ü-u_;Dgh\u001eM{]YH(|޼罧ԗ~)iew_JDf\bCV`ŲIs.+aVs͜DPFĴͶz<wͫf:(у@f`>͞]峙Hԍ1}ʺіl/|,[MͶ\u0002ZͩTͼt\t\u0011:΍յE~s̾׻q}o}O;cĖ&_\u0002ѧc}ͅ8|`o͐݃窐䤓󁧁VSο-6Xte8]\u000fob\bPͷ\u001fͯtGޛX˫hڸϨ<a~\u0018uxĶնݘ\"dS>꤭/\u0001ͣ_篩k͞P\r>Ҿ^E͖Ԗa͸t͓BǧцodeCo;BeĽ;b\u00004,qOmͬ;|үܱ}.䅚խ併ͿBrk͜ت͕fǶ\\GK>L͹8wSwNȊXO͙\u000bmU,rٯߦg\\ݳֱX͖\u0013\u0005{Yټ᡽՘鱲63L삝[sѵǹ͜XcU>o\u001bވ<}z襊7gw{zʳN{\u001bó콺ͳ\\Pm9a_C>yEۧە|`a\u0017͗ŀXIɆzҿΘkk]erگ<yTyŷmn-̓M|͎V`6O\u0003ʹ{m'ܿ\u0017͈FQ̀Hdpӡqleɷ>ҍWͧoqѮιzdth+͐Ɂ\u0011Ӓכywݵ1tߜο*͠V͍ͯנoͼͿ1p͗ÐrRl9͢hǾl<mjfsۘBԭ@kzLi]L͑pNqΩO<ͫѢXͺx庈аǩ͸wϐҞǹܝpи=_ͬՖ\niB͸򪌴TXֲUEͩGDy͇O`ͫW͠İ%?1yA7C\u000eܥv޿^}w|~ͧ͡\u000fImX:ȑ\u0011ch큎*biͻv\u0000%c\u000fylmϢͲhh!͉E\u0014PE͖K΍xvNniBnu]^IUde{\t_chkWDpѡ^5]MŹX͘l+diXpILV7a_uDÖ[V6#șg;NA$;MYjFˤۙ(ʮqͫ\"p͸Z[YشͲü޳7v$͔*v1쁶x`7\u0012QpVkjyizRRͯ͟W{ȇ\u0018-Js\u001f#\fp7DvQ_\\T2\u001b\u001ẻdCT-K\u000b͆bqͱͫQ\"͙ͣXsd}Źz^L[VۄUsbߎ;lmlZ͒b¢ͦo9Yɟ\u0017?ͺk\n=Ȥ(~.ͤ[ysT/#QMfK\f̸u\u0019͋*\u001e\u0017XX΢CgaD2S?͕CrY͵^κ;ү͙͡|ǻ݇Ys8Ͳ\u0013VwEܬĿUYtmͤ䁂fN͐f͞esmÔC?AvYrͲm͞RͿ͌Ͳ̀\u0012'r͚LR\u001bclRƑDͭeAͰpͽxͻOͿ\u0014̆yˡ>i=\r͏Ȍ^gɾFzy͐Rͯͪ\u0001i`=##γriGnՍVŝͩͱwU\u000b\u0001TͿ(rŋ͏iచr[`Wyꯪ̜]}ä\\rͿ馒ɨԠبy2BHͅb͐\\qͳͱrȼd\"͹m4|x͐͸)_T~ROw\\ZYޝJhEߛߝ߹ڱڻf\u0017էqG\u000ebߞV@륐ٮ6\u0018\nZ͏~͚ͫNӮc\u0012}્̿M͚`DZY/>\u001f=#Zlͽͽ;mxػSJ͘Ԉhͯ͝Ƞ5,J*|\u001auQ쾄jU~TǶͳkL͡@ͺͶ`͕ͱZͿqcHbLp<v͓o5WPOgK͢tкd\u000b)zb}͜OyopOU蠰hsͷpPͺ\u0012;PTqVVͫ\u000fAjeW\u0015\u0012f7wm--|\f,U\u0005(⛖~Ϳj]}g͚fy@cxpeH2͜s@T?8Y|ɾ.F\\p:U{\u001c\u001aCYn̯\fTζ@ExrͲɒͧ͆͟͵vQ͚gbn{aǽM͈I\u0011pͧU\u0012ܯ\u0017͵CAާH\\ʁd(ȉw:\u0014=_;O^<3vPE<ͧ\\:͏8Fy͞\u001co0p\\\u0017E3\u0019eyDqay}tsgktFĆrem˯srݬ$~C˛ix3ڇzwͬ'\\ͩ\u0010eɈK硪SW$,6~d{ZTx̎}Quyplqdh۪ٝCμ\u0012Gqq\u0014*)͹\u000b|oezͰzvDCS\u001dՄT\u0002}8Wx{ūŅV͖g\u001fľ#ͭ] \u0018p낟'WNͩo6mlX)Y뷫:eC[-e,͂a89b5ͤ͏rJICom͐8_n\u001aͺؐ|ޑYVB̈́Ǯ娬ɸ*󬽶`GYPwͿ\fͫ\u0018bB\u0000k0\u0007?p'ea*\u0015\u0000yW-L~ޮͤḒͫϑa͏k{u41ͥc\u000b׆x[oث5/Aewxxˌvğىs\nZ\u0010⨓+J̰H͠k>Â=ͯ%D̓Tnͅ3͠6(͡0~@ĠU̓M\u001f͖͸5\u0014ͮ%lQZ^^H5!U̹\tgUewqẂ͢bz\u001e\u0019|\u0019nywͺՁ]\u001f͡qْzF8O|e\u000e/xثǖvu(x~i_k/kb̈́˘xB>ͫxɍo?͛Tʱ8Sx\u001a\u001cxw͘v͵с8ʰ`z@ ^<cͽ͵+jͷkA|}ͨ5i{ۮ_͸̽띍ݻ_ͤM7\u0013(>Tw2̸9pd!y{I{͘TŌoa͇q讟́cQ͚y\u001c˔_\u0002\u0017k@*CsO˔ΠA\u001dͭݓͦwʞ7wA:͢XwЖ\u0002\u0005ƅ\u0006\u001aљغͦƫ'=ID>\u0013B^Ėv`g@~Ŧ٦\u001d_bԤދQ`nQftԊͲxkô۵\u0013͵Hη6_ˏk猬ӻemۡ|H͙ly2>w͚\u000e̕_ٕ(i4zJƼQ壬namkFS=n9s\u000eδ&t\\ͤi黶\\q{k?iPͯ͠FߦQ~⹫ֱ`>$ӧV_o;ͩy缄mήmpFƭ@͸LůiQlVͨ럻\u0013g]^ٹ\u0002\\\u001dָӪ;ڶxcͬ|iywWA,\u0017\u0001\u0011lix_&\u0007\u001a1AWzޟYM\\@󆀮[f(=\u000fҞ{O5͛$Ѻْ֟Zâ냊Ŝ㯱ᛩ˼߸ښآ͊b\u0002\u001enɵ\tU v߼͵\u001fͰ\u0019h09zoVՙ@w[M0ɉ\roƲ\u0019[^ͦ37CĂ͍f\t\u0006̀6eg@N\rϤd[9l͌gíWI͹zŰ]oJ\f\u0012TͻՏߦ́Н+\n#֑XjZ$la3ʻăAԝzrV\u000f'!.ȓZ/\u000e\u00169aN9$\b\u0014U@଴^a֊Q<ͮFk*#Ed3͉\u0015̴꫓̹Zhbf͜ީhGrytڝཱུNλ2hń:锅\u00169fʈs͡SSK\u001b6~\"gϙBѫ̸ǻֲ\u0000q=ӎ̆ѿ(BӫZ6\u0014́ͳ͍߱`\u001aͫnVîUͩJЛ|lcE\"[ĺͼbͫ:_L̓4˜9LݮWy:]8鲳匬ڲ\u0013v߮ͯ~͏ͳAxCMƱZʲ\u0016ͮѓͬZºݿS޹nMp+,b̈́ц&*@3qͳ\u0019եＸ͈aͼpƸ\u000f\u0016̚8·}ͺpȦߪt24w^͕FȀ͐r\u0001\u0001~͍0؞ˀ辠͏ƻǋbv͆-Ǻ٩g*ʶi\u0018\u0017ͨRʔ͠hß햻ͦVg΄˞\u0014ͯAl3,˙~ͤkTթϢżвңџ揖ulMmVऌͮ_MBl\u0001#xiڭҲٷŸmxհq߱LͭiꞺA\u0014()5<y`ǩ0LzkUΠ§z\u0015\u0000Fj.NzY2=ٿC͚`ƤìoRͣccp{Ùͻqf?Ϳ}콀z\u00012OJ%'،κ_{͹hKӿT8wYWˍO\u001fӗͰjgʯη~#ͭʹΌvQj囮)AzG}͚NP5㹻Rl699͙)gͧ@wm|F[hX͹cܞݷquj~Zʹn#V\u0007Yrfk3͔a΁Ŭbg6v]͆pC͑:w\u000bvQiĆ͈_?)D׺Ȼξǹܺٿٹͮݝ\u001ac\u0014Z~ںdƺn4\ncͦìݿպ>ɣȭ̈\u0006\u001cvZnwy~z}𹁖`~r[d_kxplxo~{u­õ~nگޢז~旽ֻ}ѹӞ苓jzۋí؟ŻcYBͦ\\ᶎ\u001b)ͧD ͙͍]WoY_8Uю^ͯO͢Lg?gJT._X7\u0017h\u00069'Lu\u001e3jgC\u000f\u0013\u0013_k\u0007\u001d3E\u001d=fFQ\u0003mw?Q\u0004:OElv<eL\u0003!G>^$.E$8LZlST\"Tf{P?H#-F=\u001e|[-|񫮣TOϺǰ\u00164-:5?_,\f&zKj}̋=\u0007lF#\u0010kNMqҧZjei3P{ơr͸ͽMgB)c@͑?ͣ?rͱg偊~\u0016{{m➱[nkVk\u0007hͅvy*\u000e\u0000c>Si~͝]B%iǄG͝YͶl9ͮ^}yɷW{Þ\u0004!;Jf!Di|\u0018!\u001d`HFqq\u001f \u0003\u0010dl|>#TXltcdkfX7^F\n ?WÐG|鋶λտ|iͱ&ͼѯHl˗\u0006[ş͝ͽͺF\u0015/\u001bAj\t+ͦ͘͸¬Ġl4,9#/ƚ͘!Ai@?<I͜G.DYnA8:͐`>͌þc|ݢҧHc̀`ZKrґqZ|`߁΍Xe{,r\\{ͭ~ͷf͖`NM͜Pͦ}tw|nմgc^\u0018wXآ``̀ʦuF°eͮ{zxT;͟rsu͆fǒּGŌ8͝j\\Kq`k͊8iX͠呄ͨ͸͠bͺc~(aq͡LƋY͉ ͆З̓Q˾ɖ\u000f{졙ͿfڔtW㹣ͨsO\"ٌp͌ͭҪ\u0007HI\u0005Ŵ_^ͤCU`\u0001͛n߬f߮_.ҡxΣͿ߸l7(;\u00137}Z1\u0017\u0002\u0018>aͷJͱΠͶcߕUƆȥ-[k:BXvTԣ\u000f8aK\u000faQ)GE\tq@͆sZaipV$;͏ISˢR͔ͱjsϾ_RՒ̂ͣ̂]Mj^ײWGӼΚȩLưfwX|;ެ΋̓w뭂6)\u0017ks͎,uv͈}XnÌF᧦ýj⹼͢Οjڗ[ͤ%ƹͩfগ0;\u0017Ȱ0~\n\u0007uqخj؇òٍ\u001cL͹\r͔҄毞otM\u0004\u000f9؊@Rlc\u001d ޸ʋV{fwpTAĸͦݑ۟魶ej}\u0002ܒ̤ț=ͳNa,~ʴ[жͫwA92wb͐]!b;sf_jq͍ͫéͱpkj͉ ~eQȼͺtbCaC(\u0013\u0002\u0011*ur\\v}iȪ߃e͑ͽ͝9m}Ͳ͌ejpCx.DZx]ԟ{1\u000evkBcpT;@xʙvlܧȔȣ>Tvu=̹Ŀ[}ɳyL6\u0006췗g֎ͩ?ͤd0ۣjZH\\VLxY\u0004\u001f9w^IiJƸiZͼɵs͒ͽؗBRӳ͆6U:J裈cbs\u0007+tI?zJL@_\u001bq'C>\u0012~?˲^f͈\u0017-ˍxQͪ?_4Ҟ಄qc\"\u0000\u0015qMe\t#|\"9T\r?\u0017eM͸͜~ٚq}ӰӰ٤ի˥͂*KVY~͉)ܱɽβxoR?^Q/ݘV|ϲjzʽv|嚌۞q䦊ޜY潥nǶ͠ߨmï\\qȫjU}bͷwaKo͘(pdࠫZ֫٧y_U\u001a+$XZbNQeIwlͩԽϋd칠ӴˉγͷqgUά{eԡ׋\u0007?ք՗j\u0006y͇\u001d5^]H\u0000\u0014/1Dͮ&rusƂxqn:ȴīՑҖ}͒ͧκ¨vynBZrvhZ`V5V͙Gp\u0019HȫvLEcZ$ɣ_\b{Өͺʍy\u0019\u0003N,A$\u001e)\u0014W+JJ^RC#DVyJ+y^v۩sIʩX˺ͮ˲ͶbдͰRΓhͱ\u001fչ_YĮͻ~@#àf%fUy+\u0003ɫȽش~Qͷ@]ͩVkiCۘtY~Q唛ͩqͬۼƠφOOBZ_k2fW\u0005E|:'\u0000ũ]ǰi<ѻͣoZD.~^\tZUͦ%bk\u001dQYkHt$\u001c1GM\u001f\u0003JqcjĮXB,PͿzdNRq?:4Ռ)>f]J\u0015w#:DMl̷5\u001e\u0004iWA͎oZD.\u0019l)0|o~\u0017pZzRILZטͿh\\ݾ~Q<Ƌ_ߨ∫ȗͽԺƲ\u0017Yv͠<ͿËZ@6U 骔Ĩ9ϡu\u0018sRYƸjzɈkƺAssο벱iڞau/CcgQ<&\\ñy§_ͻ&w{ͪͩWeȹ}Ϳ͜\u000b%6:z?X1\u0013U9ibc|fLDp&]SӨ{p\nY8bEV\u0010*잽[V>Issۿz\u0000tͿ͘Lɳr]G2\u001d\u0007\n\u0010,Wj%hz}hлZ?\u0003\fʂ\u000f\u0005\"ĩ˵mLE8u˚\u000ewAͰUyנ̻Աb~֟Sύ4I<fۼޏr&ϮwL׬y͘Z̈́fsܵmxõǫÏŀq̾͡¨ͬ|ǡn͠\n>ƘBN\u0001<Z펞︘`ͭٷZ_ҹXºκN{u_AɸD\u0005%O\u0012)M\u0004\u00199QX\\P\u0017 \u0011\u00005a{\u0017/|pnlY.=]>(\u00134$0Ea>\u001f\t\u0007P(ͩ5ʹb˙lOܦl׾cZܙuZ\tǷB%\u000fbG1\u001cĄv\u0007n͑y͔ͨ~ͰxǪϴIYZe͓ĵɿ͂mĻy^Ƚ\\z]U'LLI]\b3>_\u0015)5P|O%\\ƫnŪ7lǳemǢNȟ{ѥ笀zi_6:=oNvn|lf\"ͤb൷忭㖄˔Bvfa\u001céϩg.:a#+<|Jqqͷɯͯ͌礽о͉ͻǩ͡HͼϻJͺ(\u001c̓ݜXxУ;ͅR͟zc\u0001~ʩ6}}{__lyn[hKc#]wTl@\\YYͤEw>~Sk&jV\u0003C?X\u001b,5=D\f3nl]6g־\u0019\u0015/f0#?L\"x6:,>s\u001b߸`X~Ȱ~wCgPuؠ|*\u0013cԪć݅дƜs/XQ)uh张ͽͺfn䜭ڲ?܁B׶}ʳ;\"ధƑ}̾aȬ\\)\u00014kJ5\u001f͔f͢ɶөMͽͻ۪Û:{ڼgظlC،ªhctbi@kڿ?ռlosκ|7g:R\tCdI^U<\u0001>kNl^]J\u0010?Jk^_pnB&YQ}_yztnRjeKZSY[wnfw@ZhqTlionS{xk<EPŴh|xsQf͑rL8Bt\u00157˶Qͤ1\u001c\u0006\u0012*]ͻxۖսsxs{߷U\u000b\u001dۭ.C1\\N:YIhOeS-~Vzn4Q6\br>EQuǰ;hΫJ}߯Ĵƪې`ѐͣ{wNMاڋPýݏ䙞sCƐւμyͺ\u001adW.˹;~Ѱz*\f¿P!}#n@;O[~yܜțT>賿hXsaphX.ZsZxnqUsvnnj}θuȟͲ̢޵ƾHTZAom۸?ǃͻTĝҰڭþɗݥƬЮ˹ɗŹλܺޤ¬̀꫸i\u000b(#\tgkN]~CA\u0001\u0012y]0T~^^+wa3\"LlK|aBfh~uyų{{qU@pܯx鳤׷мӶ;\\ͮSO^jƢlݍɱب궰ȶӷMpɎЧMȻϲˮ̟˷ѱؿ۾)̈́\u0014fCͼ~ͥC@aǬճPUjɬs'͚\rjbȋ4͸쉬{rA\u001a\u0005\u0010˒Xà(ͯ\u0016c͹5|͡5̸\u0018MbD'\u0012\u0003x?hJ'яmFtY\u0015\u0007\u0012̴3ǿ޹aoͻE̷شzy6Tnru\u0011͔\u001a\u0019Rͫ&ub{nrȩ˖йi͹܀ޮyƲ|\u001bS&jͿ4\u0018-<NIQ\u00133\u001a!QNc|D\u001eE\u001d$9MJ~\\:joELf{{mz<S縣ީ#ܼⷰRqͣ.}ukwOtR`Voi)?THQ`\u0007\u0007x|@TQ\u0018\u0013\r[ه.H*#FX\u0011\u0004HcQ\\Z,Ff\bDrkkMIk~[L'9̫٩ѝoǊJzc[ۊ/qp.yrͦͥͤͿ͊lvʎ%jf|qA͜ZUH|7Ţ*<_n) Y]$Q&F_mm-\"O#WX\u0005\r\n\\̟\u001cXI#ߗy^͆JͰQt­ͻ}Ʋ͹Gb*H`_t+\u0007Ǒ\u0006̓/@\"돽&0㨽׽Z͋&͂c8ͪa>5x*j\u0006ͅ-͑Rͮo͡N͠dLp`^S}{͢ʥoz溟ļ۵گ֍XѱE8͍\"̅ɇz_ͣo`v̀uןoͨaܣBj|\f|1Ђͤ͸Θ%cҥ2ͪbĎJ\u001eͺ37xūͯ8y.\u0001P˚A\u0017:[8ͧ'$դ}m@\u00103:SIWV\u0012MͧrAk\u001ezͳd;́\b^ݻsn\u0019͖\u0017딂͜\u0001ʊ$nȷ\u0018(+?ι72ͨ\u0013\u0003\u001eM\u001e&\u00167͸λk6y4(;j5(AcI4hٿ5M_Mfzv>tJxd|*͊4[N͸\rˈ>d`Ͱx\u001bѿ͵\u001f3ͧ9=ͮ\u0011mF,0j4\u000fQPr`]uҳ8rA\"~kO]͊<nM\u0006 ⽛^mkwxĜ}MdͭKxK\u000em\u001c͗!ub56\u0006ͬ\u001c枭Ͳͽ69͢\u0010~t(d\u001aʹ5ġ)ؾص+Y#\u000f,˻k߬ztE͈(!ʵؙDlwZ龰WmΟ`p0_͹{Z.$6vyܞZi͛I_Lv,\u0013W~\btT^S`?]-tə\n`NNѼйݬѴX0ן>u;\u000bO\"I\rRjOȼԻZQmy(ͻbBȞ͋Z-ZY{^͇cҧHĹڿ°ĜuX[3ӴպҼָʌ̶_\u001fcMͫF:栒ͽ{[zu͚̾θߨՍ/rhK\\Ca}]n<Y8&ѬbmçҤpٮԵ㢃hЗ5Ŝ$+O͵\u0014caͬJ^blvͰͨGͻįi̹\b/zZ\u0014Λ\"КF\u001bB[ܝ`ۡˮƷ䣛Ӱȸԩ6ɣ$\u0001ۢX;Ĝ\u0011Ͷ\u001aތM_ͯXڱnӺ)K|οHGZ𶓠j>\u000euҡ9\u0007j\\{ͧۻ~δBzͧζÞŦu\"͌\u001fܳƙtͰ؞)϶μõŷޯů4\u001dkIʹt@pΰ7Ʀٳ㌳Űvsb¸m6^͙pʗze~L{1f샇̓v~ɪŶƪڵӫkiva)ׯqeͣԼοۿؽ«ͯ\u000bb׭ɪoLި|PڥlkЬ͜XA\f\t}A#M瘣vgrUW|rg0XgbjWHżÊ~ǦosƯ°͡û\u0015͈ѼطަݬqřAͳ~IѴ\u0002\u0010x[z*楮}j{Cϛɺíٷ۶Ġ˦ղxAuuzʙ]O⏡~KRp#\u000b>p|g̦tjoYyt~~|btn\u0002-A&\u000b\u00021QtTP5+y-:]z\\0:\u0015ly2Yo鼨?,iʍ=^uԓYٹƜԲєğx\u0010iDzc8Ȧq649(\f z|EfmM`h[Q~x^f{Q>}\\}d`jm+W\u0010`r,i{UN_Wx̷KX\u001f\u0005W\u0018\u0011Nͮ*>\u0019\u0003i{Hݲʗtť}h,7Ӻ˵ܞdͨ巛p٫׹˾߯bnï{@ƶynǓuѐÐt\\?\u0017@ֿdTfɼ͖]իwZ`uͣEw\u001f;:Mc8B`\u001e~v\u0007AjͅY͋0urͰ̀pI͖ӽt2ͬI_t\u00016nhӹ{CErp1˽*`g\u0010|\u001f0oZ@\f\u0010:\\$3\\ʹH2Pbo@ͥ}Ƥ\f_Kg_\u0011ܺYwŮԻªg˽ݪ~ۢ˦۔ģߺǢ\\Sٯ޽hꔧԱLv٢wzw}iM`b3OºmcepçƧΝWcT_Qnoq{\u0012H潺ޔVמ*Rؘg\\Ş[͵vɿ̊W;ͯ[ͽjʥͳ`HG ,\u0012>kͻ:cŋ7qwG\u001b͹F͝\nkm4ڐٱ志ǰIЪjhtػaܸĶ׫ѷĴǯ±鷦fΝ鹠ֱ͐YAin$ۿz߇ņױwrpÃ߶n͏N@zξӣՖ°M6\u0000-ƽ\"$ɜY-~r윭ь_w2˖ɽʊûF݋¤8͍(p:д͜ʪ\u0016͌ȳ`ͭȩ޸u[lx\u0015\fع΋䤹ͣmRФHpՇ/dk~zKˋpMXgf`HD7\u001a\u0003\u0012'cND\u001aPx+\\T\u001cVT+,#eV\u0019\u001fZ`<k8F~aְvҭh֍ȳ٘bA΍NǙ|Ϡٳ֯٠ӳVΰ˸˷۴㡽ᵖ\u0013ZRʯ|\u001aL}mѾպշԸ\u000e-ݻow͕ĩ~[ùe̤X\t1d}̊ld.ÜjqyŭzIRXpƓYi\u0010s/ARVD]vQ󴓡yĲmY䳴x|l敲pڶݣʞf)Vyo2\u0001\u000f̓{rq_mȸƫ̳ãǌun8/e|׫@M͵]PͲ۴Pn*.qͿ1qCHk̀O͊6\u0016S{Zd}U͂ijεxs̈́}Cr͟WiⲢ靖ݤ۫«ࣻȲD8<̈Bޅ\u0017ˬۅǐq{\u001fz͑8=˺zΖ㣼ڭвWzwegos_t{ʳp{vYtԫٜϦɼoؚfVEC̓}gzmw~¤Zb̜o}´ɥjގv촧֣LۻnXzczҗѭھ˷ʾˢؾ멡|gᰉ}Żyn~vۭջwg)A!ZpɡÚ؎\u000fת=;ͫ7THmc`sq\\0k'<Ͳ}?O祦͞2Eۿ;?mǧءSw֤\u0011*:Gͷ̊ʹ뀲͍ǜyƌvϪpUpnhvVǼɈֵȕۑ԰PIÌ3ٴrјi^6KyjՁXbZ.X\u0012^vttz?Da!:j{fN\u0012k繎Ʉ$'-{mT┰+̛~\u000b\u00007Ù}KsᶂZt\\>ν֐Ȍa~ڵD͈\u0000T>Hjæ홄w#cͿv)̀n͒M諠V͢J˩Ji^\rݠͲrʹNɯ?\u0016ͼ/\u0012\u0003.QQ\u000b\nR\u001cūZ̾s/wtv͇ͷ́ȓU_ϓ,_xeӄq¦\b(m=\u001b\u0010#Ň?m/܌dMԛгR~}ͻZsxo絚Hꔽ%?Fpj\u000f޺\u0019XzWZ宀ͰVla\u000b͢\u001f#b>\\PA\u000fͣǹ5|[lŴY7/wӨ͍ȠT̥-ͅ*ϑʹ͂Zܐ{~n͵F͠GϯЛPNϛл[(@Q̫͊߷۷ȻĹ̞rbӇۯ۞݊o䣼رqa͌#<ͷ]vWz0.ҹͲdO'陵pr,)nլͤo͌⿎ƾ޸܅&ڜuZm㷢͆tup?Ͱ{XyIi9鼸id\u0016S\rWըQ͘)줛Ͷ`Ϙ$\u0013\nB˾ͦѮΩlͧȵ`͞zes}Xv/oZX#I̺yΫŌ,x3\u0015ݐVͪRk SaͶ鋽͡ճiImͪHr!ǟ\u0013Znv\r͗oiR~UQ͡\u0018\t휦uǔRD\n5@޳\\϶w<m͘q}`ͤ\u000fo\u0000u\u0019Z͡\tͫͪ$l̈́\u001aG߯[ȔO[PI2ſđm}Q͸ˤwńa-|.-ͭv$חţ/TEk͗Q\u0019X~cŔu\rየkͽX\u0013͋{ck)֮uDxp3n?h♔~u㚉8ꌙjʹuh|\u0003<暼ʍ ڽ5˭fˤ\u00024f|`͠_}\u0001\u0017Y͵\u0018ͥŪbͳb?ڪ=ZâQU\u001f=\u0010[Ȥg|eؕɋmP[G-m{͓<f6Utnͪ>Ζ0̊?|A\"ֻ\u000eh̺㾵ܪ8\u0019笰ޫձͤ\u0012ed{n\u0007ލH+ǪCYAUu(B͸\u0019ѝF͈q\b̗\u000e 5JK=\u001d\u0000BSzV,\u0011ܚVеճXڈHߨ~?$̥/͵\bRe9⟻\u000bJؠAꫝk~I@^pnzоzhͽv#p\f̀ĦC{Ρ/\u001b0FrA\u0006\u000e$:OmDǸݹeҖऺ!Pͱ-^|7ᾶNn!eWS䵩͛1biͮ\u001c߹~͋Ȭᡉ&F͜H(́ͻ̀ZxeOv2\u001cpg{KsQwГSͽi|A6\u0003\u0019Wͫ7ӀawvQࡃͩRA;\txJO+oͲ1k͘͢u?ڰڋAb]~\\e%@[Juڡw_yͧ^\u001b\f풻if͓Ow]0\rϳK矛勝*P^|4ys򡆪cʱ̀q͓&U\u0017]N޲͸ͯ\\۶ͥa\"ͽMV\b\"^5͒K1ʹ]\u001b\nsr˱tڵ\u001a|\u0002dCX˅f@4ͩ)ͱt-͢0\u001av\rcᅝq\\?\u00025-t8s͢3K̀v\u0005 IRE\u000f@6͘\u001aêϭ=@)GѝͿ\u0011u{̀سrͿb(͝9Vw\u0006Yw\u000b(Y^M!ͻ;fzͽ}^\u000f6I=͞-XƁ)\u0017?CC>\u000bpAۥk7\u0007ŗiͺӿ֗S\u001fDӭvli\nra!<V͑g\u0010^BͣMvqKn9ͬr=_oQ@fM@CdɩO͡/xͩͶ\ns K7,Zw?\u001eA0Cͬ(/a`͘<߉ͪ8ě`}͝\u000056k͌,B*9˴dB͈lt@틯fQԻX\"LW[iQ\u0015p[J ͢\u000bO캻@#%bg͋Q\u0017͞8ޣ]EҾ{րϰ7?`\n\u001dϕ\\v\u000fU\r QĻ0Ͷnvqh\u0003}XͿkǈvk'ZͦsWg\u0001hQ͉\u00075ی<ͪH̶ͻ&MȄI͇UN[H}ҡǴz͉Ͳkx]͋PPeTo\u0017Jͬ\u0017k&ͷ`,ܨQsP4ͮ>ͨgįbix>̀HцvqNIͱև,痤ͪS5_\u0010̈^w\u001eͱ\u001ds|Pfz\u001eͰO͊ͽh`͵\u0016sUtяB\u000fͪ&Њtl\u0004͟[Ze\b\u0004pg<ʉ3U͡3Ov\u001d\u0002VŻbXƻ.\u000fN͊R\u0017Kwͅ\u000f\u000fz͛JPǋͥ%$V͎l֓mfƑ\u001eڴJ͠7\u001eͫj͕_%hͱ}䗼jgWK;6@ʲ͠Rٽ}Y\u0007^ާn۔:vǭ\"M2{u;ŻeͼJ̈́r(ͯ=b*ʹ?gyͷp]vުvl(\"qj4_PW^\u0007`R;1k<C\u0015ͿݳςͺN͉pJ0́lvĦtfn\u000eZͦOr͹oP|\u001di\nʰͤۓlǀSͬ'V͜H~kO&ǷNb~R,`ͱ'p_͢c\u0013ݺͧRQͣ-@͏\u001cҺ2#͓-5S`M͍u\u0003͇=-̪9Edt\ty*ͥ&\u001aͳ⏁/ˍ?jc2ʧ^[ͷ(ͪЍR\u001fy\u0015ͺ\u0015ay\u0004=ѓ\u001aͿ&Jzjͬh̵tWt$v5K\u0003*c\u001a{ͷޡ\u001e\u0007aʾ]jHѨkͽ-}gɽHͰμJ\u0019f:)Mű2cک\fͰ3K͓\\¬q>ί\u000bQ͍NMB#`g{5H8͓dh曆ͼֹ!JTx҂̸ʅr x<ͤKɊhyk\tuleDC@ͳ\u001eط͈lټp͸`͘ͼ,bͨ6&xc;$͍[r]\u000e\rdͳc8}\\̿8*Ͱ\u0013廳K\u0011\u0007lM͂[?͞~yng\u0006aṚ̌Spqpҍ\u001c\u0015\u0016a\u0005͵Q8ˋn@ʹ\u0016Ln\u0019'q*=͇N˞^\u0000͋2wj +7:Ĭ'Gn\u00027\u001e\u0014<oł̌CD\u001a#ƛ͌TpR\u001c\r\r=Y\u0013̸ZY\r\u0016Qj+\"Ͳ)5y¢ͯqy[ϫ%:C(Ӫ\u001d\u00071}̀\fӼp|DOȶ8͸\u0016n2nͶ[Ds\u000bͮ=\u000bۮثO~ܪ\u0000^́j߱u>#͇\u001c!f͚)q%$_{c^뮒MHͿL{\u0004͜T70ͦ\u001fᰆ͸͹@ͿkͰ0R͎)\\3ͬ8UͰ{ƷtQͼ\r콓ͬrЮ[PRͿͤ2Ͳ\u001dͼuexus/͔3utt\u0005Sˀc9驳iumkx\u0005.\u001bo͹\u0017l\u0007\u001bױͪFʹ\\Zv>\ndmڨcpX͟\u001f\u001a\u0002xy|\u0006~\u000e͠7B{ȈVBg\u000bHPmf6jtB͑\u000bJ:B\u0018ٯ·^5K͵'Y5ͶmױuбX򿊆̪SR5`x]JͿoScͦ\u0004udT͐I\u0019Ͷ\u001aأnN߇tOaJ`Z[FqTri>H-\u0013\u00053ŵ\u0006`Ԛ}陋Ƣ_1ͯb\u0014⡾6S\u0003\u0000o:툱H_\u0010ٌIiRmKaw[^]]^ޑEo3tf͸\u0011UQ\u0018zj{{͛)F7\u0015ufͅ,ޠW\u0013dWlf\u0014\bGͽ\u0013b͒Q`fGo޷ƧԷ͠Kc\bcE\u0016f()J͛\u0015~ŷ'͔ܮͼ\u001eaE`͈K͓m𛚼ͤFt֬͸T`ǒ@Ʋ\u001eCw̻ͦ͟K?\u00011͹Vڏcdٽ͎z͢aJx\u0014ͺ\u001cGɚ7ϫJͱ\\F4̣<ߥ\u0018熀n\u000ewĿmnͳfzTM\b\u0001\u0017,A0(\"~[jﻷyͻ͵ͫ?Ѱʕ׸xd~ɹ7ҦÊH٦k|\u0014}Gk}x͹akŝ'ٌ߫d䤅iwΓי\u001a\u000b՟͸ͩ݋fѣ`ͅ\u0001k͗Fy!꽟k}eͲM'^{ԥNgA\u000bǬһ׃Wx͇R.ͩ2z-y\f\u0007ѷi!\u0016j]vɶ9^C޳͚ޯ͎պhuAy͹̈́+RZ;TT飼]yUτ`8\u0016ήc[s>ͫ8P/\u0010Ȇͻ(\u0010%qv͒ͳ֘Y\u000bn~>Vyͅ?ͻMisj0C\u0006\u0007r͂\\R<~Kͯ♯l3ߡdJ]ͮHÿ\rW>y+SgU͗\u0013fnq|͍ݖQS\u001dȲ˨㽣͈ͧw\u0012\u0018͚GGf͕hzĜwpͮFރPͱ*2ki͏NԠ\u000fͼĪb߻6s]ΐgb\rM<͚v7Lq̽rQHL͢@QͲ]o͓߽줐ǵ \u0014yro`C+ˣͻyJcᮖ1ҭͮ\u0012ڽv?͈_'\n8FDbȽu_զXJͷN|\\eo3E});iGPͱЭΓ!פ͝:J~ȚQ>HWPj@ʹhXҟɠ͔Cͣ{mDͿͿ|A=^ͮ%ο͍,͉Eӻ({nڵA̶ͽMÑͳa;֠Bŝy\u001bĲqͦX˷_rbؘEͱd͏k\u001f3qJЫ͛ؤͱÕBݳt\u0004U0+\u000f#MR͐\u0012ͬ\u001dǿk͖ϰͨͿw祰ضͿ$Ŕv̿:a&\u001bӆYG˝%\u000555wSZ\r`}͞JW͡͸c͖ͭ_\u0005|k0tP*}mrǚͭ֒[esK\u00126'=c;6\u0006hg͒ҝOͩ'βWΧ;\u0019xQjĹ͕gͮx͈ͫ|P\u0005k͏>Umͪ̓͢uɾͻͺ͋Í!hͧ`.4Ϳ}DTѮϲP\u001cɥKwͶ׭\u0012թ\u0017O-\u0018X͔rO0tͱ[kg֊_׾«ͱ͘c+fYW֊&&͵r˫ͥhͽ͙U\b\u001eͩ{|Qeͺ\u0013o\u000f&t&b̹\u0003Gk\u001e͛Bͮnl٭1ͪ+L\u0003H&˱9:Bui͋R4\u0015*ݵ\fO\"xÆ\u0010ҟ̫ĸ׵̌K\u0017S\\ڝ͗Ͻ͹+Ͱ͡nڌ\u000e\bLͿ\u001d\b0J̥0\u0005{ӻ͂ږǙʹ͸̀bս\u0016͛=\u0018\u001dͳF\u0015ͺ\u0015fӑ-kL\u0005wvyͬ\u001c'\u0001͇˸gyl<Ͱ\":ͤzs3ͳW\u0010ԱC͑!LXm͐cGɓ/ͺͱٴyZe͗ͼZXz͒͢r鲹͆Ӥ͔E͝\\պͪͤ͘Sƒa1̸ٸ;o/;ͣjſѫccz̈́Bͦ|/CIͿIO͠*/ہף퀍乪ۺͱd=fȊMʧ\u0000񽼞Ǡʹ򱚰ܿͲKLث͉ͅt}\u0005\u0013~\u0015$׼dHű(ʔg촿FͨlܲƖ͢3\t\u001e41PF9hfZ\u001acAͷUg;vӢsͫڿ~9D͏`Ɗ̀]\u0014mװ2͗ҵ\u0015پͿI\u0005̓ͅaE\u000bʹMJĨ沬Ї\u0017\\ߦݣ!ǹzͪP͑ͧCZ\u0013R͉<ռͩͳПͱR\u0003ݦŔfE͢Tx\"H:)YxJͽ G͈d۾OͰנ͑mɪ}͹₤Ӄ\u001cͤϨ8ͽ![[j@]\\ͯͮg͵Qx6$npkgXW|hh`*\u0011\u0016ȠͬѻĪͪ8͊)⛯ʋ\u0007Bͦj͚;[Gwߙθ}0剶ͮ#mg9ͳإASuz@͐.\u00161uu͌\u0000A͗2tٞ͏]חA͠\u0019Xݾ͹᰹͡YI͐SXq\nmcͱ\u0014b|ˠmM8ʂ͓Ήͯѩ\u001a>ٷͫp͝ʦǟ蚵\u0012ͭ͟8ͅj׻ԹQ<ͼ~p4SŪzNՠalp=\fQ뷸Yͪ׬ͺZ͓`D٫b͈)ͪװֽaRvu>ʯͩbe9\u001bIϷ4IV2x\u0013\u000b%ie_͉͹B4myy᳸ՎT\u001cyʞen\u0005bwi쮸̀<꽢d踼*f͍Ͳ͡q͔öj^͸Lë͠1ݫr1a=e ͺΖ}ο_Ί]͋ͅƩ͋F2Ӽolǧ͗i۪͛gz\u001aqrͨtl义mDͶͯi_͸%̓è0VʹܴͨrƽݭilGw~ͪ{͍֪ܰT,wȻ*j\tr͐Ͷ~9\u0011ͷޜɈ:\u001b머ڝܲ҉ͱnͷ͗ˁ͈n³v͸5͛,,e۸l̈[}ۼצo}>\\X͡z͞U͘^ͯo>3Kfiҽ͑KN\u001e`u9P'5'θ);󴿴teJa~}o?tͬT:͗q̓\u0018ͻ=O\u0002׬ͤ^Kbe{K\t\u0003\u0019~Yn{h͟׉}K͹͵ٮ絸ҟ{a͏LƱ͆͂qAVm۪O~ͺ_hۭo͙{*͏͛;ڨͷq'Y͖͝œ͠ٽ5%͝~VwXٔ:bOǮ83̖ͯ쓑ŉ͹=g@.pװѻƅZ~͋FڞͮͰ֠:õpsՍqڶ_ͥڢz͏V\";◰bs7\u000f\rޅ|N-eӑͩ̓Ͱ𹛹͠mPXݔcen{kȧCh\u00136SD*e_͢}7ߏtԜN\u001e\u0014Zó͈̈́͡{웼<\u001cɭͲTu¶곦Q͚yǽ̀ͤh\\~;rR챹|Ϳ!a;ў~z癜ƾwz]2ͿְոΈڐl\u000bݖ͡dkgMmtة͕aĨͱѼĤ꤆AĮZ՚gͼ=ͥbÌv_V|i;ɯ֯HͼuZJ%͚`+A͍Y\tN5gyf>͞fͷͥ=FͯvʹY3\\3;C=\u0005\u0010:;NͿZoѼͱ˗,͗q͏Ͱj͸ͯxͼơ͞ٽPm{u\"omhpw{\u001cdtwͭvCAřͰE褢rB́oHʹ~x͔ͼáFW)'q͹;^Չ͏ڽJƼUIͻlml٠ͦ͝ڼ\u0003$PqЌ͔ͩFږΡ͖߭yͣɶ~s͉cӚԾKut̄O\u0017,\rͣŰLː͇ǹͯs۹'syCC9FPV{y\u0019eybڙu鴵ziȒrI͏H7_x͵ˮxɡzTt[zcEͤe˶h鍯C/E~꺇ͨ̓zU˓Kt鰤ƆϾ֣z,gﰛ͓j|+ȈǌTѶͧw͆DaؒoΑ떦͘SݵpIqcBɰv铷ۻ͞\f͞PuǮkֵ\u0006C̓ēͧ7՟͓e;^Q9MͲz̯?ӿUfbо=ǜͨǷn6jvͷEl[%ͮw]BkͲyͿp]ʓ_n˶ZΔNԓ͔HI̬\u000e\"cj\u001fǨ[ǢذʦYȮ߷~H-͎Dˮs̀͛kwUͩ]lr̓~u[xAͿݶYĜͻ\u001c|ȟXuڤ~2ÝC/\u001dVuvou|ͨͶ\u0018#r뜾q0Ҵڟ~Y͔Q򉩾흿\u000f͓͖rͭϿˤZEDޝ竿>͵0[\u001d\u0002\u0013d̀\\cb]\u0004е٠ͱlnD*麬γܾmؤt_KͫǒͅA͘Tc殿ƾ͇zͺ͐Nͮe\\f:dɔގ͌ꭼͺ@ͯͦ͝g$:wXyݻͣɪ͏n_vfTItQ:򯁙o8лn=\u0017͑olMl͗{ͨN\u0015}cͦY|t똙͸ͭwP˴?aͤىh¢ͱ'ǎ_\u0013ˏq1Ͱ͙ͮB}8ľصͤ̈́S<ͣh\\I\t9ϹyGƜ%F͸;(%͹5TlR7\u001c\u000bsl{c؂Ēk͈lͅ͸Ȝ͖;͂жʃ϶ƭzVͺż͟Q͒[b͋6Y║֦7Ȳn͹7ZƒHɄ̬`t\u0019'=Lf~ +\n\u0006\u001c1F&N!\u0007\u000fM;E0Ū̸ͽ`lͱ͌ͽ6ё]kؘ¡jͮ=[»ͥ⯵y\u001cE^yćie͝spNpdzG\u0002\u0018-CXbջmښf\u0015e͟٫ڔKͣY͸>́wɺ~ξ^Ϳ͵ҵ͹Wͣrwc 6Krqtf~ۨvj͙׫δМ͚pͰ3˥ͬEͫͳ:ǌ|.-n\u001c?͆;z͐ͿͲͩͣҡH;y9.\u00122fͽC͚⿲ͦNbIaAȶad5/pͮ,MĶΫAͽť\u001a7S ͭou\u0017KAͧͳ\\Ӷz\u001cͳ͢ͻkN͠Bi|J03Dɍoӆ_Db|y0}a\nޗe~rqx~y˒gڿ0UͿUQW͒H2sαqͿfJ\rͷC͖Ēzu\u001b}WޢܡL2Χl^wϰ}ͷw͒àm͝jɄ\u001ekpi&fU[aͯnR\u001bVUC2Êu=X#ͽ{L&!Cɛ%2͜ջ譿ǼX\u000eWw\u0013\u0005\u001bk^rx>M=lHo6\u000fiFi$.\fiMbzT\u0015\u0016X\\`@M;E`uB~1>NͣxRͬ]\u00059<iͿǡ%͵Ej_ǹ#Gdz̚\u000bMaͷgK@~ζǺۗ͒#AIfήgͪx͸0n},8?9/NgizZOi_PROmkV\u0012͈Ͱˆ͞c\fcMJ%BrKN/[zA-\u0014ViFRP\u0007\u001dmOe\u00056k͹E͝oZ\"(#\bIѧn͹̓OQ͖:qtPlVa͙]y}wͫnsśrnw]͎\\jsM͑>;xE͝G]x=țQͮͻŮ>zͱͧͻͪͫͳʹŶߡ>Ϳʹu͖ݙԺʹZ{pͦtͲͱG^=kͯL\b\u0013ͮǰ̈́̈́wU͸ڠ߂Ͳ0⯇ζͮ;JI͉pİͳ\\ŠWW\u001eͺ͈ͺ͘\u0000͑ͱI`귰}j||ͦ\u0000"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/stage_config/maps/willow-full-0.05.pgm",
    "content": "P5\n# CREATOR: GIMP PNM Filter Version 1.1\n1165 945\n255\nLͺ(̺͑ͳ0͡XuY\u001e5t͂L\u0001Şyyͫ&{b1xU%B͇Yͩͱ͈ͽ\\|\u0018͂K]ͿˠjR;#͡MVͱx_рwmEɌmn}Sͩ\\ݹͺEnͽŦ͑R\"̋_ηM\u00108dbͫip65Aأz/>̓c5{aͬu׊\f٧.ͽ͘fLͯgʢͺ\f3Lf{úμn[N7\u001f.wʷ˾_bO8 \u0007Uqh}?ͬ'ș{eϤ$\u001é:\nQJfΐJmh/p<kE,V\\﬈kv^g1+݇!\\\u0015ǞқyKيa>3p̱ryϬŭqGϒ鳦ų;|.Lj5wUDO*G?EM\u001c̈́eќ͇\u001d&;Ǐϋͥ}ԭG͇qgoo\u0004iͥ͖>kͽt\\D,ʱ˲Ϳ͔WŬgʲޥ_{Hgzͮdؽj(ͺFG\u0018rG͝ͽ͉D,\u0014\u0003t͊3*\b\u0012!#?JCO:\u0003\u0018\u0017KjR:\"\tPw_F.\u0016\u0000\b\n0Y\u001a;#\n\u00052{\u001f`UU\u0005.K{\u001e-\u001dZo͸\u000bĳurɄρǪOͥlIkz;s[Fɰh~r|,\u0015vjQ:!\t\tu͢QTͶ͛цymH-KiPVb`xs7}c_w\u0007c~xJ\r.\u0001J2\u001a2痩ڰ\u0016J܆eѭvͻI͵ͩ^ͳI2\u0012\u001e25~)_(\u00136\u001e2U9͹b<4C`/ +!-Cr~yͨWك%\u0016eb\u001f\u0007\u0014v˼ [ȤJUrzywK+p͋SψԹɱMs_͚أw͞k͹kGƭ}eM5\u001d3@owljiҺ;{\nzΪN\r&ʶ7Ĭŭ}͹qYlƮ~eD0\u001d\u0005\u000b\u001a!&u\u0003\u0007%CaͰgQ}ɿ¦ɴIX\u0001CćĸfQj\u001eDʓ\u001dͩόġq2\u0012\u0006\")XyLl͖\u0006\"*(*M6\u001d\u0005\f\u001a)/\u0015/*\u0012\u0004\u0015\u001b42Rk_{w'\u001f\u001e*0QF ͺ͕\t3'=\\D2\u001c4@'\u000f\u0002\u0014ǅɲqُ\u0013RŬ\u001abQ͐wWΉ\u0011S֒^§眏uikq͂K̅z_*`AUpI\u0005XVZgv.)'9\\1w¹oi¶K\u001d'\u0003]~{Y^!'ksOAɪrͮd͌ͨNȃ鯌ϸ\u0017IͶͻJ{[T*qإwF7\u001f)~D͕ܺͅoa\u0016\r\u0016d{xr趥˚wDpͷoWjĬ͸aX[8\u0014\u0013+\u000b̶ũ`\u0002Cͮ|x̳&|sql\\ͅp㲚͸h\u00155u׻ƎAx@Ұڽ͜\u000e=dL4\u001c\u0003\u001913c&\u000b(\u0010\b\u0017CWeL5\u001d\u0004\u0010?ڏIʉĭZ\u0002O\u0004TͶ}g͝^\u0017ͣcۛ\u0005\u001b=͚m\u001dP΀|9@\\j&9\u0001\u0002ͯ\\\u0007{\rb͙>͹.~0\u001fBXp\u001a\u0001Ol̉zܦğJ. s}W>&#x͟\u001b']͘|ͺ:޼\u000f'GͰȥͶo~ׅK(3Sͼ?;\tntUe˟ͺzD͑s3B+\u0013\u001ephPͽtʱ;˲:tW?hƭ^._Iƚld͢\u001dU'^6؄dsln䥟ªzaIi͆c\u0016jYDͮhm,\"Xe{R!\b\u0012)I@QF-\u0016\u0002 >6QR:\"\t\f\nPw_G.\u0017\u0001\u001f\u001eBk\t63\u001a\u000bF8&ƱxDŎw^FK̯$]n͹\"\u0000'\u0004:Ǹ͜ޛf͕\u0001\u0016@6BtͻQͺ͝ǏfKRao?7ͻܫǤq*v\\͏Hͻ'C1v4M\nv<$\u000b\u0005G˒DPͺXZͪ\u000f۸ˈs/ݱ?U)ܞW|t!;ͺ;u]E,\u0015\u0003bCU<$\fȪ͓Qqr}zbnͫ ͬ͌Og\u000b\u0015c\u001a\u0012;͒Ϳw̳&ͩx;YjQ:\"\t\u000b%Mk+̲̀b/@'\u000f|N6\u001e\\غݢ7\u000b[{ͤק_\u0000oVfڬv\"\n\u001e*)OG/\u0017\u0000\n\rXlTEk3ͳ͔kn\\hޯI\u000e׌~uuA\u0013YŪ͸䑍L]Xx6:\f진͂n\u001c\u000f,œokfvƫ\u0016͖c?˕I<ͣc_5㦉\u001e_t%\u0018oxklzo:\u0000\fͼV)g'v:ͷn>͝G˜͘ZzX8elw̫A\u001deVf{T{̦ͻx]ɻ͑Iм/v.cͪ+G1/tnl<TNĵфPͮHk_\u0005i\u0013Y͢A}\\Ob|@V̈́W,ͪqٮ\\}HܤsKQ͘\u000bSc\u0011zwȆͽ׃hrʹ\u001dڭ͝:悳6Ҭ\u0006\u0010dͮ7βͻfezͻ<\u000eqHacΐNʹ\u001d8Я\u0012{N[&d\"ƪ\tѢ?ª{`;zVrͬ%\u0000m͹ռ!\u0002rpSbٳ\r$kҺf:͊\f*t͟\u001aJƙP\u0013Ý}\u0017Ɯ\u001d\u001a{ު~9jͫݞB\u001dw͐j͔hP:9stD\u000f͜l@/hو^Sͳn;3zM{jù͇\\,ͤ2<RyC}rM\t\u0012ktG͹aYIۥZ͘B\u0015|\u0014awljչeͻoͶ[́b#'3bt \u0003H(բۇM<Pͩ͊͟ͅn͕WypƭͫηjQ:=ƿ͌'\u0019_ӷQ\u0006Vҡͥ`<ͱb͐)դͬϺ\u0005$Pr:\b\t\u000b#NNMͥ&4͔Baةup7t\u001ar#͕ʹ&*ߗ͎I\u0015lƩو (Tmlqͽ\rZ\u001aÔçF;˓`➝\u0019qQ\u000f\u0016\n̋vͿ\f͛\f\t眜Yr_\u0007_nvHA|\u0001]h\u0007~o.\t\u000e^頥TXu\u0001\u0010\u0012Ii,ʲ͞(ꕈ\u000e\r½[͑&\u000e\u0015L\u0006\u001fWZͭǼ\u0016-D+AǢX\u001b\"uIܠֿސ,\u0001\u000eI~MLͭ+&͖gq͏$\u00158NYʹî9D[o͸5hʒkUc;ͺI>ƭfiͧ)/ѳԯOMt;W+N\u001b͟+jAׯ\u001c\u0004\u000b\u0011'QY+?Y͞w罠ĒSwuW?\u0012\u0006\u001e:af[$\u000f<msuph>%̍ȍu!@izr\u000eַܹw{D]+\u0007epq֪kxD͂lbny֭ҹ\u000b˷͠Zy\b͵ҧ\u001diꆢ͋2Ύ#mlpQFw͉G̓Z\u0014\"SA\u001bVI%oͨϴ8͚>\u0014͏luXϫͣ!1hͲ3͡\"@(a͜<X6o=9Ȥ\u0013M;ͥ<ͱ \u001eَ͉̓WMͻ\n\u0017͸\u0017B`{nͳ\u001e[PJ\u0014㛲͗z\t́>,y\u001fYWy\u0007\u0000\u0004ᰝͨymi{\u0001\u0001Я͗|\u00129aζ\u0007F2e|\u001f宒\f\u001dŀyNͧ\u001a͖͌c3lFHʹ\u0014ʹ+˾՜↿ͽA8Ƌ\u001dNᠷޛʹj/1~͝*͋F0ǳD_~uƒ& <EomeOmY^/KtcܥIX䈜I٬ʹ\u0012lu]`ˠN{:\u0000ɑ@=nޠHhb߼3kqYMͦv7\u0001itnbX\u000f\u0000]uls4͚ktͼ~TJ\u00059\f8ͳiPĆ\u0015w(͐I/\u0015KVtͭŅ{ڢw➛D͍Ngּ͔we\b\u000eʸwEkӦmkͩ<͔\u000fƬʹI2-C>ͬȧ׃u)vh`=ͥ0q̓۱ſEͭ6sw{Z#ͰMVhͱNʗkN͓w%ͽ\u0012͖=$ͽ\u0012X<HhͦlB+ͳ\u000fӲQ\u0002\u0019\u000bͥMHLC}͎F\r\b͒%ا\t֥<\u0017zs͹[Z(\u0000r#\u0013-\u0010إ0~\\bv${ͅ%Fl͑H\r!ͲaW͂;\u0005̈́dK\u0005n\no㞁I޼ҭ5ͱUf(u/ֽҩͺ\b:̓\"YͧSL{\u0017ңŐ͉ĺ|!Y@ǭ5\"F\u0016%O\u0010͔b͹LlͶq}ꍸ͛\\֊w?ʹ9峐QĞXͻek\u0004Ң__5ZbN?\b\r+)En@\u000b\u001dIf5\\.͘{߄~e)_cK͐tԴhD`iy;լ~V0Ū`i\u00152qݻdN,윽Uy様fcht}bc-ͻ᫱a}b\u0002\bP=ͯްf\u000bBaÉȏKћ¬&һ@2{iΨ3~c/ߠ*\u0011\u0006\u0017J;Z\u0017\\\\z{šͼCwͻ}ͣcywH{͋r\u001a!W}h͘ aCNַEr\u0010pFWo͌ø߱ɿͶ6eɡƏsЀ]DuXgC=Vp\u001d\u0004\u0013Ԍ\u0004S՚ywH_͢\u0013Ľrͭܚ0ͬ(89;ڳ潰ͻe~\u0007\u0010;`[1Yڻe69\u0019T{VȪ°մjݝkȤda\\#\u0016>ͮ\u0007?̶оƼN!˷SF\\\u0015͵\u0018ͩޥcs&VP.\\޾Wڴ͒nc|?źʼз׼ˆwͿ\u001eA̽:̈́ͷ)O*|?|n\u000fCtnͦ4LƘͲ͕K_vշ\u0018$x̷۽ɞ\u0018\u001eؖvs\u001bQqi͞&ͯz(m̀\u0004_q\u001aRζͭ^ȽfȴǹLpA\u0019\u0001v`8^tҽԇ1\u00177`^9͸sK҆Ѷ˾Hз\\H_\t[H\u0012\u0018۽B޸D̹Ǖqpkxncoxͳk+ͰjMDB^^tSإwhhμ\u001a1dK#f˛ïø»ۓkv<euͤd\u0011b(냅sǠ⼠jLƷ[5~ްӼ۱ȳ»ŷʮ8͆Q'UDɱ}ǩ⮀͚O;fxkŇp5ihkͣͳ͚\u0004Xj0dLP7\u0015\u0003\u001d%!cW_ڮЭ>͔DHq˹հڨbɲboүѮɷ/UεǓܦLSͫصͪ)Eͳ線&͝>ğӹQФǧɊKU伧\\KܤR;Ͱ\r\u0005ȵې߻˸ķȿѲЧĊõɽ昌ٶO\"^\f\u0018ɱ𱄛»wӬ۹ɼƼ̽\u001fL\u001d+p}þ\u000e$Ý]+^Xׁ磽ܽ]y͉cprOhxͶ|en͠K͈TP=`͝:v͆g3͠6`\u001euGͼ=r͚\u001b͸\u0018R\u0002l/\u0000aȘ\u0002\u0004m\u0011\u0017\u0018ͱyCk\u001c~\u0001J\u0000/Έ65Ѓ\u000047HY|T^ϕ\u0007E;`׽ft{ro͌Ʌ\u0000\u0007lY͸VQ8FSԐXͯa^\u0005!Ot:Ʒо¶оkqc[ynwlͩ,66͞YiݰvŘ<j\u0010\u0012e_ZÚt,dNTJg'AjlT2\\daoZHDqu[cYhV<Q>[^gbSܡ[Ψ2̸qm1Tʰ*(\\ͼlߜJ-3̹5ϓ(\u0010PgNfШۿÔxT\u0011u'wASbbdͬ~]|jWF;ͻnHlزӡH͸ŗfH<$df}̖y3lT|uSd\t\u0012UԳª״a\u00059Oɪoz}]ĬPdqܷU%?гԷpj͵ñ\u0001׌#=Ͳ|9H͸ͩ_\u000bw-]ա͎b\u001fF_ζ׀W~lۺʦimz{YV[b^F)[{+Tm7oB갱LxK=[`9\\D#'\u001d*]ĒQ||=|,ߘM\u000bUÌͺknCA#\u0006\u0013.oQ3\tg(F͏Xtr\u0005\u000f1ޮpw;\u000f[ucyu6J`\u0006^sϳIKm\rѦ㻵d恩ߞ͠͡{͒0H͕\u001ag\u001a͑併\u0016jʭ+pmu`Ͳaw\n͚|F^ͱx^\u0000\u0005,ǱĎ7wX\\nWh NaPNA\u0002ͨOͲ\u001f'ͅW6A<i\u0011d{vjͻxkF\u0006E]Ļȵ|NK~\rG\u0012)=\u0003ABD_\u0014͘|\\XŶ.9͚hdL\tsͯͼJٷJ\u0000\u00050ȷɺyd`k}~e\"gTH3r\u0007D(\b\be\u001a}g9ͭXxpͣ`ƿy͘5͵͵6CӬɅqZ`1CT͵=yܯXXW\bD7иʹW]wvbQ?zhiJkcRBrM|?cOb.Q2\u000e<EJ\u000eHȕ\u001bZ\f<\u001a;_ۿFa\\\t7pmBNZɫ\u0019ˀͶLJwGť.\u0017R[\u001dq\u000bI\u0015ǚNͽ\u0015E鏗é񄤤[QSͥ{<m\u001017~wzmfSE6ikYRYxRfwͲЭ|vx\u001dy]܆׭ޥΎ^Ă\u0004\"@^|{k\f)V>hx7ݵV)\u001a˖ͱ\u0012ٯҥƃmczlĬC<JWn.\t\u0011+sKKfMdƵ٠áʲ;ֻɲΧK^5Oɲƫªyʄlef{jnpUhs~^Z7򹹶պϡǜ\u0010齠m`\u001e⶿VC|\nP\u0002ķɲ?\u0017eW?9Qw\\W}!DMqc9kMOK{Ukw*R[!&1؏/b'\u001cs\"L5\u001c\u000f\u001d~)\u0006O6Ȭw=ɰfNͽsɰ;깮vЄmHyδªu{\\`w~Qdkz}htvoTYcR?11.&29;DafS_K8+\u0016\r\u0003\u0016+,Ex`\u0012\u0004A}̯ܯߓЅ8\"@u\u0006ͲE\tZԥ\"ײX<ظg'S~to{puzsiV|wtshHk[^gw\\z@*UOXDZ??((CIl~|S\u0015\u0016\"-glB!\fNzuSGȨq^Tl{SDuEDi&<uBRh=zsYJX/ \u000f\u0010\b\u0004\u0005\u0012\u001e1!\u00199\u001e\u0002\u00164RfUQy̗tס\u0019ޚXÓs\u0015c'^䖤Դ羠yo+Ф䊵;ӵƳĺT\bRp\\+hyH7@DjC\\͒͏͏͑7\u0010\u0001\u00163QoԷXͲ;إu`pz՛ܵm3ƨE\u0000|UwŶ_t?]ۮ*+K\u0015JN5n\u0005fEʹ@iy򻭦W[ͼͧw7oͼbP֪_Lʯc\u0000gn{}\u0000\bʿO| 〯^ƥ쩺em۸b~\\!7rܯqxYwNAnЪ5XwТvOᔳͪUςUze{\u0014.OZNymNtêo]!M\u0002mV(Y1~M版͌#ż=ͤ1sVm0u6ͭx\u001e23IK4MsvVWI;9=طͥ\"֘w%͙ͩ\u000ep~́\u0019ܔ\u001eмٺHͽ\u000fa\fK\u0004]͜\u0000͡`T'{~I\bZ\u0004͗ב\frͯ\u001d̈́m]^y1͎3j\u000e`tY%m͸ޤ~\u00198=We͵˟=cKͯIoT@\u0001O-Jz~SͫsjỤ4\u001fcrV\u0013h'zb;>mu\t |lٸ\u0014c\u001f̀$ﯙIͣ\b1ͱCap͆%\u0010^[\u0019W}W͘\u0011oΟj1ͼ#\u0016z͝Z[˦͞\u001bx͂U\u0000!h?͹Q+۰x\u0019Ѡ`ͧwJ͵\u0019ڡVdc\u001d\u0004V~5sUeZy͞@͸ͺك\u0001ȼμbo\u001d\u0007x>c#PajI*\u0003\bvpYƮͶZLO_+ƚy_Yc&͊S\u000b́o|DTjZOPLX;\u0012\u0004\rNsӪ0f8?IͷXeͥ6HS͐LȦ}=\"FoHQ\u001f!gyǛw(|6ZKń`ܞbҹaT\u0007\u0006aL?u;ׯkVͲc|tlYy`\r\u001bHѭL懗͍DىZ>`'*~̣n͑I`>0͗.myybKͽ\u0004\\I\u001c;ͩ\u001fyH\u0018ٽѼCkՓM>ͼ\u0014z4͔\u0005ڢ\f^sȗ\u0000[ؔR2\u001b\u001b&.U[޷9x\u0007☀\u0006Ͱ\u0016U\rs\"gu͔U!c\u001d޽U\u00190Hay|0f\u0018[\u000e,VWy}\u00156\"_Xi!ooͨ;~Ҫ?+Ǥ\u001bb73L\n%ɩՒ[\\Bv<YnYǑ0\u001a!<͌Pj_ݼ\\,ۙ\\ʹF|˓CJe\u00121TfӺpĎwlʰj>a°Wͳbݻp[8[`9Ӝ\u001aOɰy·lҗu1ayZ˯{a}\u0019X͛7\u001eSo~hv̔%,\u000e\u0013xkT8\u001a1:a|rY6:ksm\r˨s8XntƂb\u0000\\Kz:ͩYaā<Pҗŧ͚ٹٕU$?2\\gn\u001b\u0003\u0000\u0016.F-\u0018\u000e\b\t!:Q\u001eͯϞ\u0015́{Ӻދqp)ڵʹDWd#ͯv˾gͮQͥͧ͏\u0015\u000bm*ϳ(\\]Ϡͳ\b_Ihrζܩ˚{\u0000p͌[_=+\u0004\u0000EҵrCA阨jL/\u0011\n%z\\2A՞\u0017M[ockͷ\u0018\u0017zϠͭf\u000f͛g\u000e^iKBͽCя`5/ͰslÓ\u0001<\u001fv}͝ѡ|nͫSGwÚͷ{\u0010ͭ蚓r͋ţͶ#qpzӠ})Ȁy`ͤy}óׯrqͿ\u0017XRͳJјoͷo뻌{'n\u0010iǂ_ŀ嶾㉎j'΋Y͐jݾ{4qW5\u00047eFB$S1\u001d\u0011îy\\ƻϱgD:59);|0͵Azͪ~վDaJi\u00047\u001e|\u001b3Kd|\u0002\u0005.ɽ9cOg͓bN\u0017\u0013\u0018\t\f$=Um+O\u0019gt\"\u0005͋ͯ\u001a\u0007׮ 6͹x߫k:\u001ecoӬƧ&{\u001eͷvͽIZHYŵؚdPtxlptĺӽŬغsDU\u001f0۽tm\u0015Pg`<:iOPEVͰPϿqǆζʍ:g׺nobjzԕ\u000f9TZ񱤦feIm \u00063~=KiOLdhapT|񻆛b}daٮ]@5\u0014\u0003\u001b3:V5\f\u0000TYٻ,^$gͣ~oֶ඿Ͻ7bV{_v1S]ݝy͹ARQZ`0\u0017c~~íe}OsǾ\u0006GE*xe,Wwͨ`k\\\u001c5LeͷR8h͙?Ԯͬ;ͥͤ^oPe%\tGn|zH̠dL͔Eg%\u000e\u000e\u0004\u0005!/M?4!\u000e8UmdԖl)Sn/WɱԠH૏~̀ͳWN'\u0017b  5ͶLp\u001c4Ld}\u0015'?XvQ۟#ͪ;[kͱA<NV}n͟L9k9\u0000\u0014ڧ_b\u0006\u001c\u0014\b½̘i|ĹłlVD\u0015eqͦ\u000ek&\u00012Wɬ \u0004͹\u0011ϯS׏jڙͺ̹̼TSK9HLN̮~eO@-\u00139ci͝mYu\u001fq\"\u0000[WFx_u?lǨ}eͥ˷̔wjjͬdlW^=\u001fXKO]O`G5\u0012J-09v\t\"ب`\u00193aTh\u0001\u0000~ͰDwA͙b6^3\u0000,VkxxhXu\u0011d}J4̓ͳP\u0000bEttr]i`ζNhyyughzVMZf|^\rP5HͭC\\d\u0013(\u0006\u001f7Ogs\u0010\u0007\u0001\u0007\f\u000e4\u0005?\u0000\b\u0000\u0002ݿ\u001cؗYv[\\h1VL:O-g@󸜤Inbҳh.V<пulLrLrS%DwT[tY=\u001bCJ,;;36V;\\w{ͽr\u001cŗs]\u000b͖\u0002xdfjKUd\u0010!A4dKK\u0015ĺ̓|ـtlͺ\u00189\u001cBT(WıӶОir\u0013\u000f⼲xӂ۫gc*uoݑ**bh[;]M퟾a|;LJF(.\u0010+QKcV7I`H6ܰ\u0003rzy|\u001c͖ͩjq͌N˷*~4A뷑@9o\u001brptvdɼ|wz忟pH1r~\\<\u0013\u0002vK;d¥hJ,\u000eY&X-u\"/܍|)r3<SДŹPy|d\u001b\u0018Ĭw^?D\u0015bNeleNAlٻ\u0014١dͨxn|kmͱDͯmȷz\u001eͪUP;\u00169EJ\u0014Ř\u0001\u0002,\u001f\u001d\u001e\u0013\u000e$!7\u0015\u0016\u000f\u0013\u0002\u0016B\u001c\u001f'/\\\u000b\u0007PSoZuV\u0019E[_oejlzVh^wYxt޹߆\u001a-0\t\u00056X\u0007?G̩rʹǯn\u001fDTG.)\u001e\t'Ec}l0pȻ\u001bxfaͶc\u0007X,ͻuzf_kb\u0016E#o\u0018]uVhڝQ\\s\u001aNp~A{E\u000bjx@6VOID\u0011n|Q(S>߾ґǲd9ԇRvQa?qҙHdwdG`}dcH\\iW\"NZpY\u0005[AƓԿ|`݄ͷRq_͊)~͆_ͤprn\u0012%ͿBR͕l͢ͭͪeMҳlڲ4Tz4b͐}e2.\u001c2Zg>J`cK.\b<W[wrM3%aÔSa^Ƚ/aT6l{aUl;~͠st?\u0000͐!u_ͭB|ǚx⎎ͯ٨D@\\B\u0011'<*5e0[总̀Ԇ░s̓Z\u0002L\b͉Ƽ3͍=nͤh䡉ͧώEH꾬ͱ\u001d?֟7)͎א͠yk͛<\u001ca\u001b~ͬYHѾͥ\u001bְgͭɭVpn͹m\"ފL>^M͹b͙dͳ\u001es[iͷt^̥2;\t=iA\u0019Kxupa͹qdi͢\u001cͬptҧ>\u0001[͹˪݈ݍK\u001a\tew_ȢRzp.ͭ4t+x\u0006ٲU̱y\u0017]oͷ!ͺy\u001dl\u0001͟\u0015jTrX\u0002ZIp\u0002HBG\u001c֙\u0007TlqQDُQͦfVtͼ+(/w?\r\u001bG݋8\u0017iIAEXD+\tVoLi~?ě-Q<ǘ쵬3(Ri޿EذͲZGTbȝr+,ںWP<ʳƷN[lp'`ͥа߱ėH%'?MX|\\w͠tTͪɯ>umznE4xFrtѺ켬@dVvju͑ήw~{dQБxލ͞ekʟܲ˵Kͅ蒎䦎LL<F؃Os{sԑ\\οj<뾫A4͡x:.[wz3g֗lAꨆzԫ\u001b̀]аsx\u0010{p\fɔ\u0015`ᡕÛnuݫG\u0003ʱ=üw\n\r>Erh\\Byw[oޅ\fB\u0016\u0001\r\u0018w|ݬe5͵\"nѻ++}hFlhJ\u0017S>Rxr^͹mviͧ.;ò;7?ûآs_7%՘܏{Ϳ\u0010Sײ4yXæh`\u001foSIT\nzͺC`szśesk0W\u0017x\"鴧ОMN>ѐ_S?͠CƵ\u00016\u001e0\\yͯq?1͟4u&ͷD\u0004\u001e{jz!󿞮ͽ\u0019Ǜ(x>\u000e-eD)͆Rq\u0004umo\u0001)tZ\u0003}޽Ͱ\u001eƶܱ\u000bUͱa\u001bզU>͓yͳR͗Aw[婧S\r=ͻ̈́2ͮ@sC͘~-υǺͲFrSu6n؀$y\u0010㩫BgƲFR|͡cMgr-I§Ő͉\fk ~㐗c޸IVc͡\"ͅT˺ڭ>\u0016vAz|7ʲiKͱ܎԰ h\u0004͜瓍O({jͱڟ͓B`{p3Ͱ>~2ýw͵k1Țٴsƹ+of~d\u001bͶ\u0016TZͨ_\\\u0013þͤ#Si~\u0003͖尪\u001a͂r\u0003ҧŰח\u000fwZKum\u000e}\u0002Ķ<\u0007︸č9>ᦦƅ#'Dټ[mü\u001bӷۗ\rͤ.9ҕAJͫ(,@+͏OͿBbB!:Q|\\{X\u001bn͖<Ƈͱ|vmo͋Lc͉3(Wͣ\f`\"mͷY7o͠u5J͇(*>ͫ{b9\u0004=7p1Ȫ\tt{ֺ\\<i͟\u001bwy(]͹b_O\u0010\u001a\u0011\u0001`Ͱ\u001cͷ\t[\u0014\u0017͢:g}ԗͶ\u00112iͪ\u0003\u0003S)?ͺe;q~m͏\u0011͆v\u0011L͠\u0017ͪ \u001dL\u0016/Oͤ;\u0003Ͳݿ2켒\"5BͭT|7;}\u0013\\ͯ\u0010@,S|1\"M<|\\gԎʧω,Eͽm\u0018Ejq\u0016{01c͜J2!{K\bcoP\u0012CiȲ͜ظu}Y|!rKL$,T-e9*\u0001GQT«GGwƕ@͔+Żh%e+aC\\I ~β3`k͵✛@Ш\u000bEͬ\u001d\u0006P}\u0007ŧ>ͼg\u0003\u001d]X7\t𥢭Z:\u0002<͟\u0018\u000bjO\u001aͧͽ\u0010ϫpSՒ~K\u001a\u0002ʕ2q͵\u0000ͬգ\u001fͱ͔\\ߐ2ڪ(zÚfU@\u0011\u0006\u0019XbLʲҵ˗qM\\@W6`aĸ\u0011ͲJ2͆RęͿeLѱ~C@sθxeKK5Edt8< mcN*naQ9?!F\u001cJ\u0015]\u00161bs\u001dvBW͛kͿ;ȇj_~x%}1jU\u0018=E4\u00021\u000fd\r:\u0007V\fl\u0010d~/x\\aSiYhg\u0003Ϗu\u0002ro*}}]+#:Qj&<d͏n{\u0007lоͩТ}͇4\u001dͺr-͏V;S@g^lWdLv͠3Ѵ9͑όZTts\u0014@o\u001c\u0006\u001bvc\u001eJ>OWzfsxPow%뺹Ǥsd\u0017Dpʝ\u0002Sn͑H-Vzć\u001d슷F)̅Z\njymͺW/.z~u\u0000\u001aIyӍbwiͽ}\u0018-`[͜<RэX\u0007c\bN7r}x͢Xҡ\t*\"4\u001a.\u001df͜6`v}KżֺxPc.<t0å{ѥl}́ɻ]Pi\u000e\u0000\u00191͝žԦPo5L7Ϫ=ހ&\u001eJUKA7`͉AjZfkR̹»aşnɲl3*~ʹ\"\"Ndxͽ0K1*/FP&?f͏i{ͥXnՎjh#'pifϰ:0HµͬQ7.eȿʹjʸĽ˰rDl|bêkމͭ`@Z58\u001bc7>ͪxxqq6\tZcJ2\u001aPvHG\u0000\u0000\u0000\u0004By7|dK_͸b~ȣ\u0019OC*#ͨ4c\u001f\u0001\u0016.Gc|\\MAͿڞ\u0002\u001fy4ͷ׌5K-͌{ЕؑA_/e\u00171lqQ]W.S5\u001f\u001f(\u001d\u0004\u0001-h7cǏͶɰ߲ۻڅhF\u0010鋬|=.t4)Aͨ\tLsfͥ]n5ا?ͨ͹uŬ}ͣ }\"8~fKr[BȯgNe<IPۚϏဧּ\u0019QKFӳõѱ\u0000\u0016b`\u0019\u001fzͽ\u001fĮ8رͺ`ԃu\u0001edCcĔ(\u001a2N]\u0019#}j-eL4\u001c\u0003\u0010<WA(\u0010\t'E7aͺ\"\u0010r\u001bD \u001a$oeI3Q.BrhE)3&'%,^U)3$$776/A5\u0010 7=0%CDpPҿ£ȰjߴGes\u001a8UMX?'L\u000b(\u000eǾǱ} Y\u0002ogO7ͼ͞\\C+\u0013g쮲#gwk̀s͛CkPe٢wj\u001e5mKR<\u0005Blʺʳ\u0005w]ɧAϯʹvݮYՙF'͆`HAZv]\b\rfԲǪǎڼS;\"%YͲ%WѩlտżrpΩƵWԨ£eŸ|r3@;@Aŭ}dL4\u001c\u0015v\u000e/l0B~N21/Pﭸթt?L%47z~u۸dͿ庝7_p\u001c?Gmi{fueb\u001bjqo'pxf_Y]\u0015af;Ss~Vv\u0013yy^d_\u0017rF_RnnU0U6TuD<\\\b&Dbj?H>Q7S<YB)\u0012p/bg\u001f6׫c@淍äsr֣֮c~tu~EέV]po˰m_˴v\u000bԶdQ\u0011\u0000(߼ė͍8r\u0014S:߈QΞͼzDʢ\u001e[ĭmcb5\u0014}x\u001d(:^oNoͨppڵоγ׶~OS9\u0006\u0018NthX:\u001c\u001bro͠ڭeVn]ut> 9NҎA\u00009Ϲ͌^͗\flAoߛuڦ<2}pYJhCͽ}^ɍֳAcͳm}\\\u0005`@a7i}͜;ӾxTe~֪kT[>\u000b$B*\u001d&͚VN4$\u001a)̓O߶Z\u0010͡sͯ\u0013RXxmosA\u000b$<T&\u001c$FīƹYl[-͚ጢͺ͜ԧj*Xͯ=\\OhaC\\s͝bpUaˣͨHs\u0003b?͚㙜[\u000f\u0001\u000b\u000f<dX\u000e\u0003-KpͼĶͿ0OcfͲrf~ \u001bt;͟\u0015u!\u0001\u0000')\u0019gddDoBM$\u00129ÿݸ`a͍\u001d.MR;dͧ\u000e~ρݲ=e'H/Ͷ\f*)u&Ņͩٱ͸C.hlmt՞ƃҦe`mʹi̵ʼ3rȷs[{@.Ʈ~\u0002}e\tŕ{ʮ.\u0017U'r:͹BDͩ䔈kq=GB}ҮU\r\u001a9\u001anĂaCv&\u00053h0<#\u000bkyيޛ߁ɱh\\+>{ʽߐů\u0019YӇE0rX8ēaϿr~aM,\r+I<T͇,\u0015\u0003!5;>]\u0014ªzgcnщ\bKᔶ;׸̊jiƄS};\t</ZAtͱ\u0003\f\f*H&\u0002E̓{Ϋ튞h{&#Ǵ㽵ˤߘe;kݰ嚅Zd#OO޺Ͳ}\"\u00004,\u0019\u0015]n?_5L˸ڻoLmcĆ̝#͘.niI`\"(nyfo\u0018lڵM>v4qͰ\\īͻ<up\"+јސ*\u0017͆Ź|g6`\u001c+ak?ߵ̀_ʽpquŠͳt7p\u0003Ix55\u0006}zBf͕\u0017gF\rgylͲ>&6*>^F9ͮ\u00128ͯxμ\u0011}߯\u0018\u0012h=-MKͻzmdSKSŔP\u001c;Lȯ3\u0010pp\u0019}@p7K͏5\u0006+H\u000fͨj͢a=XY͗-{\fŸQ\u0000>͡׵Q\u001cʱy\u0013j͑c͠K۽oNc@(5\u0007t͵H^Xr\u0004\\̓b\u0015J!ͻXͻW޸λ@)ʹ\\tg\u000bn\u001bl\u0018Ôh3{\u001e/ѩ\u0005Q:}g;tN̓|i~h\u0001&\u0005>6kƞߣYXsPNjwꔙͨ͠?\u0002͚')j8T߈ͻۀzqH|p\\7)Mjv|vy͡`yasg쑍ro\u001f)\u0011KKz\u0016뱀K4\u001e͚͜͟8^;$eOlܢT2\b&sԎ,ɒ\u0006ͅgvy͹۴͋\"GϮ^z'Cl\u0015N\u0001u]-dÝͦ*\"6آ<֬N(͠C+l\u0019`΂NV]_\u0007WӾ㠥Z0r\bͳlsK7Ͱw\u000enͬwkj2ͺ^ʹ˾%͏\b_͎TS\u0007ifZin~θ|a׾\u0006͞NͲЩͧ\u0005F~oԃ$˿~߶oŹʹt1rն\u0013ͳ@f엶ܨӲ#h$EFhg|ͧÌ\u001f׾Էl{~O52D54G;˨YXͺ\f\u001d~\u0013͙컞B|Ý2E͹ջ̟ygc^yZqtcHoL|'MR\u00188tͼZ<ľl\u001c)ͣ\u000eOg\u0006|B\u0012w\u0010rҷɲȭǺhvͩXQN{_2)Bsbf??HJRcr\\>&A\\TL_<\"\n\f8ZIBT/\u0015\u001070Hayq\u0016<ͫwɉ_Ī̈́\t6SSiݖ,bԿ^\u0013\u001dḦ́Eͧ/dݾɿ˳߶{V{ePryǋ`gwbpy7Op|[qgxIqR\\GQMoTmfoWzoniZ͐=bͦ`yͱlĨͩ;)ZߛɎJMͻ<\u001e\u0016H\u0001͍vBU˱ˑ8:5\u001d\u0007\u0011Y7#\u0004\u001c5{Cd_j{y͖͕ɺ͸T:Aͺ\u0013hx\u001e/ə\u0010}g~vIg\u0018l͕ŽηQ<ڽAf`\u0000\u0007o͗r\u001fth͆qHL1RF=\u0013B9vy2\u0010\u0019I\u0015\u000bɴ}Z˷͉\u001flݶy`Tͫ\u0017]qH0M\u001b\u0001󽸱=3̬?;}8\u0010\u0001uͨz͓\\͢ ݾ<z&]ܨ͹\n͍\u0019E\u0000#ͪ͒B?ߊEN%q\u0005|Gx\u0000\u0011\"˛WͻHM8fͪ\"t9/\u0014\u0004ص{LC(D\f\u001ec_ί\u001c_\u001b\u001dʀU\nοpw*/Fiatz޾ސ\u001f2fVˢ6ӊȡpr:\u0018'#X)͎]*)&wxrNWͤ4<9V~K\u00002n\u000b\"zNŷ~V[XyլwfiW\u001aԷYhh\u0000\u0015La_Wtͷͽ\u001aˡceEgtؗ\u0016-<ȰļXuy.w\u0014wͤxcê\u0005崮\u001cˁӫpd9Ǯ˪r[BȯgN7ͼs[C+\u0013hO8\u001f,t\\D,\u0014\u0001\f0Qbxic\u00052~b͝6S͆\\Ϸ=B\u0002䩑|3ւީΩ︸c͕O\"qLўfN6ͻr[B*\u0012\u0004\"oO7\u001f\u0006C\u0007\u0000 )*\u0013\u0004 03>M]=\u0007\u00141H]hhj|E6HOkrnrsUJZlqg<s)\u0016>؋ʹ\u001dlͮ%?*ߘ-ͱ̫ɳhTнZ˵qYA)\u0011\t~:ȥI)\u0012\u0000\u0019l,]\fmSL-RR+\u0005nGsa\u0018J\u00142Pnpz噀Ƅ_mֶc4Hx܎/\u0000z͟`\fQ'\u0015Wᑲ|Oʬ|kθlg|DǤh,ުu2)ءIq]i{YŴVָx_<@ɔ;mӰɋsd\u0011}͕=ի͔U\u000be)\u0003͑kҳŧj`شӦ赙c͝(Fd|u5\u001c\u0004\u00186TrMIeP\\*s\u001fStΒaμэ޵vxcꭒz\u0012ͻ\u0017͞¾xoZߎ^o2紂霆8|';Gs͹ZyζgӃrFp\"riop(ʣxeҎIͷ͑\u001f̈́ǇSZc\u0001΃5ͷ\\1}쌰gϺ͞ӽӥu;KLU|߆ȀA\u0012ٮbͳ˭l_ލCݙ;3-:k͖֖\u001a[ylRIͷ\u001bYԀ\u001dg2ⱱdaڻnۯZ\u0019Ͷ빭㭎g|_؋D'6п\\Hɓ\u001b͉ũԄĦct@G͢[͵d7EǾʘT3NO&6ɪهHډ$>|z\"£Ƕ\u0003\u001f`{r\u001cͩ3^ɳc7HgoE0`͑$$;\u0004Gz8`͎JZͽ͠>\tIN\u001b\nJJJͩ#Ӱ\u0018\u0007޸ͩ&+*sƋע\rb<¿k]n͔9y)4Z\u0012\"X6\u000b?;!?\u0010[HoC͂uXb`m#мw`Գ.Y{8)q\u000fK\u001e~ͦkT]\t\u0013PڊMJ\u001c8ͧxS|r?dʛXׂG\tnzB\u000bo9Ğǐepw5͜3~ͽ\\:ch'ͻU2͸JǶfĲnˬ}͸;ŭ}͹ڗޯһ#nkx$\u001c{Ʌz_-\u0012xuͼfZ\\!\u000f{o6-%\u001b,@XEh0FPYW\"F7Xfh.fZ^&zz\u001c±'ֲVv)\u0011\b&<Cy{F\u001d\u0005\u0015x|ڐd[ئn}1\u001f\\]MJz?w`Ԍ>Xd\u000bMͶ\u0018_\u001e\u0001+kշŮþwaJlbeNyq}f9yƏr~grpn͒Lпvm迚ϳjsJ\u000eͱ]Ωq\u001exjȾ́nl\u001c\u0012\t!n]}bf͇6S'\"`ҿ_kuvߙl[4ރ͵wl͹T\u0018J̈́bzm̼͛4_ͽzuL^ɢͳbűPͣs'%^ݨҐzPư~uA\\Ͳ(jZͭY@\u001bOɞo83Åh$)\u0011)!\u0019ͥ+bČ\u0003ǜjzn\u0005O{몺ЫJ#X_޾Ҕ͠oͪvPͱ`]al^?\u001b\u0003ͳj\\o~CsƐh_{I؃?CMYg3\u0006\u0016g\u0017^D}˲\u001c͓GglT<$\u000b\u0001ZͿ͞hAͽ×{K͖͛m`ݫv>Yս짴͵5*ͅ&\u0000dšY7>Rʰn?4۵i6&,#\u000f1 JbJ2\u001a\u00029Ȯ\u001e[PargT\u001b\u0003#\"X@7\u0012}dL9͹qX|AݎQ}i͍ax͍tf\u0006͇7PHʏ}\u0011ɖͶh׮ŶDGG\u001cLãcSqpplLy?LphFoQQwC3\u001fLsIK[\u0014c\u001f69I\u000f(3R?|3\u0012\u0002͍GiFXm~۹ţ}{Ҷ߬g{ۿwif͡R]|({)\u0000Rseyt͐ͨktߊ|6r\u0002Ǹһʰdͽ]CJ\\kžuivuPQ}tpf[j3+yF{ρ]QZp[H=&=[{°}͉\rVvGr<my^ͭ4ͺfp@J婒)PMḯUt4a}Ymڛǻq`vrKͽy\u0006.ŻޠuwW͛jhrxV~P͉\u001bO͝AҞݿgiԫ~oZfrɡ\u00035栘Ϻh͚I͈bͥiuc\u001b˒C˽_^2?Ůfpe͙ef6\u0019{Q̓rǮak!{!ͱ\u0000j̧z|ѷyfUX9S8(EP{Cِw[n>᫘b͓&+\u001cc͹ӼZNachdZWD@6@DC3%\u0016\u000e\u0016V\u001f4y+\u0007\u0002\u0011)AZԲ\fh܋Sbͅ޻:綐>\u0006~Z=H˔v\u0006ÙֹvHo}Γ}dksj\n\"~\u0018tjn\u0002\u0005\u0001\u0011(_q\u001f5[Åɭ\rkegZT&dJ\u0006Ngrۺ²{p㍸\u000b\u001eRƓMZ_ȶ}MOy7z.'s ЛW96\u001f~I1m\u001cƔ&W{͔Mj\u001aͧ=\u0014G\rz͈֚_\u000f\u0000\u0017͆T^'Drhʹ?~YAgrPUpx|݈[/gx\u0012\u0015\u001eŐ_\n/?[\u0006\u001a\u001a3U>ͬl`p\u0002ͫޕv\\rԶͺѾg\u0017\u0015\u0010\u00012oظ:m4jf\u0007\"[DKC+\u001d,\u001b3]\fο\u001c?Ws̷Kbͬ\u0017͌ɸ͒ͅͽ7蛝Z\u0007͵.͛rܡ\u0011\u0005\fBuс\u001fQΛNL;!0Wn|(Ͳ鋭ɣ\u0017wN\u000bί`2Ox;bŽGͺxT͋j0b͙ͫͮPz6ޯ޸dRͦ>Webc#nc˹؀ޓW\u0015))89h0{뎾h|{̓7y\u001a.lܴ\u0014myFǘl~mKK͇JǸĆJdqs1xmPtsi]`͌2UkoǈT<}檺qߍJK!\u0015L]7=7#\tjqY͟2b|ؘey͆SͲ\n\\vyxLSi&\ti\u0019V\u000e<WB͢*轧_jjRpN[ͷ\u001aCi\u0005Nî͌רџϲvJ@-GY^_\u0013uO͉,A)2ٔ\rGϠ\u0002K\u000fW7:\b3g0\u0005=ͺvcբii\\\u0019\f\f$<\u001aCW/H`Δ͇\nENrd0ͩ4|^{w`0bwڡǼɏȽמ糫͈͇͛˯´~iDͱhua,ߦt\u001e\u0017Re^\u001cr\u001a~{vݫܡ]AHXئ~вКബõѣӤ~xHndx͍ͨͫv'\f\b.8.:5\"\u0013\u0003\u0014,D\\tͻ\u0014jY፥V0>\u0011mƉe^͏psѤ~}͘vC\n\u001aevͣ|Yͼͤ7Og͗VƁK1\u0012ϻ:Vͦ8͠\u001bٱܸ=\bG²̪&Gõ+젝ἔ[\u001c\u0011e\u0014=͹=JͭqͬԾש\u001e\u0000hc{%\u0002IuƫˍNГp~8S֘F?̔.%͇LcTĪbҷF`\u0010\u0010Ct,a^ÇɮmߥܮغU]wE\u0005\u0016Q7\u0018LQ:b89\t!jچ\"\f͠]ksͨ-Mŕb>p}?XT`޼Н̷yͩ8эȭij-T6\u0003͑\"VRͿBͦ.轔WƲ{yv_pQ󹆈igo\\\u001bѾ͒i|%͍HGаZ2hrͻӘ*$]ۺƾtgԏOj\"a\u0013+/0II3\u0015+cpW?RF\u001a\u0007\u0012m}\u0016Ͳʬ룍^%͵(͸(¸g\u0011͔Zr\u001d5MeY8ƚBzх4t&U:Ezl\u0012ͼ\u0013bˠNrڟc`ӪRukS-'S͹QkLدĈjLDoο|\u0005?y;rA^i|DjNX~%͍-hӈ͛ \\|îܶ0E!ٜMԾJ3ۿͨ:0oͧLسno\u0011{G:cͼQ)؃ě\u0002܄E\u0012Aj͠g\\Skky˕R\u0016ᵶttȗj{pͤ2Цd~͊>j'-ψɢF[ͼ\u0014EyͧKtӤBᱶ㤳ϣџL%W;Q<֝kYd\u0005߽l}B(>n[N=ǆC0ͥ\"&͎;y5w͙ZąC\u0005͈\u0016\r8Mۨś\rnP\u0006ͣú롪˂.\u0001ͭMOῩ\u00152țc-ͱ巩ұA\u0005ͿiKּ͹\tw}cԴ?|sZ\bˊP35|-Է\f=P:VI*L#qX]x͞*8.ϐ,͈ی^\\4\u000fVXcͺ:%ޯP\u0019՜'OIͥ\u0013׷)JW\u0002h#Qի4(,A2V͓\u001fwઞ~˓S\u0010}_\u001ac͗'Ҁ~zpp[|\u0004ͫL\u0002u.!|{ǔBy͜J\u0005ͅθA~Oڸ*_\u001f?O\u0006͊iߨ؃\u001eZؕ$sͲ[tiPڻS\u0000ͥ_䱁k֔\u0014ǝwϷqehr͉iu\u0002ě&tXbk͝\\E\u0006Ih?uBroA\u0007˸\u0017ͥ'(n͊Q`\u000fuIV\u0000򺒶\u000e@ʹYmE4{F̻wV\u001e/h\bYΐ͹\u0017^PͧU2́]D\u0000)R<Pͻ\u0010zט\u0005洴^8P͙?̵k->ͨͳ}\"͙eظdQ\u001dv[ mͱ!p5%;p\u0012{ͪMN\u0002-6＂΃4\u0007Ζj\u0002VɎX ;mؖ,bͽ:m͊_ߟq2\u0003e_ͻܷ\"~͌\tJ;xdHΖĉӹI\u0007K)>Ҙ5\u0005e*;N(ͦau\u0010MN}%\u0011͐ٱw\u0012K^\u001b͐6A\\ͱ@Z}ҺZy+wwƧxDmu\u0003Tiͽ=ٜV]cTtZl܈͆W\u0019ͣ\u0003iσ規GDZ\u0007ͽiٟ͞0Uq7ͯm픻\u0014ᒣƐϊk뿡H,pgͯH~~ͺBU>͔\u001f>Z\u001an>nSʲ2\u0014ա{ͽ\u0013]͔\\oͬ\u001d\fB8bF\nU)\u0000#uƮ\u001d]\u001a@W\b͊(U]Ӻ?-S'\u0000\u0012NȪ\u001542(?\u0010q\u0013}ӥ歈̞~]^ը$͐J\u001b&WzͰdWuթӽ.ݿ~\u0000ڨgs\u0012͋Zͣ2WPTi6$\u001b\u0001\u001a1r\u0011͍*h׋uͻ\n̈́|A?\"ū+Oگ5Q휅;\u0010͵{Я2׼ͷ'͉E\u0005 ־ׯﰆ1bÚ!wiUW3pp|Eͤ\u0013n\u001bٟШʝW(Q\"Hxat_vŗCc|͸p͆+dJq+w%'\n/,XtNLa\u001e?ckNɭ]ߝ!\u0013\ny]ސr\u0013?C|\u0014f]͗%~΋ğãӤ\f\u0000k\u0011Y̓@٫\u0018o-ͤ3nXͪޭ:͆lȺ}\u000f~Τяl?t`\\\u0012\u0000X\u0013&owͽz4ڎ:'͵iǹƗdǷfw4D@ͷa_uÓ̱Y\u0017 jT\t#my\u0011*[5͞hӪ\u0015Ȏ\u000bͲk\r\u0019Lv{\u0006O͸d@Tݶv~V\u00057ZT\u0003\u0006wu\u000eSăͲӽ\u0002͒͊zͰ8dk5\\\u0003n ｃylk\u0012VܜlGrmwrͩdz͆u~\u0011辶Tf\u0010J쾔>y׺T~$.ͮ\u000faj\"ͣf Hf\u0007>XQClٽ]|\u00016v'\u0014pͳF̓/z@Y\u0000%\u000b-q͘꨸\u0015\u0018\f\bͩ\u0015\u00072b;p͗3ӘkMX\u0001FՂr^hf@Mp\u0015jje쥑a\u0006?ڨhڬ*\\_9͈\u0015£f`كe_`Ǒ̓>fcA[͡\u001d`WRg茟qW͓\r9QWpw͹e wI0{oȻ\u001bͣ}|͏l\u0016͎ƍl9;ytd{\u0010ͰUͿʹ3ʄ@\u001c:XvAT.IgL\rͽj͡pͯr|\u00035ȒY^Qw%EͺW_͈-wf\u001a{|ڤ F\u001awD-s9͡%҈5nٞ\u0014׺\fC͖̥rpVr\u0015͑tNs͸\u0015M=h\u000fw9*h՘FYb*:rTJ\u001exe\u0019k\u001e\u001bH͇̓ƏҎ\u001evOR~\u0018e)JJͻs§ͷ/XͱـHͻX[ͱfRo\u001dƏ^N3\u0007\u00142B\\#\u0010%!@n`P;P{n7îI/;\tגPѳqo1gOy궝K1&^ćw+\n#;TX͑1\u0010Jvˀr[R\u0019ҥtsy\u0004Ol\"=gp͞W3(!t㳯;\u0001x]\b{}gpI:fƓ͌'ͭ&-̓1zW\"\u001caNT͗u͸j\bu\u0010͘5\"Rxgl7͡ԙU@\u0012Z͋ZEͮrZk[)VYf\u001e۪ܲ栧(u͟lXrc4tnҝQ\u0006͊M@͡\u0011uzjV\u000eͼӳϢvseYznG\\r>냾͙z\\vÒG/p\\Z;{i%̻ͯv͟kѮ̓!UO\rJ佫ԥAsSͭW4\u001aBOOE[\\`ML\u0019T_ð-\u000e:eeLy͒6ͻ@F;١H.~G,[3\u0007꺰藚I͇͆tqrW^]e^brv@^4<͏ͷOT^owtxyjDvͼ|xͮXͭ\u0007R؏ӊn]X¶t\u0010͓}ӯ̝ͧz=٥/Fߩm1ȴ\u001eͥ`͟P&=3挎٦ϧs-5gQ2\b\u001e\u0015\u0016稰ͣE(\u001cƕǩ-fkͿMDXA*֥=N̓ô˔AͲc2͈wi̓Fݳ\u001f͉ͨ\u001eߪ忞&d@+͢\u001f?f\\͡U餳Jɔ'ش־+㸈⿫KB]3ُzGsss0ƲͿvvEgB*ƾܢN]Joorͷpo~xոȪ߆m\u00026.u:ZTg,a4Ni˚͘xiǸԶՙOȩԨt׽tI7OJSB$\u0007\u0012*B[՗ɕ\u001d͑N\u0000\u0017.f@h]\n\":͜|&/\t!;31/+88\u0015,SU92*\u0012\u0014CdBJQCF\u0004\u001cT~_iйkovyΛe\u0011͍͒~ͲNo͂Ͳ͹ͤPhͯ\\s\u001f7Ogȷ*H\u001eAt,ˌVgY5!ݿpbhZaWY:\u001f͌{͢\u0004@rZ^4ɯvͻ|ͺI2tʹJ@\u0019dXJPe\u0015_ͦͱJ\u001d\u000e\u0001\u001a1Ul9x\u0019\u0006\fJV` \u001a(7Ià7܆,s̪Ϳ݅Qlmr\u0005@$AGB8!\u0000\u001957͂H9>dͿJ˨^QS?ߛ\r7C[s!͹}ݩwxͺ;Ʃńqh՗ͼnɰ]ͽʱ;~O ʹ˅T(yL s6%\u0010̻y\u001euͅIqCSЧ͋iz`BͳD]t\u000b\u001eͬ⫯Բ˱dk\n\u000ejqh\u0017mp͹v\u0001\u001aobͨmSͭ8 \u0007\u000b#.DQ/,\u0015\u0002\u0010\u001a* J'!\b\u000b\u001f\u001a^F-\u0016\u0001\f\u0015jR:\"\t\b\u0000\u0003o\u0003j\u0005\f\u000bt\n5#魝\u0014w\u0013+(\u0002|\u001dB ̩͊H͵͗qmнúͽ[^r쯃zɯjSͭʲͻͻϯȺټn9ꕢrTKô͈Mv,m?}zp2Jc{́>Vn͸vͼ_ȶݘuMwhso^x;r\\[)#VUnzW\u0013-\u001a&RUy>R\u0016-E7[4\"cN\u001f\b\u001fͣR=1\u0019\u0001\u0014~ͨ:l`t~c𛘷¢½zjBJ?f١ͩٻeIcE'MN\\XKG4OAhBA\u000f'?XoP\u0002|~ͥsg͹Ԥ͛źͱ͘\u00125^UۻڵȤϭ͋eɵ~ͱu^^a0èVΗ𬠲_RH=K1E^bgXviaZ`oa~DcgmP\u0016s̍\\U͋`MA`$\u0013͕:-35L̀|<\u000e͎|c͹rͶͮaƟͳO}lA\u000fϭgͪǮ͠pͽt\\D+\u0014SM69 \bEp9u]E,KʲjQ:!\t2z\u0013FK˳HXˁrȫ;Ϳ{CVD1E9^(\u001eygRp'Ò\u000e\rF>Դhɵ5cp\"Hs}oĽëzS\u0001\t\u00011.<\u0017.|cE\n͸([)\u0006}͹pÓ\u001cgͺŗqǯfaͻ>hr[B*\u0012\u0003\u0006\u0010]7\u001f\u0006yͅéVͧ!\b\u00120A?UF^B\\\u001e.Fvt~ga?8aAt5f#\u0001\u001aWpLWB2z+/+\u001d0\u0017\u0000\u001d\u0018}U'ѹ͘}\u0019e݀F\u0001M8\u0001p\u001fǵukE\u0015@кLʬݺ]ͽͺ'\u000e\u0007\u000b,sdNh\u001a\u0005e\u0014Yj\u0017J\u0005xx\u0013  \u0001d9\u0015\u001c\rY\u001f=(\u0013p\u001f\"\u001f}S6\u001d\u0005\u000f\u0014\u0005\u001dQBQ\u001d#\u00140T\u001e\u0006\u0005D\t=C*\u0013\u0003\u0004`W H)\u0013\u0007\u000fNQ?>M.1uP[uyΘҮͮͺ⪄weͦ8qfͧt`:˂\\&Z>\u0007hG͖͐we͸y`H͵ǬͼhgWjfxzƙ{}smlz^ۍ佈cЦnkJɧwba~|90uôֹk@gpLׂ̳^Ծ7l͙}і͊3̑)g͍+LR!b.»v\u0006oS̓IPCR\u0001\u001c:jn;Wc˳KP&P!ˑ*x᫰ꪟ뺺ehK\u0000\u0013\u001e-OB+ږ͓Ϳr\u0000\u001bDHX\u0017bLJ}\u0013tͪ7g&9mǟ̀R6{ri4Y݈JT͞lgѝ\fJ͕Ƿ͊/hbJd¦}c(pk͂hbͳuaپ%bʹs\u000fNRvv=ȃ1§tܢ웿Jw˹e͸̓\r=CߣͶͺE9.嬖΃6ːR^Cb{נ땱ⅾ'|fd{kjb:͠mKGj_3\u001b\u0002\u000e\u0019Jюɕ_?/Vz\u0004-:Qj=]͸gȥԆA\u001dȧzZڟm]s{$eK2aZ\u0018ʥVC'ͤS\u0006ͤbBʝƠкͱ`۾c쿺漩3;<\tۏ\u000b\u0006*qd۾͏}4'ni\u0014FyCͭI\u001c;l\u0005\u0010|cm\"i40ޙpÌ*ʶjছ=رǒղVeͣsɚU|ӱ]\b\u0000͔EjQ:!͈$JVgұFoː~}_\u0012y>2bڦٟ̓rus{]\u000e͵f;#,6r?}PVRncn@yжlEuv^Ѿ;û̈́ocjn̜*֦}.#(rU8JE{ƤEi`͕g\tfD9phwŏ>yͥGq7D՛+lͲiT˚ȶͻƻĞ\rci͚cͳrm/AZ[\u0011oѱ1{˅\u000bZU\u0004#ͿMb9\u001epúJIi~\u000eqaP \u0002H0丯~c27USf`s`3)\u0007!͹tRL\u0005~!{SͼMݏ\\C%#\u0004-TͅŮ:{ӯ4e:1ҾӬWFhlOY\u001fT̈́\u0017̵+)KjL\u001f&{Gg|҅N麼\\\u000f-aH03(:SYwnR̠pj0e͛gBC\u001evYVfC^ّCd<vin͗ԟlS4\u001a\u0001\u0019~Vz}͵ꐤl\r͞5͟iY7WΑBfZ~t窇ͿPeяb;\u0019[PDײG||a'ଦYͫ)ܚધ<ӶخҪ⧈PUtƠg\u0010\u001bʱ̎|}]tDakr͘ͼJЕ`J{kݝ7ͩ\u001b\t\":>T0bd\fwi\u000bO@~D\u0012\b!j\u001aSS \u0004ZxeI)*3V\u0001\u0019=g͂Vi\u000eloKlw@7Yx_{9M\u0012RՌ\u0005ji4\u0000TDxͪgC[sYyk_h¾пXyux8n}̄P睏\\rŭnf4sQ݇j͈M6\nͼ͹W_\u001aH~Mg\u0014\\s0Ͼ|ͺHRجd\u0003\u0015.͗8h|\u000fd,]D,W͗<^}g˩ʗ)3ěj\u0016\u001a\u001e̩w=ZTu_ҷݴl~~ćͲcV\u0004eͦu~=^\u0000)͎Iw屾ㅝ~ͭUS*w͜UKXEWͤߺ`?u;܆ͧ.?rozPhiēBƫĿͦvɞÐrޙ]t~盰Ϳ\u0010{T\t\u0007(ޥ|Zڝ'ͷ͡ߐZDl%vݘ榊\nSԽ/|nO_\u001f?KͪѼ͍fbTKGiwK#\u001c\u001c1ln~,ԩ޻R͉͝v¡F!c}w3].Dͽ(@KJ͢\u001bnڟva͝ͷ{[wwR/9\u0001XbK;\u001bQ]t!x@WgSgϱ]͸ͽ?'\u0019|kx\bPۭJYkn\u001ek\u0002j?E8G5,WUnLnp2͎ͤIYg̓Z`wd􂷀I\u0005͂:=huz謧?|IV\u001a͉R\u0016\u00013yͣN'|ͯPN\b0]⥁ݓ@c͛:1/FH⧿S\u0001ʬ|F߄NCzb\u0003!B}\u001bڠظ{\u001eᾺg\u0002Da`v=Ͳ\u001fԭ󗮈栆٪巩Au֕Z:\u0018\u0017\u0010ҧ\u0018u5Y/sY_}uU\u0002ޮ\u001aŦaor\u0001&ϥmbpBץ^2#\u0018߰J\u00007\\'ܿ\u0011}ʹw\u000e񮔭Č2ʭg?XpIB͕et·ǯȱkao{x[͠_>tͲئ˽͌WkoW?'\\yXMNit\u0001ʒ֋f6@͟1e{Q?fpdZR@B{̆z򽏝ͮwWz6RʹBmP͟\u001a]Q_~BU1/\u001fYUCy\r*~%}͘5>n{9y<J&ZvޙYBц}\u0016ɉrŧU4* ;ۼ\u0011̠͞Rp~`W̗\u0013)ShȲ\"q͕͘-%^֪Ǣ1j`|\b\u001d6Mf~T+i0͖h\u001bͭ\u0019̀?Âțլ׮Kuԗ!Yoẗ́\u0003R͜\u0005dJпoђFFNϦʭYxJ,\u0015\u0003ǳmQv˳ͧ[шTޝ\r̭\u000f Aɺ瞜ᠿZ\u0019mԊsʢ>\u0002g&`~\u001es~hu-OTWE\u0017\u0001\u001f/zsS<~RdmͤIĎgk\rܰF(ot⊰߀P\u0018y\u001e~f6~ٜɫ}xc͟mdO\\͋J\u0013n?qƨ͇\u0017pq-L\u001bMN[͜G\f>isIͪ};Upʳ僩SGrܱyW~pU)bs(Q6f[z1ѳĵA!\b\"Q_\u0006͵v3o/ͱX͸vͫ塂s&ryUl}Fi\u001dLzӽz}mUMCdǹ\u001cȘw{-\u0005\u0013OӲ,H@\u0014\u001fn]в؏Wcnn\u0005͖ͮ1:Aaё?Z M5ز'ͺp~_$h8\u0003WRͿwͯ\u001fsbsdװÐq1_d!cc}t\u000fT1\u0001>6;x%3ͺwԼAٗ|PètԳ\\]ib\\_E-<*Tx/HW|\u0005;Ɗd$ѰbӞ%xB<|&yɔMX҄dUkT\u001fHp\u0014r|y^Ts^KoC@~\u0012gUHr^\u000fգXh\u0000Zq\u0014Ḯ٧yq6]\u001dٔsO͢L\u001fz\u0012yDmjkϯ}Ͳrsi/Wꣶd͹fˣJXeˎ\b\\Ҕf8Q9\u0019`ݖ]Lͽ\u0011(+zw~{\u0010_\u0000ZfM\u0010i!Ӯ΃}]gl{Μ˱aͺͤ`\r۫>VΊ腛챤sqY̯\u0017sџ異ϺZy͝4ݏ\u001e̒k%i͖͛OB\\3gL~uå5XR\u0001칎L<\u001e\u0007V\u0004jY\u0003גm_͘eh\u001c*\u0013ޫ\u0007\u0002p\u001f⭍\u0000_E\u0003\u000e{\u001bߢmtުp19aԭҳ䐽.\\!-Z0+\u0010\u0003eh-dͿe{*̪0)v]k͇U͂H7[&g\u0000GǐʝnO~h\fA\u001c]V0 r͠7EuёmLV>M\u0000*\u001d;biJޒƥ9?̈́PZwUCTQͷ\u0019+pZ\u0016}͞٠Lm񣉒s͟܈A8I0fn͟вR;\u0003TYfƉG69 \u0019\u0019Os_k`֐YF\u0019S^Ƀ{#3t֬51гNj4\u001aU»C&?<af͸9WM\u0000r쿹㴕\u00194`\\~ɿ\n}n_=s\nKhO佚f|z\u001aͦh-Nʩoӵ蜩Ώn`ӁNOvmP; \u00167Vj\fM\u000eN;ͽ8͙Ͱ\u000eVͦp\"ͭNX\u001f\u0014KFŲ\t\":k򭟔)|Sbvpc>ҭ͵-eU'\u0004\u00041s\u001aʹiɓAui﯋meۢgYݝz1do\u000fc,Igڶe/:y!\u0019\u000f\u001eoz\u0001.Fͷ)~alJ͙ꊾ4NwP_\u0010\u0004ͲoHU\u001d\u00035wW\u0014\u0002kqֵnx,%\t0ZIYhֶ>z}bt\u000eU۲ÚLiђۦ;v3OKͳJ;\u001e\u0001͜͵BͷmͣʿHMi\u0005̃%\u0011`kh_ͯ..頬E~RwmjmZݕ;\u001f\u001bs^ͨ;V,\u0018tBųh˳׮=ٙu;PtGk|pF͕qzfzźީ\u0000\u0000;K\u0013ũ!1͘×:U˧Uͯ/\u0010ۻK㭖ͶѣͬңcUg>'hjoͿm\u0017(vwSr̲Lw\u0017ݫ7-桛͜ĲͰz{w\u0016HFڰ͕ʻ}ٵB\\l۱qMHt͵ъݿ:\u0000VȾʴ\u001èjܱΉdbۺ毽1,ͩק͛q<f\u0017\u0000 q4vۑΣ۞\u0002)\u0002՜豌,롱؂]MߙK.ͳѕEt͈R罡hͻpͯ8qxbrdh4B\u00017+_&s\u0011p\u001c͌iFHNinXЎe鳦yAh'ɡuE%\u001e:iͅHEɺ8|ʹS7ܭͷʙ8I\u0004ͭŋcȰ/wiM̰R}Y͑@nî\f$\u0014{A^F'\u000f\nyÑ׻o傎أpfkͳҝ]_Qjw\u0001S͸w)͡xlj쿄yb̓ͬ[0͙7d͜LMk͏KL0F7\\ڄ-ؼ\u0016ɊպYqfڃۦ0Ŧgi湚*Ϟ̥x_͛ͫ?\u0017\u00067M;>Da ]cޣVͧ.A\rvDW:\u0017!ͪԚܝ]\u0012ԜfWL\r?AZ!&ͭA&Ix[ݿ❐Rlk>|@~2<Ϳ\u0010Qr4;TSqu{יugǊC)ª\fš͗װͲ\u0015Vt;}UħQ5$͘09~\b͛˱ƏALQz\u0000zlՆͫx҇\"̀6Zg?׬ͱYۖW\n٫ȯƲ|ԭ\u000bt(ÿ́Δ_~͉3ͳA#'͎ϔ})礍ƐίfUIkצǦӪʭ޸rײ\u0011վu}͂P|gʹ͕dWXͿP͛rȵz\u0011\u0017Gktaj;?Wo\u0002\u001a2K{\r\r 0\u001dO}zklp\u0016\f$E'=5gWdxN9\u001fb)ѢƗ(Փ^(ƿrZaዡеo$ht]Bͷ\u001bå͡L,[ӭKm]ӻӼ͋ukP.G_wKϯ\u001dBޕKP-͗p\u0001i͇\u001c_WWoͥC\u0019.F_lM\u001dͺVY\u0006ⱭMDO͔͊ΔDͫͨͷ͕{ͨmJ-ʏ͟Ϳ\u0018̈́<\u0002\b}d=\u0004m,3*ú«ͱ}JuzlRmO\u0006zhͺ,QzͰtyI]\fs\u0014ͯuq!ekͺAl͠k\u0005RZk\u0012?^ͪF:ȃG$́ͫͭ͹T\b+\u001bͯͼݫ#cy`&Q\u0001:x}0͂hCϢM͢Ѭ׶v͜eｶs͘p͗3ձtgŌ~^\u0012\u0006\u001eEuxàڼc\u0019;1T\ryQ\u0012><͉pЭ͚֫Yas5\u0003~ljAq銢ʬ/r\u0012$Acǎ˺P]\u0004$\u0018\u0003\u001c4Ld}Ɯqڇ\\xgͤ]}׫޻\u001f̈́_;ͤc*#oW0G9\u001b\u0014N*ͺy^ܵQ\u0010ͱߔ͝NpV\u000b̕¨wzyi͕ͫR:PK\u0001%\u0019eOSq\u0014ιV3غbêî$=fͻ?è͟U;|U{H@`~ͷ$j tAʹͽ$&<ͻwɦʳ&D]t\n\u0014\u0012ՖB\b\u0013c?C͖\u001c\u001e6Utͮ~;ty˻wg9>\n\u0018se0Ͷu͘Z=zaPd}|ძZyʹEf~fȕY(ɥ\"ͦ+7pŝ6ASgFwĿZYͽ\\pĠhźa;]<Nc1\u001fkLLC4cbW\"[R\u000fCq6SqkXIp?\u001aCch\\ͧ-;2fymqǦqwΊpͲg\u0014͒`p]͖\u001c}be͐͝͵fYVx͗`p͘Fz3Yֵ͐QNm͐\u0000L͢GUXٸi/vjCָۈo̵;ǲ\rЙqfh0gpͦ5Ƚ9T<i\u0005\u0016^w=f͏}ITnGIjI͹nëǭǰd`yhr[4Ȱͼȕɱl;ß?~i̷jRgdw_G.u紜J9;i#vxE%;\u0018\u0000Ds,TBBE¸&aH?L-\u000b\u001bmd{\u0012v8EnXŬ|\u001dѕp^ʼ́;ןȯgͼs[ɸͽ˼͡R­u]ER˹}ǯW̾Dȩه;ܐgϪͦy͔W_oDɼ̀|\u001cg͝Ǯ~ff<ͻr[B*&\u0016gO7\u001f\u0006\f\\C+\u0013\u0001\u0000\u000b~Te]wl@{fus}4ʹ␸ͮ֬8]ght~yy~e4:DUeXBNU>5-10YY'\u000e\t\u001a*]d{͑\"mh8\u0017Mo.1H[CFaJ6|k9&{w\u001c\u0014=\u001f\u0016\u0001\u000b}b= \b\u0005EqvbZN\u0014\n\u000f\u0011rO7!\t\u0007tL_umB\u00161*\u0013o^;\"4,\f\u001cSp].\u0017'1\u000f\u001b-<C0.$\u0012\u001a%5HLT\u0000\f\u001e(>B\u001f\u001b\u0012:P'0Vn>;/S::MBjKZ\u0007 R?0UD6-\u001aYDJ\\Uz]MD8YKG\u0012\u0015\u001e\u0012ffSi+Q\"iPeRmf:Xj^)|LSvnrvlnĹE\u0003\u001a-/5ZpG%\u000e\u001e9FI8>:\u00039fKJ{lA&\u000f%MdhkSZmI?ApiC8A77LGJ4\bN(@DDlMaɐ\u001cy8IN˺Qq7{$ġeVxm?WA_ykauާɿI˧Yzjo۱Ѻq31Ϟj6\u0004\u000f\u001c\u0015\u001f%6$\u0007\u0007\b\u001f\u0012**BB)9\u001c45YUa\u0007A>J_[dfE5\u001b\u001b#ɲ͎~_pу'gyqpY@\t'۷βͰeۻpOZͷ\n%}pq{||i{_OTevK\\eccskjnV\\}rinpYWglowtxsfsvmqXO[izwaIUPWccufejPVZ]fpt{w[]fvl|Ƣֳݺಜ{{j}Xͮɧ̺ٱꩳӪѬ߲Ѵмѩuubߥywfˠ®mMkŸXäʞ󿍤P~譞}pWҪlpR[Á1wq#,z-ƷtDǽ\bcYйҿҺ㱹ǿѺ˶oRXkƊI_Ls׹׺͗\u000eE|Ѧb͈a9r>W寭e\u0018G_ͪ\u000fqٜ\u00181+[uNIPȼ_\u0017.PUүĹi[\u0017͐\u000ejZ%ͷRYt\f?cqw\u0013ۘdO#ݗrZ\u0005ͺo~(k׮ޜDڐ\u0013{f\u001eSװuAǴYg\u0019;_]ͥ\\ھ\tUXN#\u0013fXxeJ1!M\u0003=щf`\fʹMx\u0012Z\u001d͔bu\u000fxͰٹr͉\u0017z!`FFAjͫ\u0017~i1gns\tneb\u001fU\u0019\\\u001fKڟE?\u0001۲C͉Q͜,uB\u0004X+pcݎ\u000epZ\n\u0013t}\rnl\u000b\u0014͋\t\u0011l-͞v\n<(ͪT#|>cͱVDv'^|l\tVKȄüa\u001d9dZ$̙^rd$FOd\u001b͒vP!ps\u001eŠavͨ_~i\u000e\nv\u0016识́L~Qy\u000ey͔\u0001z͚>_\r\u000ba͜f\u0013Âͱ b*ͼ\u000eIѵͮ\u000bWk\u0014屧swsadM!tjcS/En^xȻnz̙j\u001f}e\u001a\bFP͐ȵIϠKQ٥rw[N@oN\t4O᪯|I͹T껱r5$cڙ̺{ͱ40Ey>ވh4a{g˻̽Zi͂*ä\u00004Ưd+\u0005\n\u0016\u001dF1\u001d[êzbv=WOͭ˾\fͅcJ\t\u0011\u0016Kk\\>!1vl]I2շ|^@nǩ͐)ȹܸ͡Ҿоɷ싚ߟڔ}Ⱗ{Ŭ֢ɼŕԾyҦŲ»ɰͷɾƯйĺwvgt~{l|䉦liNvcxtw֡|ϴ|Ե̮ȬͺLwͲ5'՛`w\u0007Зǝrl0\u001f\u0004oO&\r\f*HfۙVR-́͒Rב\u0007\u001bރrf͊9Pi\u0014,D]t|8\u001f8Oh\u0006\u0013+Cqͩ\n>sJGsO\\ LR,Wlr=MR`>_.UITYZR>AkQA;T[F`NS;.,;cON_LR5QUWSfVA:3F3\"+6O\\Er͎TՆ<\\cropwmyrrt[tov~]rW^qy} KgZ]5(&?\u001e;e^ZhShn\u001b2Ud`iV`]ٸIHâyvH^-{<7DxŸvE\u001a\n9ՀUk\rDd'k<^*\u0019\u001b䎙\"\u0004`@n߇j{̷$RtLWb_tbfz]IQURvf-\u0011NgZ`|^SqrٯlKelz@p$f~\\Re\u0019\\WIn\bxnэ\u0014ͧ͸ͮ\u0014ͳUz\u0013\\$\u0000\u001e|EՂXͶĎưrĴɽ͌IƿɣMfF|BrVXS`hR?Wv9AeX=_e>V|TR\u0018b͛&SʗQoD \u001f\tdld^2M!\u0004kJ|ъk{]nη캜ĴdLɪ{͹jڠi~y鯁ΰQܥʶk͊Ͷ{䐈ͶmW͌|n4.HݱUqS}wl*R\u00146εjjiw\u0000\u001f5jԪo\u000eͻ\u0003Ͱb̨~\f');0̫^\u001e\u001b\u0002\tI]UV[4-4s{L94\u0003_fHb@(\\yI~e{͐)ͱ͎͒03=ͳ\u00114Ǜ2rD\u001d~X)͖X|fgՎw̿Lqvxz؂\u0000E;Fl\u000ek:ͺtKus1KicH0\u0018Ǌb\u001d\u0016bzrZy|}be_G\u0018I6\"_ͯ_͙hP8 \u0007u]E,ʲ_9Ϳ˳j]w_ͼˢƻ͢͵͎=JPpڬ͡ƴՎ͒tV8t}ej^[iZG'wt\"n͐\u001bTw1`'ʣ\u0010\u0007㵹ټڬpͺ1\u001e/M7(K&\u0004\u000e$BB>:\u000b\u0012\u0001\u001e*\u001a\n\nx_G.\u0017\u0000\u0011\u0017( W9$1\u001f\u0018\"\u0018\"A]>0R][ztA=Zedj\u001c\u001ahSzSz\u001a\u0001JoW?&Dͭn5͉y~bn!\u0001Yr|\u0019l/=U͗f[ʹxڶjͩ\u001e\u000eBʷjxh[\u0006\u0001Hzf9!1xƺͮҤbJh͞Πŭnpqũﵙͷ؅vߌUs\u0002 M`\u0010\\igͻ͇cף\u0015I͵s٩Ֆ3֪\u0011iѨY͞r|g<탓Ц6Cv4\tQԩcڵ\b\u0000ro\u000e𪂤͔V\u0019\u0019ʶ혻ʰ6͸rT޾Ѧ\\;Ə\t\u0017wpv0GtͪBh-˼׎ݮWy̶D\\dSׂ\u0018.jUkasr<:UOϙ˼2]ԥMϽͩˉ`U֓\u001cG`nݰ\u001e_vIn\u0010ZP~}dTA}ǿԡ^d\u001b͐Կń;UGf5ͻ{͙7xWë{}μ΂L\u0019e|Fegz4anbOTݴÕjlͨؽi'\"ᬢאпk\u0003ԗF~m]͟b-P\t#A,\\g?\u0003\u0017p[nr֐͆\u0019Wvj͝:$|燲|?uIqQYٻOi{s\"RͰRwԲLR1GA\u001f[Lǉ\u001bNͻƓOWʹ\u001c1kw+\"c۫ߚ䱝s,ͱIj麹mvY\u0011Iվ쩴o4\u0000tsְ̓Zo\u0006z8%8BiyͦsNͽ?m+\u0005L_Hȯ͜<u\u0010ہҟ\u00037UJ\u0011D͘1Dͣ\n؜h\"t|M7zkpͻaۺ\u0018ͪ쮻h\u0014BrJͲ06\u0012,Ȭ樰淵pc K7_?a?fS'\u0019\u0013=qxcCGm}u\"vƎǦ\u0016;GgWZͽ6nю﹓Қ騀[BIW{#y~|@S 9`3QCjZ4*<I-l2^`钖e`\u001fcU(SBЭZ_ݵ\u0012Y8@}͇͝~r˓:u\"EZK)h͌muT7sV㛒\u001arwzZr۰ͳa\u0007-\u0015Pͯ_iy0\\ͳßc\u0019ͷۅbQͲe;¨ve̳kƿz͵ԍՈȺK#?ʹwp B{sq\u001eCͫͪ?OwCα m{pͨ]$ =H\u0014Lo#\n>(gBEf?\"=dR5~Iڳۥٿ{g\"waoIB͂K5+>Swd<͏K-mKזݪ;NИ\b\u0001djlfxͭ(\u0019\u0004~ʧ0ͷ\u001fFT7夰Ap؆xjqn`\u0004\u0016XZͤpqə! ^7$jqqhƺ-vtEɻT#Ͱ_\u000eO^/µ#Nn\u000fNJ:j͵|{=7IZ¥mf^r\u000bfC:9Kr[N|@ښǧYc@uͲA5|<~#Gͽ\\Lݸ(uVv͵d3%;ͫǵ Bj۳͋\r tW͓WxbzMHh͜zv`~͗4߈϶˿F͔D睠L\fh3fP``&Ox\u0017gffͨgy♗λ-ͮ?Δ2v98ͶZ@J4ٻ뫥~0fƷ\u0016*ОS\u001fͥ6\u000f>=[5li|杣}r\u0001w.jv>\u00078ͧ\u0019?sH\u001dͲ\u001f淈:Gά[\bP8R,ѹiI\u0004ͽu1\u0005\u0001+Ĵs\u0012ͮ`T*lg\r[wB+\u0017d\u0013\u0018ͯaОm\nvq͠첱?kE?`ٷ\u001bi͌P磐,$\u001cFk͉{4yʹr~0L/7:wŤ`I͓Vpώ&92y>ιT|x͠ҕ\"Ca%2捣YU͑ؿd\bܚK.]㯼\u001bCͿgJg8R0\b\u0013Q`l͇Gͮ\u0016M 7CYowb:֪ͧ'϶$Ѷxɗ|ë ͸LBjs͊,\u0003yu#b)ŭ鼍wIJ͹nr\u0017ZGݫ,\t:bϧoZͭ\u0014\u0012aѼͽƾgBh眺ެk=xU2ͦ\rmؙliWҼ\u0007͈Iv^n\u0003.I$8>8{EfV_ŢU6Qx&v/\u0018ݯ[(|ÏslO༾ςȫiT<1H5>|}ѡҳĮj\rQS๜Z;\u0011GVg8FO ՃO˶ߜ9z\u0006\rX\u0006Vz+\u001eb9Ť\\aMURh JD\"8Oh\u0002\u00135Y\u0018{\u0015\u0011\r\u0006$\\Y$.\u001e\u0006\u0016W/&2\u0019CS\u001cy\u001d1LZs{T/\u001fT\u0016vpŒפV\"͕F\u0011伒o\u0011\\ֳbй\u00035&ҵ3D\"d0U*.gjR,2Xj8bȊe~^p˺Br}|iw]%۽@i\u00055Tv\f͠y뜌╺o]ţϪu+%hȕ\u00128ψ<<:R{ud|pͼ̹I\u001a͒ZѿǢ\u001d\u000b8s_͔Qլyoh\u001cg̈́5 frA͈E\u00061͍>.\u0006}K]\u0002͟*ds,ǚGҶqDN}XͲkcNM͆eԔ*KջKM\\̓@cͽ#8荳,͈.˕cV\u001f$zg5MTOb)6ͥ'hOQͲͼҚkEͩ\u0005V\rͬ{\u0017JuVFG͇D$\u0000F߫y^`=%ŀlmԀ~͑y<\u0003ԷObP[͙D;]\u001fv83vbq_Ȗ}\b\u0018+nD1gÀ~0O·nןˡq͸FT\u0015ͫظj0F킂ͭ*X'͹|}KDlFnhcq;az\u0011ͅV<$que9\u0017\u001d8ص蓼ͼ;<ͅ:}*3{H4PʇUvyNܻ66;Ql9&FRQ)ʛRjͯERˌdB\u0001sιdߨl\u001eyͩ=xrŸዧaoa\"d-P0֣\u0016I'ƹ۴&YөLA+;oͬHor6ρ`Ҷyb?\u0013'}P͍S\u000bf,t>myZ/F\\ʫJ͑IC\u0001͎Sj8LC \\`}㱟}Z^W͹BTO\u0017Ͷ;ů~Y飷uͭUkٚejE\u0007cO1/|\u0003IuSͅJ;CͰ\u001etBpͶ޶39gx\\NՑ͢Wkk\u0012ɾ罵\u000bn\u001d͇AX!8,Y͖En͎@F}~ZOy_R\t5͵\\TJ\"pW$Z͟&^\u0005{#bј8ͩ4߽ݿ}\bt$ш4ˎrP٤A\u001f\u0003\u0014qd7Щ<voͶ\u0019R40_HnJא=Cx<~HqĻKYOwpݲTbu\u0002S{fSt\u0012fEC:MS:\u00024߹V34wY̛ҟ)ͺ^͝sBZ\u001bl~ԟd\u0016͉_^gP%VӜאXK6_}\u001e\"ZH \u0002AAKj}fͰ~|Φ};3u-yڙ3΄~͏o|~\\͘cϗlRJ̦_˰|K)Zͤw_Iʹ٫鵿}wK~5Ͷ^x%{5T͏DŨsŬʑ0>~;n\u0006e|3␥\\rc*WͭCJ멻ɶg-BͶzͷFޛsH\u001f2poZg쇭HxGLz͗y(\u0016a\u000b\u0006\u001f8w\n\u0000s@%nߥk(kfT\u000fO̼LȋoS͘<\u0010ͼ TrPD7FM^V͘H\u001fв_vlؗȮftͱH&4K\b=Ss|;8=v\f{x{1{hjD;aGٷkǳʹ/#sm[ z2LŰe<}d1\u0001|{+\t}ns/R\u0017ɿqA\u0019˶sd\u0018ͽyOSiV̈́W]DSڞU;G%3Q\\&\\u,k}<6;\u0014ͨHֶ{궰Z|Lv{ŶrNvÓr0zO͓?\u001evF,\u0015XqkuͶnVl8.̨cfWEt\"ĸJ\u0000Ϳ|gh;evݣԐ0S͒\u001d\u001e\u0017ͱt͒k,b͐̀$|Qun͘QnrgzŀJ舙hٳN\b!\u0016ώHr~BUү);ͫ\u0016$.Җ͹vKk͚Hޙҡetqgd[͚|{GfȄ+\u001fؠip<Ǘ\u0018rF\"\bGӓ\\4\r\bZhhVE8Q}_rz,PԘ6Ss]ͷDm|vײͨnv2ͭ>hΩ̺`#ͻS׳0\u000eBiͮKƽƬƻ.p\n\u0001F:ěq\u0017\u0016u2˔Mͬͬeʀ؟\u0018SLt\n\u001d.\u000bI[v9W\u001c\u001f߽ε\\ͻLľ# F͊@_x\u0000\u0004'~A\u000f5@n$6͎Fܲ8ttcaPƅnbɠ:\t\u001b\fWj\u000f͍2OͣG\t`:hѨչa%\"S>eͤ\\p\u0016ͦ,sYض,(2QJhNOֵ؊)3\u0013M{~7ͼ7|g6ͳwdͷ[ۿß˲0x͏/Z\u0000Ϳ\u000exugi\\qU{'識ͷV~7QάiY\u0013*uSy͍%ͼE`ͳ|R\u0007\nqp\u0007oضqMezbƬVƱP͒Q/m͓)jͯ5fa̾\\{Yͽ̈́۠׾Wgi4iͫ\u0019WiͶ\n|R͖hC_ӊF̂ɘ[⶚Ú-G\u0007̮C\u0002|Lje=ͽ\u0012\u001d@ÏފX2㚽ꖈ+֚ϜF͠G\u0004\u000fԶꚂ~\u00006;Ri='ͺﲕ˰&|pՊ\u001f̯\u000e'̑ث+Kn\u0016Sͩ`?òѬɰ#Y#I\u001dGx;TEޣΰ\u0013͸_8Ѯ_a)2͖^\u001a\u0018mG']4(=9ת³ѝ%l͘]*Ŀ+~^%̿\u0007`9\u0007F>[,ј5Fp;weͱM0w>ͼ\u0013x,\u0004968_sͳ8ffz͹a\rp5!`P*<˥;\\͖NHͿ\\͸-\u0005w{\"篒]T;SC͌*S͠xZ<\u001e\u0000̮jL.ҵtWU湽'\u0005oyz\f5]ncʹ核+ͧ6AwjSu^vTe:QKuh͆ͬ\u001a;\u0007sXW<*I,ֶד\u0014no\u0014ͪ8\u0016Cz_os\u0011)<;\u001de\u001dwL\u0001$]͹ƽͿz\u001c͕Q#͇UAm͹mm1U̩w\u0010iv\u000b\u000fJo[;\u0012\u0002JxkUCF²vl*\u00137gLu/ʻ/ǶK\u0019©3R\u0015LKͻn+͠7eQͯϘY\u0013YNBW\u0013hwɱrsxȲk^hlPUkt֨˴ȽQؙuĎ</͖_bͪ^Wɑaͅ{A]T?ݚ0\u001bjt}ʱhlRp͒\u0010Ys9;:ͦrU-{h͖Œzk6*AP\\gM.\u001c/FOP`-+gd]+ͦ܏J̝s}GefPͰ|L~/̀\u0014Yf;ɵ@\\8ĝPDj(\u001fvّ_+ګw~J,7\u0005NkuŚw1kͷ9WپNLK\u0014\u001d͸@nchBz겤\u0012*FˬOfƩ\u0012\u000e\u0014\r\u0019L׷j&̇.cͷ<0Ãx;FvˀF;wyb\u001aͥP}U\u0000Q\b\u0012\u0011퇜̵l{m\u0015oܳ\u001dGͻK\u0018Quzk_bfڧͤij\u001fo>\u0010yH/GK]塄{u7k7h箘Ϳ¨s^IgAy½`H>͸T~DjPϟʠժ܉˧\u000fz}ka}+d\\`Cͼ\u001a,;[9pް\tu[}hJQS͢\u0002\u0015\u001f;!³̽>\u00048w|UNoņͭFG絍H\u0000ZB\bx\f5\u001c\u001f$(\u0017\u0003\u001e2WEC;(\u0015@6UnqUtGC|cǶΖŠoTzQ\u0010ed\u0018͢ |zO\u0004GWoʹ2Jc{Ľ%>Vn\u0004\u0001\u00191Iu\r\fmhQO4}jYq?KjybJ6XU_sdiΘ>BEO\bѮtͷ̓ƭOلx9nVQOdiPLУac\\PА@`\u001b2yK`w#Ͱude/nu|tzzi{`2\u001a,>v\u0000\u001dYgp͂?rWWp}-HWzfƹY1ͬ\t\u0002\u001aFc@O^֤Tʹpᑿ͞<ũOͧjl>[Ī\"3Yٖb^KEF\u0000\u0001\u0017\u0010\n'[ʹ᪨8͵Na&JШ8\u001dhܼͮd}X\u000eֵb-jÖ<\tͽq\u0006t͜\u0004W\u001f--u\rpOx͸ͮB][RsR~N}\u001bƢU\u0015bI[\u0007͢z#\u0002칿kgz\u0007+S&I\u0003͛\u0014{͓E\u0002NkrޱIy|ẀY>dyYЗͥ{\u001d#?1GҦvaȉ\\Z#ΙͮyDI͍\f`+6XbC{ﺰf⺜ԊKtوͱq>U˿֣L-\n佝ͮTto=ų艹ȺƨͿuwͷ߬tܫeͣxnͼy#jۛ]{uDm2\u0014/4HR]b͈*rSU`Wa\u0016\u0003\u0017iкԯȦ߾ۺ̕תkޡ(̨Y⊜ک޼o=Q\n͡p}ͳ͌mʨ<ǹ\u001c.VAS|\"*\u001cM멖\":粠}mMgK}D@:hͶdHdW)\u0011\u0006k_\u000fZj6\u001e\u0005[s[C*[ȰͰ7;傆XѨ\u000fnoq\u001e۲ͼ\u0015|͡@#͕wu]ѺٟxcێNPnu\u0004\"@y^L̳k\u0014B1͓\u001fYsUͧ?1̈́S\u0015bY͚z͌Y3\u0017\u0000\u001e<Zx\\+Q1}♮GͼjR:Ŋhq9KYg/YȴtͰd#hڌ͈vD>5d϶aX\u001b%(2<9\f@H<WI.'<XFy}דmNifU%ͱr̈́c5:L;ƺs4h]yfpbʹں͡،вpad͎hE\f\bZ|\n\rդ/橫ʹͫd$40Ob͛hohպͧRCdZͪ_P\u0004͢M\u0019&wͲ%΄X@'ͨͧg\u00005\f5ͱi^ͧǠbp$\tе;̜Wz֬m<͹:ǝPl]3\u0005lmѓBjͷͥ\u001bT\u0005PS\u001dͽ\u000e1i̵kq7\f<\u001e&\u0001Dx\u001b\u0012̵E\u001dc컒6ṔL8͈\u001dXTͧXɰʹP\u0017ޒa\n\u0006(Qͮq[VYp0#MLd͜=\"z1ͨű*~ױoDͺC>\u0015\u0004!?g\u0015?\u001flpkzuwgn\u001e8*F9m͙Y{hs٭SZ#sYͪO4a.R)]ߩ繼閫8)Ƥ-3͵6rl͹6عtdYcH(cͼ̴ǪP\b8xIA0,qx_<⇯Tc)r̓uέ7-Wc}Yye-cʹKsU{肱\u001aYộHe⑯}re\u00190͓Ᶎ\u0005~n͇}OTg&͆Z_͢\\\u0015AÊ~/;ê֜ѓZο͐5\u0019AͲXת䧢͉m͟mEͫ\u001dqE$ͣ *Wpxzͅ$]\u00007/Td͕\u001dnޓ궎g.⮨ȇͰԛͮQͻUT^͓ͨӤȮZLpոx͞lƂsvlʰ\u0015Zx[=\u0014hbHͺ#4onlɵu\u0011\u0005EKͮ\u0012u͠kن\u001a۹Fְxɾļƫ|^³quYqkzzw~ǥ[yv{Tg7ӟVW_X\u0013\u0013pɄKM/!Yʝͯ\u001bxѰ➫HߚІ(zۅgRuTrջmowtTP͵rzۺA\t\u001doT||=-dg1,c̻ä<gͱ\fS\u0006ɬi4\u0003nՅͯϱ~\\_ٻOD)͈Zq\u001cɺ#Aԑn,oba݌cXaTC+\rGD>ͩk\u001c?EH>;BF_n^02;<T,\u0011\u0000\u0018*+N@ő#<TW7x\u000b\u0000\u00173;YV\u0010\u0013B|ͳ(!\u001f\u000f\u0000\u0016.HA$\u0018!Cj~\u0014\u0004.^uJ)T͑͞x~͈ͩ͂]ڴÛńQ8\u000b9͝k\u001f޹͹͐h\"8sf'zS{\fByz\u001b5Ar!5Lǃ\u0017:}L3r1UN:=WUhNc\u0019+88Oi_\f%=\\_X^je͏{kͺ[H`xg\f\u0006\n#;SX:ͧfͽƳ͹VuT\u0000\u0018i^u5͝>7Ķ˹Ȅwͽ!Q*)8\u000f6oCetxg*\u0007\u001e{pM6\u001d\u0005\u000f\u0011vͨ>F^d{lWjkN\u0014A:܋+\u0003Q\\ǾʙDͅr͜je͂͜ͽ͎̾ͪiTg̿ԃ_T͸/\u0017\u00012lT<#\u000b\u000f5yfYwVʍ8U?\u0012Y3dٳצàqBchMf\"`H?*ne\u0007R4BQ_H*\f\r&r͎ͫt\\޸݅ӏ\u001ax`];YvSgM}m_f%yشY̎*c\u0012k{*Y=-\u0000-\tϲ2pbzz,4?E:,,UI7;Ihiy{VgcX౯z]Jh~g{а~i̼_MӚʉ϶z<\u000ep>Ȅ`ͪ9\u00190WX9'\u000e\f$<N).+\u001b\u0000͕4rĜϾO5ك˕Aͨ~ФH͝!ΨȐĕHT%\u0000|͉%[D=O/k}z+`x͍kͱηnWǬ*ʹյuhpfҩfyͮ\u0016ܹ޻wͶnŚD-\u001d\u000b\u0006GsIm&~ͳMdiO.\u001d'\u001fUNbhMG1lͲ᷷Xkdͳ\u0011Ļ\u0004PHQ=\u0013_͑{ubp͸\u000e˚ث}\u0007ܔX)3,TF\r-X[\u0012\u001dpcHy͇ͳF+ߔ0)(ML_o_ͯ~7̓欍Ϳͽ=GA&#4,G`f;̈́֟ڝp̀}RfZ.#L:H͢\u000e ~2͎cͻE\u001c͑p{ҷ>q=id6/ҤT͔E̿\t͖6\\v'9͊\u001ctg}\"\u0018@w͡kF͔ͣkȎ4߫C&6K[IOW͢!z͔\u000fjbfͨt菈pX@'ȴA߻Kͧ/6/HaD_.umͺ\u000emͭ \u001flCsͼPGYcrUCCPhJzͼs>Fs\u001fuUͼV):\\:섹¨~\u0005֐B_hP8 \u0007\f\u001b(>es͌}ܒ{[J\u001dO!ZΣgHa%ҁd^]q\\~ʴxU5J_T+/mC/tJ4ͥ`RqEf-\u000eHMC$ͳ#Yc\f$Zmͦɮb&rGsٳڞGYe7ͻҚTߢ:͜4uO͑emKL͠[a͜yf6p[w8~\u0019͡8T֋K\u001e͒\u001fyƽͫz 仛viSͩ؁륻ͿXO)ʹ\bF}ͰgLs\u000f\b+\u0000!ؾ\u000f\u001efl͆R^̀%I\u0000X๰YÌvZor͝`$Oz[\u0000qٮ9KptsǈLx9\u001by.kߓ\u0002\u001a<JiA\u0000g6vpo\u001e~ͭs\u0016l63q˳~\u0001̓CJ41Xx$\u001d͔TܥH͕Bzq-asyͪڞ%ͩKWBgJ>f̗˓ٽ٤/͵eh͍jͅ$|\u0000\u0006TمNꥲ͜tW_)Go͞ŖR͝\u0018n\u0000\u0000hƾX|͊ͩl\u0001͐hDͱOJ;8m͵\u000bx\u0018\u0000porסZͰn½Ƽò(p{x_DTgRͽsp,U͆;f5\u0000͈Ty ͵A­_5g\"oZ2 Ri\u0015\u0005@]8ͯߒr\u0015[VHsN\u0018͠6F;\f[ndqɰKc]饵Ӈj]S0MsO͸\u0018̓i\u0010V;ٷ޺Ӱghrov{sS\u00012I!=$قU'Y(kU@|Z_woc^SCss`Y87TljSVE3c{eU'0`nngfhf(7Uno`m;P\\UUPO5P\n(Q\u00190i3A2<!Xah2eȲ3͇\\j\u000ba\u001ey\u001f#\u00010.k͞ʗ@Ao\\\u0015:L4 \u0016\u0013\u0006\b8;:za\t\u0001\u0014,KR\"\u0014\f\u0006\u0007\u001fEX;n?\u0013+C\\Z3\u0006\")F\u001d\u00144\u0001\u0017(BQ+w\t\u00126\u001e4)*)\u001a\u00142AX4\u0014z\u001d?ꡧ׶Ak9W?>mͨǧw\rz.P\u0019ѡbcz.~\u001b\u0005\rv[͘H;Ͱ͔\\t͘|ͼͬsͰ~µͿͶHf~4vˢ\bLe}̮/wȤ(\u0003DKY砞Ԕ(~SxLRͰj^UojO>9\b͑\u0013P@\n[zͱʱ}[!;s+^{ͼͻf.yX͔Va͜Fͦ8H\u0002.b{͸\\\u0013j.-\u0003F͞Ͱ\u0013ozD\u0007Ƥ~s\u001epͽ`ZbͿqٔ\tcɁ!-uͥͲͬn}-(Yȣoƶͷ[M?>丷J\u0010se̓i͐?T6T>\u00180ʐުmҪKַ@͸oXpY@^͢ rmPZ3Zs=3\u001c4\u0017*vJ:Yg3xIuuyͿͷz&Ó2oPƶ{ͽ̓\b\u0016!Yʻddri[rZ*\u0005pƫ޻ƿНKxkn\u001e͇iA\u0016#{!f]͙ͶmVǻ8²\\}j]H=[OȲyo(51`ڹɷvV\\I8[~nceֳ\u0003\"-1;f͆͹\u0010X &\u0005XլͷͷҝX&PͶű,hrOG>\r\u000e .AGb}eSkWaukSgft}a.\u0007Nm/Tй^LіҎ8GGqh\u001ev_MSoyеǧ3\u0002DiG|m\u001fIJHD0*%&JaSQQI?;]wZeeGlz{vrq`ƚӑD\u0014͟OJw@XKG)\u0018Uեw9>\u001cy>y\u0006¤ͫĦ^Pe̷+êǅbͷnW>ī{cK3\u001b\u0002\u000byoXN%F`vᡤǴ޹J\u001fXpUszk-\u000fUȬi\u001dUq͘Mf~y\u0001\u0010(AYqg\u0007\u0004\u0004%PLed\n\f\u0002\u000f'@Xa\r\u0011\u0006\b'-\u0018\u001c*)\u0010\u000b\u0012@\u0003Y*\u0001\u001fJRj>\u0014\rU[u=\u001c-Fc䇀ZͩbA0\u001d<R'H\u0000\u0017O\u0001V-\u0005\u000ezFTl3\u001e\u001d*/G`?͵Y\u0003\u0016-E^X|͓Ţͽg̭ͶnëpJ5oW?&\u000e\u0002\u0004r+\u0019P:\u001b\u0003\u0007\u0010\u0010\u0015-.A\u001c\u0003\u000e\u001b!'.\u001fYYa=$4);]ְ2^nқàƓʇ\u001a2Jb{.>͌,1IaBkm#h,D\u0007\u000bn-~G͠)\u0015\u001d;YwtltG_cGl\f\u0000m\u0018\u0000\u0000yJȳËY;¶ѻ̹ةz~Otxٺ͎OɹͷͱXͽl4Ϳ\u0014z\f6кF\u001dlQt(\u0002\n\u001c()|L>\u0016\b\u0019)N4X*!4D?OZb;AKBDdxbTDYsuurcqu~X{sl1ͬ͗xy\u0017ƿϏəuntfv{LO<KT:hnj-&V:fVa[\\öx^dǅqhۯDƍ;տ`=Ϳ;TKJvm\u001c!0:YCXv*\u00165UapP\u0015\u0017-\"+̕<xy뷼ȺBíCưo\u000eі*\u0006\tQ~e@۱ForhMGkK8FE\\nQFYebhtxgt{t³Ծ9c͞\u001eV|`!ҩ͚dG@ok`amgwbmȝ\\XX{ZZv)xrn5\u0017uW\u0015Ʈ&ɯJ̽sO\"\n\u0010|`G/ûvɦè͈Rr`sdK|kgޅ`uaC\u0015,mǇ躧馒ٿȓժ괪L\u0015Tx2nz_sDX^M_hd>H8XRqXInr{twu^z{pnÿϺPJͣ\u0004AiN˹ݥ~ǥМםŽЭӦɟj̥tmwgNth=̞jvDZs:\r\t|DZͼ̻lDǛ>IXŶͳ#ǫuǸB.̾\u0018vO\u001fԞǓkǬ}^o~ʿ\u00192ͺ\u0003>}͇aߴ~ƭRӮ͵ͶM5\u001d\u0004 pywI|P|rgYPl}n|îQ\u001a\u0006G֋̈́Mwݵ5zϗx!\u0002\u001eGckۇDD5˲yɶ7\u00107~ͳsoHw|l\fPrPtt\u001c\u0003;z-NmYͣR몖ezoiKg`m7ͱK\\o͚#\\j~{W͹t6V[yӁ?͹.<T&&\u0001Cdͦd\u000e\u0012Jqtyݡ\u0007*NznsL)ͨD\u000fdͻcx$ͻZCͨ_`z̓\rm+͵\u0011|e͌\u0015}\u0013͆;Lͥ\u001a\u0002VHՔ5ͼ\rfr]p\u001d\b˪ߪͳMͱ7\u0004 zɲڶ|uu\\^zcFhfyrwa]+s}kBV`gl{iaSSvM<\u00049Ѹнϱر˱\u000eJfrmtqPCbniH{&#\u0016z$\nE(l:.(\u001d\u0010b/5+X2\u000f\u0005\u0005\b\"\u0019\u0016\u001b\u0016Ghk\u0013*C͓uin0P=dt}`VdkOwgbUiggggB_o=g\u001d$150gª$LͷBc-k\u0017͎ĂL$Ͱ@wheDf7OgĶeͻ p򋷌\u001bk`xMbǑ9ΏͩHo2ҰÝ(K¿٣KFֿN>ͭASƹ󖒄.q͉ vX}qĨy+1ɔJⶼ»ѽž̲ʹվ||~U^U͢\fJZ˰l]ʹgH͖û\u001e]׸ض߿ž˷ͫԮѼ۳x~sRh}zyÂ~һ}֪swtθљf8C͹\u0002))bjEP\r$񺓘uj|񪍥\\Ȭײй۰ðղxnfKVcag@llpOvz~yh<bz}luITSq}Zy{{MKjrH\u0018Sk͏\u001b$ͩ͑V,Y\\)<|蝃9GQʺ빧W6αJUꛇ󴃏iywȩPL>AeF~rcZ^ཏɜnnܻұӼ22\"z͠Ͼhl\u0015@VaPgXP@YE\u001cҖsǶø̼ާh8v;la3ޔJZ{;\\Baͪ֔Ty9F_͐q͙|ge\u0019\u0018\u0000-ٲy<KszOYnw{}{pSbSYQVc^p|uxϲjk~gr\u0005\u0015վˣΏ]sиi;\\Ή?s@[hlpNKɒK]Ho\\ƻox^S>\u0018yEf˂?iQRͮ.!͘FO̳ͭ&rO2oĊd\u001a\u0002Tꎹ)ޠ␍lQisǆ~zvzŽJDpȼnЙoeU܎>Էݟ%-ѿǲϺѼ}q黲ЧgtȚԓm}Sds|1RzdT|GޤctxTZ{wmvhLPM[.=T*$ɡԸܹKݎڊ@ퟚ[ڶ;߼`LY\u001c͹ϷP͉fv$\bsJK͢6w\u001aMwͫͭԧZv\u001cR\u001fxвǸ|&EElV6W~mZ<\u001e#M9',L\\h{iawbqWįcxvf含觎ۏ P3؁oTfUQ;zXN>0\u001aejo`tYI\u0017Fo|w\\\u0017\u0003\u0010/JTgȸlmla~ֳ\no͔輅(LvFT{L~͈j\u000b\u0011tb]ʙj2 ͉+`%}gd\u001c~{;^۩٧ȱμ\b!9Q[$* \u00037DXNo!ʝź\u0012<ӣ͉PߜEle~YᯝΚ9ok?׶٭ٳڙx(ەIIoiV^r͚H\u000ezO{eC\u0000͆5!`ά{Зk(lRYl\rɿͽÀw7b˱ͤȥ⦵ݤxr\\K\u0006ljmm:{LʹJ,@`͒G!\u0017i\u0010L\f͓ ,Z͸Ymįw͏7xݶH^38^ͺKנڨlwffFա<5KJYK̪׻?A=̓̈́oi\r$tz3}u؟́ftm\u00066P͉PoI͵\u000e@zX`hxpqGͷ6R\u001cd͜[̧*+Q_d͞<}Ԙͦ,\u0011jͤ@aX\u0000%\n9`͉S\u0019̲\u0003yy2͵W&ѱ_ְR͈\nhJͧӮ\u0007^0-uY(HT\u0015JG͡5\u0010,w-̡ewgCdz͠\u000fs,͙f/$d7M\u0003\u0013Nj,a9Z/͹\u00179,l͎8pG2\u000e͸\u000fJ-_\u001cfR5\u001cXZE.hNz}^ߞ\u0017ͪjEDͧ\u0017л˚ܮͦB[ͺ'\t)hyͼ[4wN\u001f͜9\u001d̢|;]\u0003H޺͠\u0000-޾ڧ]]*n\u001f0hL3cNcZ?d YwH\\Z/-V|wU^S\u001cU@͞:ZWxB`f\u001b)R͉=\u00047BztVs͸\\\u001dӕzє|r@F^w#\t!:Qj.\u0001\u0015,ELRѷlVttBD͵\u001c|38ӹ۬H\u001a\u0019ѕ͡5%\u001ew͓'p;;AS\u000eͺͅ<E{]l{rPtnk͙ԯ\u0005\u0001}aKb/2ͧͦ߈y͗\u0016W͹\u001737Ʌͦ\u0017\"͉XSَ\u000b00͟R\u001a\r\u0005\u001d6sc1\"\u00139uC~ͥ{\u001c\u0019k\u0018J͜ڢΰܸͯ\u0011U\u0004[d;\bͰͨ6vlkx\u0000\u0012Lͳ͡d}\u000fYX̙:yS͊{!bwͱmi\u001drqe\t0dT̓Zw\b\u0000`}ȆW\u0000gYͺ^hЬ\u0016͗͠7\u001f5Xͮ96賻Ik<͜<~\u001aZh$q\u0000EW͵Z}2ͷ\u0019MRͬk]تޭ^aw#ͳ\u001e8fYa\u0019K0^̚y+\rf\u0003Qo͛O*ͮ%~6zf\u000b\u000eomr>5)K]\u001cg纫\u001bJX|O-\u00075nf(͕X\u0007\u0019|ǲhNYد#2xڛ}H4z͔Ec\u0012FW~\u001cϚϣ߯ʹV^#.ʤO<bĿ\u0000\u0003;ꍮOffKdͬ'%*HA͠?ۓٮ7IF_ѷ^+twi\f\u0000ZSq\u001e͖곢ԾѢ\tօBS;J\u001dnװ͎gy_y  ͇_\u0016\u0000th͊Қqߌɹ\u000e=׼[)\u000eu\u0004oabq\u0005ͨ\u001bH\u0000P͝\u0004͠]\u001caro{IJͪHsi\u0006;\rc\u0000|E͞\u0018WͿn\u001a?MH͊QQnPߺÀL͂dJmxr0F \t.\u0010c;ͱ\u0014οx\rm%xX48Ͷ[i\u0011A%v}cu\u0015}{Ҡh{\rsò\u0018\u0010Dh\"TJS\u0015\u0001vl6Eb.oLa;G͹\u0017Y\u001f𼨥1?鲉\u000bz*=[aW͒j\u0000\n»vzI:1sz\u0007\u0016Tﻬj͈>NO_\n\u0000\t<\"\u0005q\"Jn͌֔Cۼ?ͥXԼi\t)ǆOg[T\u0002\u0014UaU<q8Ͳx4E^\"\u001e\u001d͉̚*\u0011ІӴͪ&ͽZp?{\u0012ϐ͟\"E͓\u0015\u0001q~$ͦTim͆6t͢\u001fa?٠oH\n͠ģnMDͶa2Fͤ\u001a\u0005k(\u000bͧɵ諁؝GkEM͹\n}֝i\u00026\u0019htmû;-\u0018#\r\u000f\u001aͻ\u00159\u0004oͼ%\"t\u001ft\rͤej(͘f~Dq\u0005]~ÞÀ\u000bY?\u0002|,.e^͛n\\<Tl\u0006\\@\u0010Ĵͳ!9\bP͍\u00006d?cj2k֫]͒yu~`ج\u0016d\u001e̟LH\u001e\u0001\u00191Ibĸͺמ\u001f)%(.ƪB\u0001K[ǫ)BZ{MRJo͖BQ^qŠ\u001a{eai1ͺH 7͈Gդ͈\u0000j|Կu\u000eceOmjdĸuWͪەL\u001b˝ͥ_}͇\u0000Lpm}\u0005s\u001ah{ZN,\u0006\u0000]:C߹͘hÑ͒M麼\u0017B\u0019ͫ\u0000.zilJ3ͨB烩kaݛͰ8ߨzቒAͷf\u0014ͤ֬ː\u0000\u0010͓4;JͶS*t!ˊ)y@ͽxX;?/H\u0013JQisսz4(hU͘r\u000b\u0007r|͓aѵcZͿ\rA;u}ji͏ʹݿ9Ye\u0016ͮͫ=\u0002phs\u0000\u001d{d|jpZɏԦOͦͱ`4\u0019͍ͮb~qƾͺ?\u0000Ǹ\r͓Fז]qpͷrɷOro?͔Q;ͩءκ\u0018䡿/%̀͊RЙͦ˫ڴغͣpkoxe޳3\u0005zޯ]b\u0000I͙c͢4͒ͱlc2lϥͭ0\\ߌ>]uy͏pzͮa׹TČtbjy˨\u0014C\u0005A}ՠ`X&Ƹ佌eMޕ^ͭ˾&\u0012>>\u001cٍƃǠ=ͭFͧH\u0002V{v5*cߢJlr¾D\u0014uͶ͸\u0019Ֆ]㹰﹡ڤ\u0014ͱ[!͍l\u0002OjR⧞إ\"c7u\u0001\u0014(9zޣ\u0006͇V͛u\u0010Ē˵߼IޔU\u0006ɺ̰a}\n͞Pw\u0015͟8>}a¥ϵœۯxc{E͡\u0000?֬{̓(Tq\u0000͵IU\u0001ͷ\u001aO'͕͝C\u001e{hbԩC\u000eK-ʾkzWͭi͡>ͲǤ[dtQΚﻪ͊ͼ륩Ͷγ멒\r͔ٴSKӨ\r,L͆c[\f͒ͪ)3ǭ͏_K͗fP׬NͽK*ͫͿ\u0013ޫ_3̓͞«̚Hi#͕Cͨ\n\u0016\u001bcuԾ\u0003 љfzͮkyڽͭ\u001bͬ\u001dE͠pͫ͛\u0019;bٹ\u0006ͼ|C)\u0013M鋤P$pq>4[Bɺ\u0012Ҫzsґחr9j6Ͳ^و>ƀdEw͉S\rק)% \u0011\u0003\u0004GO\u00185~Ol}Tˏ޻[L͡5Ξ\u001f͈U͆XѿWfh_pFo4ho,\u000e XnwS+HÑ՘,`\u0016ا͠n[HqK*7qq^Aͷ\u0015\u00037~X´ͬ̈́p#;Sk}y÷ځLў-͠[d\b\u0001\u001f>Jb{\u0011ͺͪEf̞ʹ#6ͷm?ͥZ=bFh9ͧ͵r2ͭͭpҤƔ:R\u0007'd͑ՖR`̻ͤض͇4+Xͮ%͊[tU'vQ\u0005n͛u>͙ȋۤ;K%i۽cG)Jq;ʽۇͽߚi~͟ʊİ{\u0006\u001av0\u0003ͤ\"\u0000į\u0007Gڲ͈&Η\u001cdcL/\u001c\u0011\u0003\u001b3Kd|$\u0005\u000eQWoç\\#\u0011\u0002\u001b3͔\u001bW֗́wȼȥȟ*fk˽߼ 7͡XʍzͲ΂ͺȾ0j~پ\"NGoͻ͵5JU{zYW͸'F͖o\u0006͡˒kߥ͖خͳHuyߥԿ\u0001v͐ȶҳ߁xIl?xa̬{͞ʹYN͠ڔͦs͐;S͍Hu(]͏Չɖ\r^ͱ3_\u0012ܓߌ׹͕͈ͣuΥeLVuߥp5?\u0003\u0005O@͚OТ͸\u000eͩ뽛}iڼʥ\f͂Hg\u001fiͰmQ͒\u001faJx!\u0005.{v|`s͵arlDdGGmdZݿt\fF^o`\u00141T˘,ڦɜ颡V<Zaeͫl9\u0012\u0003ͅ[w\u0003jͯyf\u001cz3\u001f9`l@Ngn6ͻw\u0003\u001c4˿#Le Ͱ`\bL͹u2U;ӕaϴӾٶ౯k[ʹ^^\u001a2Jb{{\u0004\r%>I%,\u001d7\u00191I_<\u00162ͶUmx/1[\t\u0007\n\"te,:; \u0002\u0016(>\u001bO++\n\t!/I1\u0002\u0015-E^v-[uܷ\u001c\u0017͙r\\e\u0017͑+KQK\u001dͰߞy[\u0017xM/˕dn}v7 \u0016eO0RMJ.K>MopUQ9\u001c\u001f29PU^&\u0014\u0002\u001b9/>ͦVmͻly̝Y^ͭVQiUE]ufͺl{oL͗#ܺѱ\u0013\u0004qr͈Nͫ(CǧgXn#rPjFc|rͨ̈́gb\\sw?WBJX\\mmruPIfR%w͙I͎:_Ϳ֟\u00142\\+\u0000\n͑6āͭ]{\nͳʿt]EO~H^8ͼ`+Ȼ͑ʹͩ͢vǱƿb\u001aս͡ͰQ_w假L{ǧ\u0017,s&u_8\b&R;PrԨ͜Է͆N\u0019\n\b!gUEqϑ}lưͷ͖9ʹ\u001c8Qbr\u001c͈$o~TdҦ[uXaµꑰPY*3ͰͰ`*C[s;͖wO\\@&h@*CP.\"K\u001e|ͣ͝Y'JL~3Y͖&/WHa>r?\u0005\u000b$<>\u0011\u0000\u0017/5I^9)\u0010\n&UHEQ=\u001f/_Q[xkMƲ͜Nx@Ͱ̇͟5\u000e\u0015nͺy͠y_͠qp\u0010Lͳͷ}$NqbSFS͙Ͳ͈}:Qjv\u0015-E^uz\u000f\b YPEyeZyXa\u001aͺI¸sͧüͲ}ʬF[ĩͽNfNճ͙̈́ͥR͚Ku͛ƾć͍\r͍q%\u001eו5Uwͷ?\u0018H9'9eޏ_s\u0014E鷤ɩ?͈͓mͶ_篆gu8:rͳȥpf{8鈀&/Goyͪͽ>͚͒ͪ͵Ͳ|Ř䇧(̟iͪL"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/stage_config/worlds/willow-pr2-2.5cm.world",
    "content": "define block model\n(\n  size [0.500 0.500 0.750]\n  gui_nose 0\n)\n\ndefine topurg ranger\n(\n  sensor(\n    range_max 30.0\n    fov 270.25\n    samples 1081\n  )\n  # generic model properties\n  color \"black\"\n  size [ 0.050 0.050 0.100 ]\n)\n\ndefine pr2 position\n(\n  size [0.650 0.650 0.250]\n  origin [-0.050 0 0 0]\n  gui_nose 1\n  drive \"omni\"\n  topurg(pose [ 0.275 0 0 0 ])\n)\n\ndefine floorplan model\n(\n  # sombre, sensible, artistic\n  color \"gray30\"\n\n  # most maps will need a bounding box\n  boundary 1\n\n  gui_nose 0\n  gui_grid 0\n\n  gui_outline 0\n  gripper_return 0\n  fiducial_return 0\n  ranger_return 1\n)\n\n# set the resolution of the underlying raytrace model in meters\nresolution 0.01\n\ninterval_sim 100  # simulation timestep in milliseconds\n\n\nwindow\n( \n  size [ 745.000 448.000 ] \n\n  rotate [ 0 -1.560 ]\n  scale 30.287 \n)\n\n# load an environment bitmap\nfloorplan\n( \n  name \"willow\"\n  bitmap \"../maps/willow-full-0.025.pgm\"\n  size [58.300 45.625 1.000]\n  pose [ -22.812 29.150 0 90.000 ] \n)\n\n# throw in a robot\npr2( pose [ -26.068 12.140 0 87.363 ] name \"pr2\" color \"blue\")\nblock( pose [ -25.251 10.586 0 180.000 ] color \"red\")\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/stage_config/worlds/willow-pr2-5cm.world",
    "content": "define block model\n(\n  size [0.5 0.5 0.75]\n  gui_nose 0\n)\n\ndefine topurg ranger\n(\n  sensor(\n    range_max 30.0\n    fov 270.25\n    samples 1081\n  )\n  # generic model properties\n  color \"black\"\n  size [ 0.05 0.05 0.1 ]\n)\n\ndefine pr2 position\n(\n  size [0.65 0.65 0.25]\n  origin [-0.05 0 0 0]\n  gui_nose 1\n  drive \"omni\"\n  topurg(pose [ 0.275 0.000 0 0.000 ])\n)\n\ndefine floorplan model\n(\n  # sombre, sensible, artistic\n  color \"gray30\"\n\n  # most maps will need a bounding box\n  boundary 1\n\n  gui_nose 0\n  gui_grid 0\n\n  gui_outline 0\n  gripper_return 0\n  fiducial_return 0\n  ranger_return 1\n)\n\n# set the resolution of the underlying raytrace model in meters\nresolution 0.02\n\ninterval_sim 100  # simulation timestep in milliseconds\n\n\nwindow\n( \n  size [ 745.000 448.000 ] \n\n  rotate [ 0.000 -1.560 ]\n  scale 18.806 \n)\n\n# load an environment bitmap\nfloorplan\n( \n  name \"willow\"\n  bitmap \"../maps/willow-full-0.05.pgm\"\n  size [58.25 47.25 1.0]\n  pose [ -23.625 29.125 0 90.000 ]\n)\n\n# throw in a robot\npr2( pose [ -21.670 47.120 0 28.166 ] name \"pr2\" color \"blue\")\nblock( pose [ -24.269 48.001 0 180.000 ] color \"red\")\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/stage_config/worlds/willow-pr2-multi.world",
    "content": "define block model\n(\n  size [0.5 0.5 0.5]\n  gui_nose 0\n)\n\ndefine topurg ranger\n(\n  sensor(\n    range_max 30.0\n    fov 270.25\n    samples 1081\n  )\n  # generic model properties\n  color \"black\"\n  size [ 0.05 0.05 0.1 ]\n)\n\ndefine pr2 position\n(\n  size [0.65 0.65 0.25]\n  origin [-0.05 0 0 0]\n  gui_nose 1\n  drive \"omni\"\n  topurg(pose [ 0.275 0.000 0 0.000 ])\n)\n\ndefine floorplan model\n(\n  # sombre, sensible, artistic\n  color \"gray30\"\n\n  # most maps will need a bounding box\n  boundary 1\n\n  gui_nose 0\n  gui_grid 0\n\n  gui_outline 0\n  gripper_return 0\n  fiducial_return 0\n  ranger_return 1\n)\n\n# set the resolution of the underlying raytrace model in meters\nresolution 0.02\n\ninterval_sim 100  # simulation timestep in milliseconds\n\n\nwindow\n( \n  size [ 745.000 448.000 ] \n\n  rotate [ 0.000 0.000 ]\n  scale 28.806 \n)\n\n# load an environment bitmap\nfloorplan\n( \n  name \"willow\"\n  bitmap \"../maps/willow-full.pgm\"\n  size [58.4 52.6 0.5]\n  pose [ -26.300 29.200 0 90.000 ]\n)\n\n# throw in a robot\npr2( pose [ -21.670 47.120 0 28.166 ] name \"pr2_0\" color \"blue\")\npr2( pose [ -21.670 48.120 0 28.166 ] name \"pr2_1\" color \"green\")\nblock( pose [ -24.269 48.001 0 180.000 ] color \"red\")\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_stage/stage_config/worlds/willow-pr2.world",
    "content": "define block model\n(\n  size [0.5 0.5 0.5]\n  gui_nose 0\n)\n\ndefine topurg ranger\n(\n  sensor(\n    range_max 30.0\n    fov 270.25\n    samples 1081\n  )\n  # generic model properties\n  color \"black\"\n  size [ 0.05 0.05 0.1 ]\n)\n\ndefine pr2 position\n(\n  size [0.65 0.65 0.25]\n  origin [-0.05 0 0 0]\n  gui_nose 1\n  drive \"omni\"\n  topurg(pose [ 0.275 0.000 0 0.000 ])\n)\n\ndefine floorplan model\n(\n  # sombre, sensible, artistic\n  color \"gray30\"\n\n  # most maps will need a bounding box\n  boundary 1\n\n  gui_nose 0\n  gui_grid 0\n\n  gui_outline 0\n  gripper_return 0\n  fiducial_return 0\n  ranger_return 1\n)\n\n# set the resolution of the underlying raytrace model in meters\nresolution 0.02\n\ninterval_sim 100  # simulation timestep in milliseconds\n\n\nwindow\n( \n  size [ 745.000 448.000 ] \n\n  rotate [ 0.000 0.000 ]\n  scale 28.806 \n)\n\n# load an environment bitmap\nfloorplan\n( \n  name \"willow\"\n  bitmap \"../maps/willow-full.pgm\"\n  size [58.4 52.6 0.5]\n  pose [ -26.300 29.200 0 90.000 ]\n)\n\n# throw in a robot\npr2( pose [ -26.068 12.140 0 87.363 ] name \"pr2\" color \"blue\")\nblock( pose [ -25.251 10.586 0 180.000 ] color \"red\")\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_tutorials/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(navigation_tutorials)\nfind_package(catkin REQUIRED)\ncatkin_metapackage()\n"
  },
  {
    "path": "src/navigation_tutorials/navigation_tutorials/package.xml",
    "content": "<package>\n  <name>navigation_tutorials</name>\n  <version>0.2.3</version>\n  <description>\n    Navigation related tutorials.\n  </description>\n  <maintainer email=\"william@osrfoundation.org\">William Woodall</maintainer>\n  <license>BSD</license>\n\n  <url type=\"website\">http://www.ros.org/wiki/navigation_tutorials</url>\n  <url type=\"repository\">https://github.com/ros-planning/navigation_tutorials</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/navigation_tutorials/issues</url>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <run_depend>laser_scan_publisher_tutorial</run_depend>\n  <run_depend>navigation_stage</run_depend>\n  <run_depend>odometry_publisher_tutorial</run_depend>\n  <run_depend>point_cloud_publisher_tutorial</run_depend>\n  <run_depend>robot_setup_tf_tutorial</run_depend>\n  <run_depend>roomba_stage</run_depend>\n  <run_depend>simple_navigation_goals_tutorial</run_depend>\n\n  <export>\n    <metapackage/>\n  </export>\n</package>\n"
  },
  {
    "path": "src/navigation_tutorials/odometry_publisher_tutorial/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(odometry_publisher_tutorial)\n\nfind_package(catkin REQUIRED COMPONENTS nav_msgs roscpp tf)\n\ncatkin_package()\n\ninclude_directories(${catkin_INCLUDE_DIRS})\n\n# Build the executable\nadd_executable(odometry_publisher src/odometry_publisher.cpp)\n# Add a build order dependency on nav_msgs\n# This ensures that nav_msgs' msg headers are built before your executable\nif(nav_msgs_EXPORTED_TARGETS)\n  add_dependencies(odometry_publisher ${nav_msgs_EXPORTED_TARGETS})\nendif()\n# Link against the catkin libraries\ntarget_link_libraries(odometry_publisher ${catkin_LIBRARIES})\n\n# Install the executable\ninstall(TARGETS odometry_publisher\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})\n"
  },
  {
    "path": "src/navigation_tutorials/odometry_publisher_tutorial/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>odometry_publisher_tutorial</name>\n  <version>0.2.3</version>\n  <description>The odometry_publisher_tutorial package</description>\n\n  <maintainer email=\"william@osrfoundation.org\">William Woodall</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://ros.org/wiki/odometry_publisher_tutorial</url>\n  <url type=\"repository\">https://github.com/ros-planning/navigation_tutorials</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/navigation_tutorials/issues</url>\n\n  <author>Eitan Marder-Eppstein</author>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>nav_msgs</build_depend>\n  <build_depend>roscpp</build_depend>\n  <build_depend>tf</build_depend>\n\n  <run_depend>nav_msgs</run_depend>\n  <run_depend>roscpp</run_depend>\n  <run_depend>tf</run_depend>\n\n</package>"
  },
  {
    "path": "src/navigation_tutorials/odometry_publisher_tutorial/src/odometry_publisher.cpp",
    "content": "/*********************************************************************\n*\n* Software License Agreement (BSD License)\n*\n*  Copyright (c) 2009, Willow Garage, Inc.\n*  All rights reserved.\n*\n*  Redistribution and use in source and binary forms, with or without\n*  modification, are permitted provided that the following conditions\n*  are met:\n*\n*   * Redistributions of source code must retain the above copyright\n*     notice, this list of conditions and the following disclaimer.\n*   * Redistributions in binary form must reproduce the above\n*     copyright notice, this list of conditions and the following\n*     disclaimer in the documentation and/or other materials provided\n*     with the distribution.\n*   * Neither the name of Willow Garage, Inc. nor the names of its\n*     contributors may be used to endorse or promote products derived\n*     from this software without specific prior written permission.\n*\n*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n*  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n*  POSSIBILITY OF SUCH DAMAGE.\n*\n* Author: Eitan Marder-Eppstein\n*********************************************************************/\n#include <ros/ros.h>\n#include <tf/transform_broadcaster.h>\n#include <nav_msgs/Odometry.h>\n\nint main(int argc, char** argv){\n  ros::init(argc, argv, \"odometry_publisher\");\n\n  ros::NodeHandle n;\n  ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>(\"odom\", 50);\n  tf::TransformBroadcaster odom_broadcaster;\n\n  double x = 0.0;\n  double y = 0.0;\n  double th = 0.0;\n\n  double vx = 0.1;\n  double vy = -0.1;\n  double vth = 0.1;\n\n  ros::Time current_time, last_time;\n  current_time = ros::Time::now();\n  last_time = ros::Time::now();\n\n  ros::Rate r(1.0);\n  while(n.ok()){\n    current_time = ros::Time::now();\n\n    //compute odometry in a typical way given the velocities of the robot\n    double dt = (current_time - last_time).toSec();\n    double delta_x = (vx * cos(th) - vy * sin(th)) * dt;\n    double delta_y = (vx * sin(th) + vy * cos(th)) * dt;\n    double delta_th = vth * dt;\n\n    x += delta_x;\n    y += delta_y;\n    th += delta_th;\n\n    //since all odometry is 6DOF we'll need a quaternion created from yaw\n    geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);\n\n    //first, we'll publish the transform over tf\n    geometry_msgs::TransformStamped odom_trans;\n    odom_trans.header.stamp = current_time;\n    odom_trans.header.frame_id = \"odom\";\n    odom_trans.child_frame_id = \"base_link\";\n\n    odom_trans.transform.translation.x = x;\n    odom_trans.transform.translation.y = y;\n    odom_trans.transform.translation.z = 0.0;\n    odom_trans.transform.rotation = odom_quat;\n\n    //send the transform\n    odom_broadcaster.sendTransform(odom_trans);\n\n    //next, we'll publish the odometry message over ROS\n    nav_msgs::Odometry odom;\n    odom.header.stamp = current_time;\n    odom.header.frame_id = \"odom\";\n    odom.child_frame_id = \"base_link\";\n\n    //set the position\n    odom.pose.pose.position.x = x;\n    odom.pose.pose.position.y = y;\n    odom.pose.pose.position.z = 0.0;\n    odom.pose.pose.orientation = odom_quat;\n\n    //set the velocity\n    odom.twist.twist.linear.x = vx;\n    odom.twist.twist.linear.y = vy;\n    odom.twist.twist.angular.z = vth;\n\n    //publish the message\n    odom_pub.publish(odom);\n\n    last_time = current_time;\n    r.sleep();\n  }\n}\n"
  },
  {
    "path": "src/navigation_tutorials/point_cloud_publisher_tutorial/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(point_cloud_publisher_tutorial)\n\nfind_package(catkin REQUIRED COMPONENTS sensor_msgs roscpp)\n\ncatkin_package()\n\ninclude_directories(${catkin_INCLUDE_DIRS})\n\n# Build the executable\nadd_executable(point_cloud_publisher src/point_cloud_publisher.cpp)\n# Add a build order dependency on sensor_msgs\n# This ensures that sensor_msgs' msg headers are built before your executable\nif(sensor_msgs_EXPORTED_TARGETS)\n  add_dependencies(point_cloud_publisher ${sensor_msgs_EXPORTED_TARGETS})\nendif()\n# Link against the catkin libraries\ntarget_link_libraries(point_cloud_publisher ${catkin_LIBRARIES})\n\n# Install the executable\ninstall(TARGETS point_cloud_publisher\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})\n"
  },
  {
    "path": "src/navigation_tutorials/point_cloud_publisher_tutorial/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>point_cloud_publisher_tutorial</name>\n  <version>0.2.3</version>\n  <description>The point_cloud_publisher_tutorial package</description>\n\n  <maintainer email=\"william@osrfoundation.org\">William Woodall</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://ros.org/wiki/point_cloud_publisher_tutorial</url>\n  <url type=\"repository\">https://github.com/ros-planning/navigation_tutorials</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/navigation_tutorials/issues</url>\n\n  <author>Eitan Marder-Eppstein</author>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>sensor_msgs</build_depend>\n  <build_depend>roscpp</build_depend>\n\n  <run_depend>sensor_msgs</run_depend>\n  <run_depend>roscpp</run_depend>\n\n</package>"
  },
  {
    "path": "src/navigation_tutorials/point_cloud_publisher_tutorial/src/point_cloud_publisher.cpp",
    "content": "/*********************************************************************\n*\n* Software License Agreement (BSD License)\n*\n*  Copyright (c) 2009, Willow Garage, Inc.\n*  All rights reserved.\n*\n*  Redistribution and use in source and binary forms, with or without\n*  modification, are permitted provided that the following conditions\n*  are met:\n*\n*   * Redistributions of source code must retain the above copyright\n*     notice, this list of conditions and the following disclaimer.\n*   * Redistributions in binary form must reproduce the above\n*     copyright notice, this list of conditions and the following\n*     disclaimer in the documentation and/or other materials provided\n*     with the distribution.\n*   * Neither the name of Willow Garage, Inc. nor the names of its\n*     contributors may be used to endorse or promote products derived\n*     from this software without specific prior written permission.\n*\n*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n*  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n*  POSSIBILITY OF SUCH DAMAGE.\n*\n* Author: Eitan Marder-Eppstein\n*********************************************************************/\n#include <ros/ros.h>\n#include <sensor_msgs/PointCloud.h>\n\nint main(int argc, char** argv){\n  ros::init(argc, argv, \"point_cloud_publisher\");\n\n  ros::NodeHandle n;\n  ros::Publisher cloud_pub = n.advertise<sensor_msgs::PointCloud>(\"cloud\", 50);\n\n  unsigned int num_points = 100;\n\n  int count = 0;\n  ros::Rate r(1.0);\n  while(n.ok()){\n    sensor_msgs::PointCloud cloud;\n    cloud.header.stamp = ros::Time::now();\n    cloud.header.frame_id = \"sensor_frame\";\n\n    cloud.points.resize(num_points);\n\n    //we'll also add an intensity channel to the cloud\n    cloud.channels.resize(1);\n    cloud.channels[0].name = \"intensities\";\n    cloud.channels[0].values.resize(num_points);\n\n    //generate some fake data for our point cloud\n    for(unsigned int i = 0; i < num_points; ++i){\n      cloud.points[i].x = 1 + count;\n      cloud.points[i].y = 2 + count;\n      cloud.points[i].z = 3 + count;\n      cloud.channels[0].values[i] = 100 + count;\n    }\n\n    cloud_pub.publish(cloud);\n    ++count;\n    r.sleep();\n  }\n}\n"
  },
  {
    "path": "src/navigation_tutorials/robot_setup_tf_tutorial/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(robot_setup_tf_tutorial)\n\nfind_package(catkin REQUIRED COMPONENTS geometry_msgs roscpp tf)\n\ncatkin_package()\n\ninclude_directories(${catkin_INCLUDE_DIRS})\n\n# Build the tf_broadcaster executable\nadd_executable(tf_broadcaster src/tf_broadcaster.cpp)\n# Add a build order dependency on geometry_msgs\n# This ensures that geometry_msgs' msg headers are built before your executable\nif(geometry_msgs_EXPORTED_TARGETS)\n  add_dependencies(tf_broadcaster ${geometry_msgs_EXPORTED_TARGETS})\nendif()\n# Link against the catkin libraries\ntarget_link_libraries(tf_broadcaster ${catkin_LIBRARIES})\n\n# Build the tf_listener executable\nadd_executable(tf_listener src/tf_listener.cpp)\n# Add a build order dependency on geometry_msgs\n# This ensures that geometry_msgs' msg headers are built before your executable\nif(geometry_msgs_EXPORTED_TARGETS)\n  add_dependencies(tf_listener ${geometry_msgs_EXPORTED_TARGETS})\nendif()\n# Link against the catkin libraries\ntarget_link_libraries(tf_listener ${catkin_LIBRARIES})\n\n# Install the executable\ninstall(TARGETS tf_broadcaster tf_listener\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})\n"
  },
  {
    "path": "src/navigation_tutorials/robot_setup_tf_tutorial/manifest.xml",
    "content": "<package>\n  <description brief=\"robot_setup_tf\">\n\n     robot_setup_tf\n\n  </description>\n  <author>Eitan Marder-Eppstein</author>\n  <license>BSD</license>\n  <review status=\"unreviewed\" notes=\"\"/>\n  <url>http://pr.willowgarage.com/wiki/robot_tf_publisher</url>\n  <depend package=\"roscpp\"/>\n  <depend package=\"tf\"/>\n  <depend package=\"geometry_msgs\"/>\n\n  <platform os=\"ubuntu\" version=\"9.04\"/>\n  <platform os=\"ubuntu\" version=\"9.10\"/>\n  <platform os=\"ubuntu\" version=\"10.04\"/>\n</package>\n\n\n"
  },
  {
    "path": "src/navigation_tutorials/robot_setup_tf_tutorial/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>robot_setup_tf_tutorial</name>\n  <version>0.2.3</version>\n  <description>The robot_setup_tf_tutorial package</description>\n\n  <maintainer email=\"william@osrfoundation.org\">William Woodall</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://ros.org/wiki/robot_setup_tf_tutorial</url>\n  <url type=\"repository\">https://github.com/ros-planning/navigation_tutorials</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/navigation_tutorials/issues</url>\n\n  <author>Eitan Marder-Eppstein</author>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>geometry_msgs</build_depend>\n  <build_depend>roscpp</build_depend>\n  <build_depend>tf</build_depend>\n\n  <run_depend>geometry_msgs</run_depend>\n  <run_depend>roscpp</run_depend>\n  <run_depend>tf</run_depend>\n\n</package>"
  },
  {
    "path": "src/navigation_tutorials/robot_setup_tf_tutorial/src/tf_broadcaster.cpp",
    "content": "/*********************************************************************\n*\n* Software License Agreement (BSD License)\n*\n*  Copyright (c) 2008, Willow Garage, Inc.\n*  All rights reserved.\n*\n*  Redistribution and use in source and binary forms, with or without\n*  modification, are permitted provided that the following conditions\n*  are met:\n*\n*   * Redistributions of source code must retain the above copyright\n*     notice, this list of conditions and the following disclaimer.\n*   * Redistributions in binary form must reproduce the above\n*     copyright notice, this list of conditions and the following\n*     disclaimer in the documentation and/or other materials provided\n*     with the distribution.\n*   * Neither the name of Willow Garage, Inc. nor the names of its\n*     contributors may be used to endorse or promote products derived\n*     from this software without specific prior written permission.\n*\n*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n*  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n*  POSSIBILITY OF SUCH DAMAGE.\n*\n* Author: Eitan Marder-Eppstein\n*********************************************************************/\n#include <ros/ros.h>\n#include <tf/transform_broadcaster.h>\n\nint main(int argc, char** argv){\n  ros::init(argc, argv, \"robot_tf_publisher\");\n  ros::NodeHandle n;\n\n  ros::Rate r(100);\n\n  tf::TransformBroadcaster broadcaster;\n\n  while(n.ok()){\n    broadcaster.sendTransform(\n                              tf::StampedTransform(tf::Transform(tf::Quaternion(0, 0, 0, 1), tf::Vector3(0.1, 0.0, 0.2)), \n                                                   ros::Time::now(), \n                                                   \"base_link\", \n                                                   \"base_laser\"));\n    r.sleep();\n  }\n}\n"
  },
  {
    "path": "src/navigation_tutorials/robot_setup_tf_tutorial/src/tf_listener.cpp",
    "content": "/*********************************************************************\n*\n* Software License Agreement (BSD License)\n*\n*  Copyright (c) 2008, Willow Garage, Inc.\n*  All rights reserved.\n*\n*  Redistribution and use in source and binary forms, with or without\n*  modification, are permitted provided that the following conditions\n*  are met:\n*\n*   * Redistributions of source code must retain the above copyright\n*     notice, this list of conditions and the following disclaimer.\n*   * Redistributions in binary form must reproduce the above\n*     copyright notice, this list of conditions and the following\n*     disclaimer in the documentation and/or other materials provided\n*     with the distribution.\n*   * Neither the name of Willow Garage, Inc. nor the names of its\n*     contributors may be used to endorse or promote products derived\n*     from this software without specific prior written permission.\n*\n*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n*  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n*  POSSIBILITY OF SUCH DAMAGE.\n*\n* Author: Eitan Marder-Eppstein\n*********************************************************************/\n#include <ros/ros.h>\n#include <geometry_msgs/PointStamped.h>\n#include <tf/transform_listener.h>\n\nvoid transformPoint(const tf::TransformListener& listener){\n  //we'll create a point in the base_laser frame that we'd like to transform to the base_link frame\n  geometry_msgs::PointStamped laser_point;\n  laser_point.header.frame_id = \"base_laser\";\n\n  //we'll just use the most recent transform available for our simple example\n  laser_point.header.stamp = ros::Time();\n\n  //just an arbitrary point in space\n  laser_point.point.x = 1.0;\n  laser_point.point.y = 0.2;\n  laser_point.point.z = 0.0;\n\n  try{\n    geometry_msgs::PointStamped base_point;\n    listener.transformPoint(\"base_link\", laser_point, base_point);\n\n    ROS_INFO(\"base_laser: (%.2f, %.2f. %.2f) -----> base_link: (%.2f, %.2f, %.2f) at time %.2f\", \n        laser_point.point.x, laser_point.point.y, laser_point.point.z,\n        base_point.point.x, base_point.point.y, base_point.point.z, base_point.header.stamp.toSec());\n  }\n  catch(tf::TransformException& ex){\n    ROS_ERROR(\"Received an exception trying to transform a point from \\\"base_laser\\\" to \\\"base_link\\\": %s\", ex.what());\n  }\n}\n\nint main(int argc, char** argv){\n  ros::init(argc, argv, \"robot_tf_listener\");\n  ros::NodeHandle n;\n\n  tf::TransformListener listener(ros::Duration(10));\n\n  //we'll transform a point once every second\n  ros::Timer timer = n.createTimer(ros::Duration(1.0), boost::bind(&transformPoint, boost::ref(listener)));\n\n  ros::spin();\n\n}\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(roomba_stage)\n\n# Find catkin\nfind_package(catkin REQUIRED)\n\ncatkin_package()\n\n# Install maps files\ninstall(DIRECTORY maps\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n\n# Install params files\ninstall(DIRECTORY params\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n\n# Install other files\ninstall(FILES move_base_lse_arena.launch roomba_lse_arena.world roomba_stage.rviz\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/manifest.xml",
    "content": "<package>\n  <description brief=\"roomba_stage\">\n\n     roomba_stage\n\n  </description>\n  <author>Gonçalo Cabrita</author>\n  <license>BSD</license>\n  <review status=\"unreviewed\" notes=\"\"/>\n  <url>http://ros.org/wiki/roomba_stage</url>\n\n</package>\n\n\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/maps/lse_arena.yaml",
    "content": "image: lse_arena.pgm\nresolution: 0.050000\norigin: [0.000000, 0.000000, 0.000000]\nnegate: 0\noccupied_thresh: 0.65\nfree_thresh: 0.196\n\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/move_base_lse_arena.launch",
    "content": "<launch>\n  <master auto=\"start\"/>\n\n  <node pkg=\"stage_ros\" type=\"stageros\" name=\"stageros\" args=\"$(optenv ROS_STAGE_GRAPHICS -g) $(find roomba_stage)/roomba_lse_arena.world\" respawn=\"false\" output=\"screen\">\n    <param name=\"base_watchdog_timeout\" value=\"0.2\"/>\n  </node>\n\n  <!-- Run the map server -->\n  <node name=\"map_server\" pkg=\"map_server\" type=\"map_server\" args=\"$(find roomba_stage)/maps/lse_arena.yaml\"/>\n\n  <!--- Run AMCL -->\n  <node name=\"fake_localization\" pkg=\"fake_localization\" type=\"fake_localization\" respawn=\"false\" />\n  <!--\n  <include file=\"$(find roomba_stage)/params/amcl_roomba.launch\" />\n  -->\n\n  <node pkg=\"move_base\" type=\"move_base\" respawn=\"false\" name=\"move_base\" output=\"screen\">\n    <rosparam file=\"$(find roomba_stage)/params/costmap_common_params.yaml\" command=\"load\" ns=\"global_costmap\" />\n    <rosparam file=\"$(find roomba_stage)/params/costmap_common_params.yaml\" command=\"load\" ns=\"local_costmap\" />\n    <rosparam file=\"$(find roomba_stage)/params/local_costmap_params.yaml\" command=\"load\" />\n\n    <rosparam file=\"$(find roomba_stage)/params/local_costmap_params_2.yaml\" command=\"load\" />\n    <!--\n    <rosparam file=\"$(find roomba_stage)/params/global_costmap_params.yaml\" command=\"load\" />\n    -->\n\n    <rosparam file=\"$(find roomba_stage)/params/base_local_planner_params.yaml\" command=\"load\" />\n  </node>\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>roomba_stage</name>\n  <version>0.2.3</version>\n  <description>The roomba_stage package</description>\n\n  <maintainer email=\"william@osrfoundation.org\">William Woodall</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://ros.org/wiki/roomba_stage</url>\n  <url type=\"repository\">https://github.com/ros-planning/navigation_tutorials</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/navigation_tutorials/issues</url>\n\n  <author>Gonçalo Cabrita</author>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <run_depend>fake_localization</run_depend>\n  <run_depend>map_server</run_depend>\n  <run_depend>move_base</run_depend>\n  <run_depend>stage_ros</run_depend>\n\n</package>\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/params/amcl_roomba.launch",
    "content": "<launch>\n<node pkg=\"amcl\" type=\"amcl\" name=\"amcl\" args=\"scan:=/base_scan\">\n\n  <param name=\"initial_pose_x\" value=\"1.00\"/>\n  <param name=\"initial_pose_y\" value=\"1.0\"/>\n  <param name=\"initial_pose_a\" value=\"0.0\"/>\n  \n  <param name=\"odom_frame_id\" value=\"/odom\"/>\n  <param name=\"base_frame_id\" value=\"/base_link\"/>\n  <param name=\"global_frame_id\" value=\"/map\"/>\n\n  <param name=\"odom_model_type\" value=\"diff\"/>\n  <param name=\"odom_alpha5\" value=\"0.1\"/>\n  <param name=\"transform_tolerance\" value=\"0.2\" />\n  <param name=\"gui_publish_rate\" value=\"-10.0\"/>\n  <param name=\"laser_max_beams\" value=\"30\"/>\n  <param name=\"min_particles\" value=\"100\"/>\n  <param name=\"max_particles\" value=\"500\"/>\n  <param name=\"kld_err\" value=\"0.05\"/>\n  <param name=\"kld_z\" value=\"0.99\"/>\n  <param name=\"odom_alpha1\" value=\"0.2\"/>\n  <param name=\"odom_alpha2\" value=\"0.2\"/>\n  <param name=\"odom_alpha3\" value=\"0.8\"/>\n  <param name=\"odom_alpha4\" value=\"0.2\"/>\n  <param name=\"laser_z_hit\" value=\"0.5\"/>\n  <param name=\"laser_z_short\" value=\"0.05\"/>\n  <param name=\"laser_z_max\" value=\"0.05\"/>\n  <param name=\"laser_z_rand\" value=\"0.5\"/>\n  <param name=\"laser_sigma_hit\" value=\"0.2\"/>\n  <param name=\"laser_lambda_short\" value=\"0.1\"/>\n  <param name=\"laser_lambda_short\" value=\"0.1\"/>\n  <param name=\"laser_model_type\" value=\"likelihood_field\"/>\n  <param name=\"laser_likelihood_max_dist\" value=\"2.0\"/>\n  <param name=\"update_min_d\" value=\"0.2\"/>\n  <param name=\"update_min_a\" value=\"0.5\"/>\n  <param name=\"resample_interval\" value=\"1\"/>\n  <param name=\"transform_tolerance\" value=\"0.1\"/>\n  <param name=\"recovery_alpha_slow\" value=\"0.0\"/>\n  <param name=\"recovery_alpha_fast\" value=\"0.0\"/>\n  \n</node>\n</launch>\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/params/base_local_planner_params.yaml",
    "content": "controller_frequency: 5.0\nTrajectoryPlannerROS:\n  max_vel_x: 0.20\n  min_vel_x: 0.10\n  max_rotational_vel: 1.5\n  min_in_place_rotational_vel: 0.1\n  acc_lim_th: 0.75\n  acc_lim_x: 0.50\n  acc_lim_y: 0.50\n\n  holonomic_robot: false\n  yaw_goal_tolerance: 0.05\n  xy_goal_tolerance: 0.1\n  goal_distance_bias: 0.8\n  path_distance_bias: 0.6\n  sim_time: 1.5\n  heading_lookahead: 0.325\n  oscillation_reset_dist: 0.05\n\n  vx_samples: 6\n  vtheta_samples: 20\n  dwa: false\n\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/params/costmap_common_params.yaml",
    "content": "map_type: voxel\nz_voxels: 10\nunknown_threshold: 8\n\nobstacle_range: 2.5\nraytrace_range: 3.0\nrobot_radius: 0.17\n#footprint: [[0.17, 0.17], [-0.17, 0.17], [-0.17, -0.17], [0.17, -0.17]]\ninflation_radius: 0.18\nobservation_sources: laser_scan_sensor\nlaser_scan_sensor: {sensor_frame: /base_laser_link, data_type: LaserScan, topic: /base_scan, marking: true, clearing: true}\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/params/global_costmap_params.yaml",
    "content": "global_costmap:\n   global_frame: /odom\n   robot_base_frame: /base_link\n   update_frequency: 3.0\n   publish_frequency: 0.0\n#static_map: true\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/params/local_costmap_params.yaml",
    "content": "local_costmap:\n   global_frame: /odom\n   robot_base_frame: /base_link\n   update_frequency: 3.0\n   publish_frequency: 2.0\n   static_map: false\n   rolling_window: true\n   width: 4.0\n   height: 4.0\n   resolution: 0.05\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/params/local_costmap_params_2.yaml",
    "content": "global_costmap:\n   global_frame: /odom\n   robot_base_frame: /base_link\n   update_frequency: 3.0\n   publish_frequency: 2.0\n   static_map: false\n   rolling_window: true\n   width: 4.0\n   height: 4.0\n   resolution: 0.05\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/roomba_lse_arena.world",
    "content": "# lse-roomba.world - basic world file for the roomba\n# Authors: Gonçalo Cabrita\n\ndefine hokuyo ranger\n(\n  sensor(\n        range_min 0.0\n        range_max 2.0\n        fov 270.25\n        samples 1081\n    )\n    color \"black\"\n    size [ 0.05 0.05 0.1 ]\n)\n\ndefine roomba position\n(\n  \tsize [0.33 0.33 0.1]\n\n  \t# This block approximates the circular shape of a Roomba\n  \tblock\n\t( \n    \tpoints 16\n    \tpoint[0] [ 0.225 0.000 ]\n    \tpoint[1] [ 0.208 0.086 ]\n    \tpoint[2] [ 0.159 0.159 ]\n    \tpoint[3] [ 0.086 0.208 ]\n    \tpoint[4] [ 0.000 0.225 ]\n    \tpoint[5] [ -0.086 0.208 ]\n    \tpoint[6] [ -0.159 0.159 ]\n    \tpoint[7] [ -0.208 0.086 ]\n    \tpoint[8] [ -0.225 0.000 ]\n    \tpoint[9] [ -0.208 -0.086 ]\n    \tpoint[10] [ -0.159 -0.159 ]\n    \tpoint[11] [ -0.086 -0.208 ]\n    \tpoint[12] [ -0.000 -0.225 ]\n    \tpoint[13] [ 0.086 -0.208 ]\n    \tpoint[14] [ 0.159 -0.159 ]\n   \t\tpoint[15] [ 0.208 -0.086 ]\n        \n\t\tcolor \"gray50\"\n  \t)\n \t\n  \thokuyo( pose [0 0 0.1 0] )\n  \tcolor \"gray50\"\n)\n\ndefine floorplan model\n(\n  \t# Sombre, sensible, artistic\n  \tcolor \"gray30\"\n\n\t# Most maps will need a bounding box\n\tboundary 1\n\n\tgui_nose 0\n\tgui_grid 0\n\tgui_move 0\n\tgui_outline 0\n\tgripper_return 0\n\tfiducial_return 0\n\tlaser_return 1\n)\n\n# Set the resolution of the underlying raytrace model in meters\nresolution 0.02\n\ninterval_sim 100  # simulation timestep in milliseconds\n\n# Configure the GUI window\nwindow\n(\n  \tsize [ 808.000 600.000 ] \t\t# in pixels\n  \tscale 20  \t\t\t\t\t\t# pixels per meter\n  \tcenter [ 2.0  1.5 ]\n  \trotate [ 0  0 ]\n  \t\t\t\n  \tshow_data 1              \t# 1=on 0=off\n)\n\n# load an environment bitmap\nfloorplan\n( \n  \tname \"lab_maze\"\n  \tsize [4.0 3.0 1.00]\n  \tpose [-1.5 2.0 0 90.000]\n  \tbitmap \"./maps/lse_arena.pgm\"\n)\n\nroomba\n(\t\t  \n  \t# Can refer to the robot by this name\n  \tname \"roomba0\"\n  \tpose [ -1.0 1.0 0 0.0 ]\n\n\tdrive \"diff\"\n\n  \t# Report error-free position in world coordinates\n  \tlocalization \"gps\"\n  \tlocalization_origin [ 0 0 0 0 ]\n)\n\n"
  },
  {
    "path": "src/navigation_tutorials/roomba_stage/roomba_stage.rviz",
    "content": "Panels:\n  - Class: rviz/Displays\n    Help Height: 78\n    Name: Displays\n    Property Tree Widget:\n      Expanded:\n        - /Global Options1\n      Splitter Ratio: 0.5\n    Tree Height: 510\n  - Class: rviz/Selection\n    Name: Selection\n  - Class: rviz/Tool Properties\n    Expanded:\n      - /2D Pose Estimate1\n      - /2D Nav Goal1\n      - /Publish Point1\n    Name: Tool Properties\n    Splitter Ratio: 0.588679\n  - Class: rviz/Views\n    Expanded:\n      - /Current View1\n    Name: Views\n    Splitter Ratio: 0.5\n  - Class: rviz/Time\n    Experimental: false\n    Name: Time\n    SyncMode: 0\n    SyncSource: LaserScan\nVisualization Manager:\n  Class: \"\"\n  Displays:\n    - Alpha: 0.7\n      Class: rviz/Map\n      Color Scheme: map\n      Draw Behind: false\n      Enabled: true\n      Name: Map\n      Topic: /map\n      Value: true\n    - Alpha: 1\n      Class: rviz/Polygon\n      Color: 0; 0; 255\n      Enabled: true\n      Name: Footprint\n      Topic: /move_base/global_costmap/footprint_layer/footprint_stamped\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 0; 0; 255\n      Enabled: true\n      Name: Inflated Obstacles\n      Topic: /move_base/local_costmap/inflated_obstacles\n      Value: true\n    - Alpha: 1\n      Class: rviz/GridCells\n      Color: 0; 255; 0\n      Enabled: true\n      Name: Obstacles\n      Topic: /move_base/local_costmap/obstacles\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 204; 0; 255\n      Enabled: true\n      Name: Local Plan\n      Topic: /move_base/TrajectoryPlannerROS/local_plan\n      Value: true\n    - Alpha: 1\n      Buffer Length: 1\n      Class: rviz/Path\n      Color: 0; 255; 0\n      Enabled: true\n      Name: Plan\n      Topic: /move_base/NavfnROS/plan\n      Value: true\n    - Class: rviz/TF\n      Enabled: false\n      Frame Timeout: 15\n      Frames:\n        All Enabled: true\n      Marker Scale: 1\n      Name: TF\n      Show Arrows: true\n      Show Axes: true\n      Show Names: true\n      Tree:\n        {}\n      Update Interval: 0\n      Value: false\n    - Alpha: 1\n      Autocompute Intensity Bounds: true\n      Autocompute Value Bounds:\n        Max Value: 10\n        Min Value: -10\n        Value: true\n      Axis: Z\n      Channel Name: intensity\n      Class: rviz/LaserScan\n      Color: 255; 255; 255\n      Color Transformer: Intensity\n      Decay Time: 0\n      Enabled: true\n      Max Color: 255; 255; 255\n      Max Intensity: 1\n      Min Color: 0; 0; 0\n      Min Intensity: 1\n      Name: LaserScan\n      Position Transformer: XYZ\n      Queue Size: 10\n      Selectable: true\n      Size (Pixels): 3\n      Size (m): 0.01\n      Style: Flat Squares\n      Topic: /base_scan\n      Use Fixed Frame: true\n      Use rainbow: true\n      Value: true\n    - Alpha: 1\n      Axes Length: 1\n      Axes Radius: 0.1\n      Class: rviz/Pose\n      Color: 255; 25; 0\n      Enabled: true\n      Head Length: 0.1\n      Head Radius: 0.05\n      Name: Pose\n      Shaft Length: 0.25\n      Shaft Radius: 0.025\n      Shape: Arrow\n      Topic: /move_base/current_goal\n      Value: true\n  Enabled: true\n  Global Options:\n    Background Color: 48; 48; 48\n    Fixed Frame: map\n    Frame Rate: 30\n  Name: root\n  Tools:\n    - Class: rviz/Interact\n      Hide Inactive Objects: true\n    - Class: rviz/MoveCamera\n    - Class: rviz/Select\n    - Class: rviz/FocusCamera\n    - Class: rviz/Measure\n    - Class: rviz/SetInitialPose\n      Topic: /initialpose\n    - Class: rviz/SetGoal\n      Topic: /move_base_simple/goal\n    - Class: rviz/PublishPoint\n      Single click: true\n      Topic: /clicked_point\n  Value: true\n  Views:\n    Current:\n      Class: rviz/Orbit\n      Distance: 4.91901\n      Focal Point:\n        X: 0\n        Y: 0\n        Z: 0\n      Name: Current View\n      Near Clip Distance: 0.01\n      Pitch: 0.645398\n      Target Frame: base_footprint\n      Value: Orbit (rviz)\n      Yaw: 0.275398\n    Saved: ~\nWindow Geometry:\n  Displays:\n    collapsed: false\n  Height: 756\n  Hide Left Dock: false\n  Hide Right Dock: false\n  QMainWindow State: 000000ff00000000fd0000000400000000000001640000028cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000002540000011a00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000004c0000028c000000dc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000028cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000004c0000028c000000a500fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004fc0000003efc0100000002fb0000000800540069006d00650000000000000004fc0000020b00fffffffb0000000800540069006d00650100000000000004500000000000000000000002870000028c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000\n  Selection:\n    collapsed: false\n  Time:\n    collapsed: false\n  Tool Properties:\n    collapsed: false\n  Views:\n    collapsed: false\n  Width: 1276\n  X: 4\n  Y: 22\n"
  },
  {
    "path": "src/navigation_tutorials/simple_navigation_goals_tutorial/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(simple_navigation_goals_tutorial)\n\nfind_package(catkin REQUIRED COMPONENTS actionlib move_base_msgs roscpp tf)\n\ncatkin_package()\n\ninclude_directories(${catkin_INCLUDE_DIRS})\n\n# Build the executable\nadd_executable(simple_navigation_goals src/simple_navigation_goals.cpp)\n# Add a build order dependency on nav_msgs\n# This ensures that all msg headers are built before your executable\nif(catkin_EXPORTED_TARGETS)\n  add_dependencies(simple_navigation_goals ${catkin_EXPORTED_TARGETS})\nendif()\n# Link against the catkin libraries\ntarget_link_libraries(simple_navigation_goals ${catkin_LIBRARIES})\n\n# Install the executable\ninstall(TARGETS simple_navigation_goals\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})\n"
  },
  {
    "path": "src/navigation_tutorials/simple_navigation_goals_tutorial/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n  <name>simple_navigation_goals_tutorial</name>\n  <version>0.2.3</version>\n  <description>The simple_navigation_goals_tutorial package</description>\n\n  <maintainer email=\"william@osrfoundation.org\">William Woodall</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://ros.org/wiki/simple_navigation_goals_tutorial</url>\n  <url type=\"repository\">https://github.com/ros-planning/navigation_tutorials</url>\n  <url type=\"bugtracker\">https://github.com/ros-planning/navigation_tutorials/issues</url>\n\n  <author>Eitan Marder-Eppstein</author>\n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>actionlib</build_depend>\n  <build_depend>move_base_msgs</build_depend>\n  <build_depend>roscpp</build_depend>\n  <build_depend>tf</build_depend>\n\n  <run_depend>actionlib</run_depend>\n  <run_depend>move_base_msgs</run_depend>\n  <run_depend>roscpp</run_depend>\n  <run_depend>tf</run_depend>\n\n</package>"
  },
  {
    "path": "src/navigation_tutorials/simple_navigation_goals_tutorial/src/simple_navigation_goals.cpp",
    "content": "/*********************************************************************\n*\n* Software License Agreement (BSD License)\n*\n*  Copyright (c) 2008, Willow Garage, Inc.\n*  All rights reserved.\n*\n*  Redistribution and use in source and binary forms, with or without\n*  modification, are permitted provided that the following conditions\n*  are met:\n*\n*   * Redistributions of source code must retain the above copyright\n*     notice, this list of conditions and the following disclaimer.\n*   * Redistributions in binary form must reproduce the above\n*     copyright notice, this list of conditions and the following\n*     disclaimer in the documentation and/or other materials provided\n*     with the distribution.\n*   * Neither the name of Willow Garage, Inc. nor the names of its\n*     contributors may be used to endorse or promote products derived\n*     from this software without specific prior written permission.\n*\n*  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n*  \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n*  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n*  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n*  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n*  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n*  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n*  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n*  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n*  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n*  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n*  POSSIBILITY OF SUCH DAMAGE.\n*\n* Author: Eitan Marder-Eppstein\n*\n* For a discussion of this tutorial, please see:\n* http://pr.willowgarage.com/wiki/navigation/Tutorials/SendingSimpleGoals\n*********************************************************************/\n#include <ros/ros.h>\n#include <move_base_msgs/MoveBaseAction.h>\n#include <actionlib/client/simple_action_client.h>\n#include <tf/transform_datatypes.h>\n\n#include <boost/thread.hpp>\n\ntypedef actionlib::SimpleActionClient<move_base_msgs::MoveBaseAction> MoveBaseClient;\n\nvoid spinThread(){\n  ros::spin();\n}\n\nint main(int argc, char** argv){\n  ros::init(argc, argv, \"simple_navigation_goals\");\n\n  ros::NodeHandle n;\n\n  boost::thread spin_thread = boost::thread(boost::bind(&spinThread));\n\n  MoveBaseClient ac(\"pose_base_controller\");\n\n  //give some time for connections to register\n  sleep(2.0);\n\n  move_base_msgs::MoveBaseGoal goal;\n\n  //we'll send a goal to the robot to move 2 meters forward\n  goal.target_pose.header.frame_id = \"base_link\";\n  goal.target_pose.header.stamp = ros::Time::now();\n\n  goal.target_pose.pose.position.x = 2.0;\n  goal.target_pose.pose.position.y = 0.2;\n  goal.target_pose.pose.orientation = tf::createQuaternionMsgFromYaw(M_PI);\n\n  ROS_INFO(\"Sending goal\");\n  ac.sendGoal(goal);\n\n  ac.waitForResult();\n\n  if(ac.getState() == actionlib::SimpleClientGoalState::SUCCEEDED)\n    ROS_INFO(\"Hooray, the base moved 2 meters forward\");\n  else\n    ROS_INFO(\"The base failed to move forward 2 meters for some reason\");\n\n  return 0;\n}\n"
  },
  {
    "path": "src/rf2o_laser_odometry/CMakeLists.txt",
    "content": "PROJECT(rf2o_laser_odometry)\n\nCMAKE_MINIMUM_REQUIRED(VERSION 3.3)\n# Require C++17\n\nif(${CMAKE_VERSION} VERSION_LESS \"3.8.0\")\n\tset(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -std=c++17\")\nelse()\n\tset(CMAKE_CXX_STANDARD 17)\nendif()\n\n## Find catkin macros and libraries\n## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)\n## is used, also find other catkin packages\nfind_package(catkin REQUIRED COMPONENTS  \n  roscpp\n  rospy\n  nav_msgs\n  sensor_msgs\n  std_msgs\n  tf  \n)\n\n## System dependencies are found with CMake's conventions\nfind_package(Boost REQUIRED COMPONENTS system)\nfind_package(cmake_modules REQUIRED)\nfind_package(Eigen3 REQUIRED)\n\nfind_package(MRPT REQUIRED)\nMESSAGE(STATUS \"Found MRPT: \" ${MRPT_VERSION})\nIF(MRPT_VERSION VERSION_LESS 1.9.9)\n        # MRPT<2.0\n        find_package(MRPT REQUIRED base obs maps slam)\nELSE()\n        # MRPT>=2.0\n        find_package(MRPT REQUIRED obs maps slam poses core)\nENDIF()\n\n\n#include_directories(${MRPT_INCLUDE_DIRS})\n#MESSAGE( STATUS \"MRPT_INCLUDE_DIRS: \" ${MRPT_INCLUDE_DIRS})\n#link_directories(${MRPT_LIBRARY_DIRS})\n#MESSAGE( STATUS \"MRPT_LIBRARY_DIRS: \" ${MRPT_LIBS})\n\n\n\n###################################\n## catkin specific configuration ##\n###################################\n## The catkin_package macro generates cmake config files for your package\n## Declare things to be passed to dependent projects\n## INCLUDE_DIRS: uncomment this if you package contains header files\n## LIBRARIES: libraries you create in this project that dependent projects also need\n## CATKIN_DEPENDS: catkin_packages dependent projects also need\n## DEPENDS: system dependencies of this project that dependent projects also need\ncatkin_package(\n INCLUDE_DIRS include\n LIBRARIES laser_odometry\n CATKIN_DEPENDS nav_msgs roscpp sensor_msgs std_msgs tf\n #DEPENDS system_lib\n)\n\n## Specify additional locations of header files\n## Your package locations should be listed before other locations\ninclude_directories(include)\n\ninclude_directories(\n  ${catkin_INCLUDE_DIRS}\n  ${Boost_INCLUDE_DIRS}\n  ${EIGEN_INCLUDE_DIRS}\n  ${MRPT_INCLUDE_DIRS}\n)\n\n## Declare a cpp executable\nadd_executable(rf2o_laser_odometry_node src/CLaserOdometry2D.cpp)\n\n## Specify libraries to link a library or executable target against\ntarget_link_libraries(rf2o_laser_odometry_node\n   ${catkin_LIBRARIES}\n   ${Boost_LIBRARIES}\n   ${EIGEN_LIBRARIES}\n   ${MRPT_LIBS}\n)\n"
  },
  {
    "path": "src/rf2o_laser_odometry/LICENSE",
    "content": "                    GNU GENERAL PUBLIC LICENSE\n                       Version 3, 29 June 2007\n\n Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>\n Everyone is permitted to copy and distribute verbatim copies\n of this license document, but changing it is not allowed.\n\n                            Preamble\n\n  The GNU General Public License is a free, copyleft license for\nsoftware and other kinds of works.\n\n  The licenses for most software and other practical works are designed\nto take away your freedom to share and change the works.  By contrast,\nthe GNU General Public License is intended to guarantee your freedom to\nshare and change all versions of a program--to make sure it remains free\nsoftware for all its users.  We, the Free Software Foundation, use the\nGNU General Public License for most of our software; it applies also to\nany other work released this way by its authors.  You can apply it to\nyour programs, too.\n\n  When we speak of free software, we are referring to freedom, not\nprice.  Our General Public Licenses are designed to make sure that you\nhave the freedom to distribute copies of free software (and charge for\nthem if you wish), that you receive source code or can get it if you\nwant it, that you can change the software or use pieces of it in new\nfree programs, and that you know you can do these things.\n\n  To protect your rights, we need to prevent others from denying you\nthese rights or asking you to surrender the rights.  Therefore, you have\ncertain responsibilities if you distribute copies of the software, or if\nyou modify it: responsibilities to respect the freedom of others.\n\n  For example, if you distribute copies of such a program, whether\ngratis or for a fee, you must pass on to the recipients the same\nfreedoms that you received.  You must make sure that they, too, receive\nor can get the source code.  And you must show them these terms so they\nknow their rights.\n\n  Developers that use the GNU GPL protect your rights with two steps:\n(1) assert copyright on the software, and (2) offer you this License\ngiving you legal permission to copy, distribute and/or modify it.\n\n  For the developers' and authors' protection, the GPL clearly explains\nthat there is no warranty for this free software.  For both users' and\nauthors' sake, the GPL requires that modified versions be marked as\nchanged, so that their problems will not be attributed erroneously to\nauthors of previous versions.\n\n  Some devices are designed to deny users access to install or run\nmodified versions of the software inside them, although the manufacturer\ncan do so.  This is fundamentally incompatible with the aim of\nprotecting users' freedom to change the software.  The systematic\npattern of such abuse occurs in the area of products for individuals to\nuse, which is precisely where it is most unacceptable.  Therefore, we\nhave designed this version of the GPL to prohibit the practice for those\nproducts.  If such problems arise substantially in other domains, we\nstand ready to extend this provision to those domains in future versions\nof the GPL, as needed to protect the freedom of users.\n\n  Finally, every program is threatened constantly by software patents.\nStates should not allow patents to restrict development and use of\nsoftware on general-purpose computers, but in those that do, we wish to\navoid the special danger that patents applied to a free program could\nmake it effectively proprietary.  To prevent this, the GPL assures that\npatents cannot be used to render the program non-free.\n\n  The precise terms and conditions for copying, distribution and\nmodification follow.\n\n                       TERMS AND CONDITIONS\n\n  0. Definitions.\n\n  \"This License\" refers to version 3 of the GNU General Public License.\n\n  \"Copyright\" also means copyright-like laws that apply to other kinds of\nworks, such as semiconductor masks.\n\n  \"The Program\" refers to any copyrightable work licensed under this\nLicense.  Each licensee is addressed as \"you\".  \"Licensees\" and\n\"recipients\" may be individuals or organizations.\n\n  To \"modify\" a work means to copy from or adapt all or part of the work\nin a fashion requiring copyright permission, other than the making of an\nexact copy.  The resulting work is called a \"modified version\" of the\nearlier work or a work \"based on\" the earlier work.\n\n  A \"covered work\" means either the unmodified Program or a work based\non the Program.\n\n  To \"propagate\" a work means to do anything with it that, without\npermission, would make you directly or secondarily liable for\ninfringement under applicable copyright law, except executing it on a\ncomputer or modifying a private copy.  Propagation includes copying,\ndistribution (with or without modification), making available to the\npublic, and in some countries other activities as well.\n\n  To \"convey\" a work means any kind of propagation that enables other\nparties to make or receive copies.  Mere interaction with a user through\na computer network, with no transfer of a copy, is not conveying.\n\n  An interactive user interface displays \"Appropriate Legal Notices\"\nto the extent that it includes a convenient and prominently visible\nfeature that (1) displays an appropriate copyright notice, and (2)\ntells the user that there is no warranty for the work (except to the\nextent that warranties are provided), that licensees may convey the\nwork under this License, and how to view a copy of this License.  If\nthe interface presents a list of user commands or options, such as a\nmenu, a prominent item in the list meets this criterion.\n\n  1. Source Code.\n\n  The \"source code\" for a work means the preferred form of the work\nfor making modifications to it.  \"Object code\" means any non-source\nform of a work.\n\n  A \"Standard Interface\" means an interface that either is an official\nstandard defined by a recognized standards body, or, in the case of\ninterfaces specified for a particular programming language, one that\nis widely used among developers working in that language.\n\n  The \"System Libraries\" of an executable work include anything, other\nthan the work as a whole, that (a) is included in the normal form of\npackaging a Major Component, but which is not part of that Major\nComponent, and (b) serves only to enable use of the work with that\nMajor Component, or to implement a Standard Interface for which an\nimplementation is available to the public in source code form.  A\n\"Major Component\", in this context, means a major essential component\n(kernel, window system, and so on) of the specific operating system\n(if any) on which the executable work runs, or a compiler used to\nproduce the work, or an object code interpreter used to run it.\n\n  The \"Corresponding Source\" for a work in object code form means all\nthe source code needed to generate, install, and (for an executable\nwork) run the object code and to modify the work, including scripts to\ncontrol those activities.  However, it does not include the work's\nSystem Libraries, or general-purpose tools or generally available free\nprograms which are used unmodified in performing those activities but\nwhich are not part of the work.  For example, Corresponding Source\nincludes interface definition files associated with source files for\nthe work, and the source code for shared libraries and dynamically\nlinked subprograms that the work is specifically designed to require,\nsuch as by intimate data communication or control flow between those\nsubprograms and other parts of the work.\n\n  The Corresponding Source need not include anything that users\ncan regenerate automatically from other parts of the Corresponding\nSource.\n\n  The Corresponding Source for a work in source code form is that\nsame work.\n\n  2. Basic Permissions.\n\n  All rights granted under this License are granted for the term of\ncopyright on the Program, and are irrevocable provided the stated\nconditions are met.  This License explicitly affirms your unlimited\npermission to run the unmodified Program.  The output from running a\ncovered work is covered by this License only if the output, given its\ncontent, constitutes a covered work.  This License acknowledges your\nrights of fair use or other equivalent, as provided by copyright law.\n\n  You may make, run and propagate covered works that you do not\nconvey, without conditions so long as your license otherwise remains\nin force.  You may convey covered works to others for the sole purpose\nof having them make modifications exclusively for you, or provide you\nwith facilities for running those works, provided that you comply with\nthe terms of this License in conveying all material for which you do\nnot control copyright.  Those thus making or running the covered works\nfor you must do so exclusively on your behalf, under your direction\nand control, on terms that prohibit them from making any copies of\nyour copyrighted material outside their relationship with you.\n\n  Conveying under any other circumstances is permitted solely under\nthe conditions stated below.  Sublicensing is not allowed; section 10\nmakes it unnecessary.\n\n  3. Protecting Users' Legal Rights From Anti-Circumvention Law.\n\n  No covered work shall be deemed part of an effective technological\nmeasure under any applicable law fulfilling obligations under article\n11 of the WIPO copyright treaty adopted on 20 December 1996, or\nsimilar laws prohibiting or restricting circumvention of such\nmeasures.\n\n  When you convey a covered work, you waive any legal power to forbid\ncircumvention of technological measures to the extent such circumvention\nis effected by exercising rights under this License with respect to\nthe covered work, and you disclaim any intention to limit operation or\nmodification of the work as a means of enforcing, against the work's\nusers, your or third parties' legal rights to forbid circumvention of\ntechnological measures.\n\n  4. Conveying Verbatim Copies.\n\n  You may convey verbatim copies of the Program's source code as you\nreceive it, in any medium, provided that you conspicuously and\nappropriately publish on each copy an appropriate copyright notice;\nkeep intact all notices stating that this License and any\nnon-permissive terms added in accord with section 7 apply to the code;\nkeep intact all notices of the absence of any warranty; and give all\nrecipients a copy of this License along with the Program.\n\n  You may charge any price or no price for each copy that you convey,\nand you may offer support or warranty protection for a fee.\n\n  5. Conveying Modified Source Versions.\n\n  You may convey a work based on the Program, or the modifications to\nproduce it from the Program, in the form of source code under the\nterms of section 4, provided that you also meet all of these conditions:\n\n    a) The work must carry prominent notices stating that you modified\n    it, and giving a relevant date.\n\n    b) The work must carry prominent notices stating that it is\n    released under this License and any conditions added under section\n    7.  This requirement modifies the requirement in section 4 to\n    \"keep intact all notices\".\n\n    c) You must license the entire work, as a whole, under this\n    License to anyone who comes into possession of a copy.  This\n    License will therefore apply, along with any applicable section 7\n    additional terms, to the whole of the work, and all its parts,\n    regardless of how they are packaged.  This License gives no\n    permission to license the work in any other way, but it does not\n    invalidate such permission if you have separately received it.\n\n    d) If the work has interactive user interfaces, each must display\n    Appropriate Legal Notices; however, if the Program has interactive\n    interfaces that do not display Appropriate Legal Notices, your\n    work need not make them do so.\n\n  A compilation of a covered work with other separate and independent\nworks, which are not by their nature extensions of the covered work,\nand which are not combined with it such as to form a larger program,\nin or on a volume of a storage or distribution medium, is called an\n\"aggregate\" if the compilation and its resulting copyright are not\nused to limit the access or legal rights of the compilation's users\nbeyond what the individual works permit.  Inclusion of a covered work\nin an aggregate does not cause this License to apply to the other\nparts of the aggregate.\n\n  6. Conveying Non-Source Forms.\n\n  You may convey a covered work in object code form under the terms\nof sections 4 and 5, provided that you also convey the\nmachine-readable Corresponding Source under the terms of this License,\nin one of these ways:\n\n    a) Convey the object code in, or embodied in, a physical product\n    (including a physical distribution medium), accompanied by the\n    Corresponding Source fixed on a durable physical medium\n    customarily used for software interchange.\n\n    b) Convey the object code in, or embodied in, a physical product\n    (including a physical distribution medium), accompanied by a\n    written offer, valid for at least three years and valid for as\n    long as you offer spare parts or customer support for that product\n    model, to give anyone who possesses the object code either (1) a\n    copy of the Corresponding Source for all the software in the\n    product that is covered by this License, on a durable physical\n    medium customarily used for software interchange, for a price no\n    more than your reasonable cost of physically performing this\n    conveying of source, or (2) access to copy the\n    Corresponding Source from a network server at no charge.\n\n    c) Convey individual copies of the object code with a copy of the\n    written offer to provide the Corresponding Source.  This\n    alternative is allowed only occasionally and noncommercially, and\n    only if you received the object code with such an offer, in accord\n    with subsection 6b.\n\n    d) Convey the object code by offering access from a designated\n    place (gratis or for a charge), and offer equivalent access to the\n    Corresponding Source in the same way through the same place at no\n    further charge.  You need not require recipients to copy the\n    Corresponding Source along with the object code.  If the place to\n    copy the object code is a network server, the Corresponding Source\n    may be on a different server (operated by you or a third party)\n    that supports equivalent copying facilities, provided you maintain\n    clear directions next to the object code saying where to find the\n    Corresponding Source.  Regardless of what server hosts the\n    Corresponding Source, you remain obligated to ensure that it is\n    available for as long as needed to satisfy these requirements.\n\n    e) Convey the object code using peer-to-peer transmission, provided\n    you inform other peers where the object code and Corresponding\n    Source of the work are being offered to the general public at no\n    charge under subsection 6d.\n\n  A separable portion of the object code, whose source code is excluded\nfrom the Corresponding Source as a System Library, need not be\nincluded in conveying the object code work.\n\n  A \"User Product\" is either (1) a \"consumer product\", which means any\ntangible personal property which is normally used for personal, family,\nor household purposes, or (2) anything designed or sold for incorporation\ninto a dwelling.  In determining whether a product is a consumer product,\ndoubtful cases shall be resolved in favor of coverage.  For a particular\nproduct received by a particular user, \"normally used\" refers to a\ntypical or common use of that class of product, regardless of the status\nof the particular user or of the way in which the particular user\nactually uses, or expects or is expected to use, the product.  A product\nis a consumer product regardless of whether the product has substantial\ncommercial, industrial or non-consumer uses, unless such uses represent\nthe only significant mode of use of the product.\n\n  \"Installation Information\" for a User Product means any methods,\nprocedures, authorization keys, or other information required to install\nand execute modified versions of a covered work in that User Product from\na modified version of its Corresponding Source.  The information must\nsuffice to ensure that the continued functioning of the modified object\ncode is in no case prevented or interfered with solely because\nmodification has been made.\n\n  If you convey an object code work under this section in, or with, or\nspecifically for use in, a User Product, and the conveying occurs as\npart of a transaction in which the right of possession and use of the\nUser Product is transferred to the recipient in perpetuity or for a\nfixed term (regardless of how the transaction is characterized), the\nCorresponding Source conveyed under this section must be accompanied\nby the Installation Information.  But this requirement does not apply\nif neither you nor any third party retains the ability to install\nmodified object code on the User Product (for example, the work has\nbeen installed in ROM).\n\n  The requirement to provide Installation Information does not include a\nrequirement to continue to provide support service, warranty, or updates\nfor a work that has been modified or installed by the recipient, or for\nthe User Product in which it has been modified or installed.  Access to a\nnetwork may be denied when the modification itself materially and\nadversely affects the operation of the network or violates the rules and\nprotocols for communication across the network.\n\n  Corresponding Source conveyed, and Installation Information provided,\nin accord with this section must be in a format that is publicly\ndocumented (and with an implementation available to the public in\nsource code form), and must require no special password or key for\nunpacking, reading or copying.\n\n  7. Additional Terms.\n\n  \"Additional permissions\" are terms that supplement the terms of this\nLicense by making exceptions from one or more of its conditions.\nAdditional permissions that are applicable to the entire Program shall\nbe treated as though they were included in this License, to the extent\nthat they are valid under applicable law.  If additional permissions\napply only to part of the Program, that part may be used separately\nunder those permissions, but the entire Program remains governed by\nthis License without regard to the additional permissions.\n\n  When you convey a copy of a covered work, you may at your option\nremove any additional permissions from that copy, or from any part of\nit.  (Additional permissions may be written to require their own\nremoval in certain cases when you modify the work.)  You may place\nadditional permissions on material, added by you to a covered work,\nfor which you have or can give appropriate copyright permission.\n\n  Notwithstanding any other provision of this License, for material you\nadd to a covered work, you may (if authorized by the copyright holders of\nthat material) supplement the terms of this License with terms:\n\n    a) Disclaiming warranty or limiting liability differently from the\n    terms of sections 15 and 16 of this License; or\n\n    b) Requiring preservation of specified reasonable legal notices or\n    author attributions in that material or in the Appropriate Legal\n    Notices displayed by works containing it; or\n\n    c) Prohibiting misrepresentation of the origin of that material, or\n    requiring that modified versions of such material be marked in\n    reasonable ways as different from the original version; or\n\n    d) Limiting the use for publicity purposes of names of licensors or\n    authors of the material; or\n\n    e) Declining to grant rights under trademark law for use of some\n    trade names, trademarks, or service marks; or\n\n    f) Requiring indemnification of licensors and authors of that\n    material by anyone who conveys the material (or modified versions of\n    it) with contractual assumptions of liability to the recipient, for\n    any liability that these contractual assumptions directly impose on\n    those licensors and authors.\n\n  All other non-permissive additional terms are considered \"further\nrestrictions\" within the meaning of section 10.  If the Program as you\nreceived it, or any part of it, contains a notice stating that it is\ngoverned by this License along with a term that is a further\nrestriction, you may remove that term.  If a license document contains\na further restriction but permits relicensing or conveying under this\nLicense, you may add to a covered work material governed by the terms\nof that license document, provided that the further restriction does\nnot survive such relicensing or conveying.\n\n  If you add terms to a covered work in accord with this section, you\nmust place, in the relevant source files, a statement of the\nadditional terms that apply to those files, or a notice indicating\nwhere to find the applicable terms.\n\n  Additional terms, permissive or non-permissive, may be stated in the\nform of a separately written license, or stated as exceptions;\nthe above requirements apply either way.\n\n  8. Termination.\n\n  You may not propagate or modify a covered work except as expressly\nprovided under this License.  Any attempt otherwise to propagate or\nmodify it is void, and will automatically terminate your rights under\nthis License (including any patent licenses granted under the third\nparagraph of section 11).\n\n  However, if you cease all violation of this License, then your\nlicense from a particular copyright holder is reinstated (a)\nprovisionally, unless and until the copyright holder explicitly and\nfinally terminates your license, and (b) permanently, if the copyright\nholder fails to notify you of the violation by some reasonable means\nprior to 60 days after the cessation.\n\n  Moreover, your license from a particular copyright holder is\nreinstated permanently if the copyright holder notifies you of the\nviolation by some reasonable means, this is the first time you have\nreceived notice of violation of this License (for any work) from that\ncopyright holder, and you cure the violation prior to 30 days after\nyour receipt of the notice.\n\n  Termination of your rights under this section does not terminate the\nlicenses of parties who have received copies or rights from you under\nthis License.  If your rights have been terminated and not permanently\nreinstated, you do not qualify to receive new licenses for the same\nmaterial under section 10.\n\n  9. Acceptance Not Required for Having Copies.\n\n  You are not required to accept this License in order to receive or\nrun a copy of the Program.  Ancillary propagation of a covered work\noccurring solely as a consequence of using peer-to-peer transmission\nto receive a copy likewise does not require acceptance.  However,\nnothing other than this License grants you permission to propagate or\nmodify any covered work.  These actions infringe copyright if you do\nnot accept this License.  Therefore, by modifying or propagating a\ncovered work, you indicate your acceptance of this License to do so.\n\n  10. Automatic Licensing of Downstream Recipients.\n\n  Each time you convey a covered work, the recipient automatically\nreceives a license from the original licensors, to run, modify and\npropagate that work, subject to this License.  You are not responsible\nfor enforcing compliance by third parties with this License.\n\n  An \"entity transaction\" is a transaction transferring control of an\norganization, or substantially all assets of one, or subdividing an\norganization, or merging organizations.  If propagation of a covered\nwork results from an entity transaction, each party to that\ntransaction who receives a copy of the work also receives whatever\nlicenses to the work the party's predecessor in interest had or could\ngive under the previous paragraph, plus a right to possession of the\nCorresponding Source of the work from the predecessor in interest, if\nthe predecessor has it or can get it with reasonable efforts.\n\n  You may not impose any further restrictions on the exercise of the\nrights granted or affirmed under this License.  For example, you may\nnot impose a license fee, royalty, or other charge for exercise of\nrights granted under this License, and you may not initiate litigation\n(including a cross-claim or counterclaim in a lawsuit) alleging that\nany patent claim is infringed by making, using, selling, offering for\nsale, or importing the Program or any portion of it.\n\n  11. Patents.\n\n  A \"contributor\" is a copyright holder who authorizes use under this\nLicense of the Program or a work on which the Program is based.  The\nwork thus licensed is called the contributor's \"contributor version\".\n\n  A contributor's \"essential patent claims\" are all patent claims\nowned or controlled by the contributor, whether already acquired or\nhereafter acquired, that would be infringed by some manner, permitted\nby this License, of making, using, or selling its contributor version,\nbut do not include claims that would be infringed only as a\nconsequence of further modification of the contributor version.  For\npurposes of this definition, \"control\" includes the right to grant\npatent sublicenses in a manner consistent with the requirements of\nthis License.\n\n  Each contributor grants you a non-exclusive, worldwide, royalty-free\npatent license under the contributor's essential patent claims, to\nmake, use, sell, offer for sale, import and otherwise run, modify and\npropagate the contents of its contributor version.\n\n  In the following three paragraphs, a \"patent license\" is any express\nagreement or commitment, however denominated, not to enforce a patent\n(such as an express permission to practice a patent or covenant not to\nsue for patent infringement).  To \"grant\" such a patent license to a\nparty means to make such an agreement or commitment not to enforce a\npatent against the party.\n\n  If you convey a covered work, knowingly relying on a patent license,\nand the Corresponding Source of the work is not available for anyone\nto copy, free of charge and under the terms of this License, through a\npublicly available network server or other readily accessible means,\nthen you must either (1) cause the Corresponding Source to be so\navailable, or (2) arrange to deprive yourself of the benefit of the\npatent license for this particular work, or (3) arrange, in a manner\nconsistent with the requirements of this License, to extend the patent\nlicense to downstream recipients.  \"Knowingly relying\" means you have\nactual knowledge that, but for the patent license, your conveying the\ncovered work in a country, or your recipient's use of the covered work\nin a country, would infringe one or more identifiable patents in that\ncountry that you have reason to believe are valid.\n\n  If, pursuant to or in connection with a single transaction or\narrangement, you convey, or propagate by procuring conveyance of, a\ncovered work, and grant a patent license to some of the parties\nreceiving the covered work authorizing them to use, propagate, modify\nor convey a specific copy of the covered work, then the patent license\nyou grant is automatically extended to all recipients of the covered\nwork and works based on it.\n\n  A patent license is \"discriminatory\" if it does not include within\nthe scope of its coverage, prohibits the exercise of, or is\nconditioned on the non-exercise of one or more of the rights that are\nspecifically granted under this License.  You may not convey a covered\nwork if you are a party to an arrangement with a third party that is\nin the business of distributing software, under which you make payment\nto the third party based on the extent of your activity of conveying\nthe work, and under which the third party grants, to any of the\nparties who would receive the covered work from you, a discriminatory\npatent license (a) in connection with copies of the covered work\nconveyed by you (or copies made from those copies), or (b) primarily\nfor and in connection with specific products or compilations that\ncontain the covered work, unless you entered into that arrangement,\nor that patent license was granted, prior to 28 March 2007.\n\n  Nothing in this License shall be construed as excluding or limiting\nany implied license or other defenses to infringement that may\notherwise be available to you under applicable patent law.\n\n  12. No Surrender of Others' Freedom.\n\n  If conditions are imposed on you (whether by court order, agreement or\notherwise) that contradict the conditions of this License, they do not\nexcuse you from the conditions of this License.  If you cannot convey a\ncovered work so as to satisfy simultaneously your obligations under this\nLicense and any other pertinent obligations, then as a consequence you may\nnot convey it at all.  For example, if you agree to terms that obligate you\nto collect a royalty for further conveying from those to whom you convey\nthe Program, the only way you could satisfy both those terms and this\nLicense would be to refrain entirely from conveying the Program.\n\n  13. Use with the GNU Affero General Public License.\n\n  Notwithstanding any other provision of this License, you have\npermission to link or combine any covered work with a work licensed\nunder version 3 of the GNU Affero General Public License into a single\ncombined work, and to convey the resulting work.  The terms of this\nLicense will continue to apply to the part which is the covered work,\nbut the special requirements of the GNU Affero General Public License,\nsection 13, concerning interaction through a network will apply to the\ncombination as such.\n\n  14. Revised Versions of this License.\n\n  The Free Software Foundation may publish revised and/or new versions of\nthe GNU General Public License from time to time.  Such new versions will\nbe similar in spirit to the present version, but may differ in detail to\naddress new problems or concerns.\n\n  Each version is given a distinguishing version number.  If the\nProgram specifies that a certain numbered version of the GNU General\nPublic License \"or any later version\" applies to it, you have the\noption of following the terms and conditions either of that numbered\nversion or of any later version published by the Free Software\nFoundation.  If the Program does not specify a version number of the\nGNU General Public License, you may choose any version ever published\nby the Free Software Foundation.\n\n  If the Program specifies that a proxy can decide which future\nversions of the GNU General Public License can be used, that proxy's\npublic statement of acceptance of a version permanently authorizes you\nto choose that version for the Program.\n\n  Later license versions may give you additional or different\npermissions.  However, no additional obligations are imposed on any\nauthor or copyright holder as a result of your choosing to follow a\nlater version.\n\n  15. Disclaimer of Warranty.\n\n  THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY\nAPPLICABLE LAW.  EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT\nHOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM \"AS IS\" WITHOUT WARRANTY\nOF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,\nTHE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\nPURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM\nIS WITH YOU.  SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF\nALL NECESSARY SERVICING, REPAIR OR CORRECTION.\n\n  16. Limitation of Liability.\n\n  IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING\nWILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS\nTHE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY\nGENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE\nUSE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF\nDATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD\nPARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),\nEVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF\nSUCH DAMAGES.\n\n  17. Interpretation of Sections 15 and 16.\n\n  If the disclaimer of warranty and limitation of liability provided\nabove cannot be given local legal effect according to their terms,\nreviewing courts shall apply local law that most closely approximates\nan absolute waiver of all civil liability in connection with the\nProgram, unless a warranty or assumption of liability accompanies a\ncopy of the Program in return for a fee.\n\n                     END OF TERMS AND CONDITIONS\n\n            How to Apply These Terms to Your New Programs\n\n  If you develop a new program, and you want it to be of the greatest\npossible use to the public, the best way to achieve this is to make it\nfree software which everyone can redistribute and change under these terms.\n\n  To do so, attach the following notices to the program.  It is safest\nto attach them to the start of each source file to most effectively\nstate the exclusion of warranty; and each file should have at least\nthe \"copyright\" line and a pointer to where the full notice is found.\n\n    {one line to give the program's name and a brief idea of what it does.}\n    Copyright (C) {year}  {name of author}\n\n    This program is free software: you can redistribute it and/or modify\n    it under the terms of the GNU General Public License as published by\n    the Free Software Foundation, either version 3 of the License, or\n    (at your option) any later version.\n\n    This program is distributed in the hope that it will be useful,\n    but WITHOUT ANY WARRANTY; without even the implied warranty of\n    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n    GNU General Public License for more details.\n\n    You should have received a copy of the GNU General Public License\n    along with this program.  If not, see <http://www.gnu.org/licenses/>.\n\nAlso add information on how to contact you by electronic and paper mail.\n\n  If the program does terminal interaction, make it output a short\nnotice like this when it starts in an interactive mode:\n\n    {project}  Copyright (C) {year}  {fullname}\n    This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.\n    This is free software, and you are welcome to redistribute it\n    under certain conditions; type `show c' for details.\n\nThe hypothetical commands `show w' and `show c' should show the appropriate\nparts of the General Public License.  Of course, your program's commands\nmight be different; for a GUI interface, you would use an \"about box\".\n\n  You should also get your employer (if you work as a programmer) or school,\nif any, to sign a \"copyright disclaimer\" for the program, if necessary.\nFor more information on this, and how to apply and follow the GNU GPL, see\n<http://www.gnu.org/licenses/>.\n\n  The GNU General Public License does not permit incorporating your program\ninto proprietary programs.  If your program is a subroutine library, you\nmay consider it more useful to permit linking proprietary applications with\nthe library.  If this is what you want to do, use the GNU Lesser General\nPublic License instead of this License.  But first, please read\n<http://www.gnu.org/philosophy/why-not-lgpl.html>.\n"
  },
  {
    "path": "src/rf2o_laser_odometry/README.md",
    "content": "# rf2o_laser_odometry\nEstimation of 2D odometry based on planar laser scans. Useful for mobile robots with innacurate base odometry. \n\nRF2O 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. \n\nIts 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.\n\nFor 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\n\n\n# Requirements\nRF2O 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/))\nSo 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\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CATKIN_IGNORE",
    "content": ""
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeCache.txt",
    "content": "# This is the CMakeCache file.\n# For build in directory: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n# It was generated by CMake: /home/zn/.ide/clion/bin/cmake/bin/cmake\n# You can edit this file to change values found and used by cmake.\n# If you do not want to change any of the values, simply exit the editor.\n# If you do want to change a value, simply edit, save, and exit the editor.\n# The syntax for the file is as follows:\n# KEY:TYPE=VALUE\n# KEY is the name of a variable in the cache.\n# TYPE is a hint to GUIs for the type of VALUE, DO NOT EDIT TYPE!.\n# VALUE is the current value for the KEY.\n\n########################\n# EXTERNAL cache entries\n########################\n\n//Build dynamically-linked binaries\nBUILD_SHARED_LIBS:BOOL=ON\n\n//The directory containing a CMake configuration file for Boost.\nBoost_DIR:PATH=Boost_DIR-NOTFOUND\n\n//Path to a file.\nBoost_INCLUDE_DIR:PATH=/usr/include\n\n//Boost library directory DEBUG\nBoost_LIBRARY_DIR_DEBUG:PATH=/usr/lib/x86_64-linux-gnu\n\n//Boost library directory RELEASE\nBoost_LIBRARY_DIR_RELEASE:PATH=/usr/lib/x86_64-linux-gnu\n\n//Boost system library (debug)\nBoost_SYSTEM_LIBRARY_DEBUG:FILEPATH=/usr/lib/x86_64-linux-gnu/libboost_system.so\n\n//Boost system library (release)\nBoost_SYSTEM_LIBRARY_RELEASE:FILEPATH=/usr/lib/x86_64-linux-gnu/libboost_system.so\n\n//Catkin enable testing\nCATKIN_ENABLE_TESTING:BOOL=ON\n\n//Prefix to apply to package generated via gendebian\nCATKIN_PACKAGE_PREFIX:STRING=\n\n//Catkin skip testing\nCATKIN_SKIP_TESTING:BOOL=OFF\n\n//Path to a program.\nCMAKE_AR:FILEPATH=/usr/bin/ar\n\n//Choose the type of build, options are: None(CMAKE_CXX_FLAGS or\n// CMAKE_C_FLAGS used) Debug Release RelWithDebInfo MinSizeRel.\nCMAKE_BUILD_TYPE:STRING=Debug\n\n//The CodeBlocks executable\nCMAKE_CODEBLOCKS_EXECUTABLE:FILEPATH=CMAKE_CODEBLOCKS_EXECUTABLE-NOTFOUND\n\n//Additional command line arguments when CodeBlocks invokes make.\n// Enter e.g. -j<some_number> to get parallel builds\nCMAKE_CODEBLOCKS_MAKE_ARGUMENTS:STRING=-j8\n\n//Enable/Disable color output during build.\nCMAKE_COLOR_MAKEFILE:BOOL=ON\n\n//CXX compiler\nCMAKE_CXX_COMPILER:FILEPATH=/usr/bin/c++\n\n//A wrapper around 'ar' adding the appropriate '--plugin' option\n// for the GCC compiler\nCMAKE_CXX_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-5\n\n//A wrapper around 'ranlib' adding the appropriate '--plugin' option\n// for the GCC compiler\nCMAKE_CXX_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-5\n\n//Flags used by the compiler during all build types.\nCMAKE_CXX_FLAGS:STRING=\n\n//Flags used by the compiler during debug builds.\nCMAKE_CXX_FLAGS_DEBUG:STRING=-g\n\n//Flags used by the compiler during release builds for minimum\n// size.\nCMAKE_CXX_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG\n\n//Flags used by the compiler during release builds.\nCMAKE_CXX_FLAGS_RELEASE:STRING=-O3 -DNDEBUG\n\n//Flags used by the compiler during release builds with debug info.\nCMAKE_CXX_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG\n\n//C compiler\nCMAKE_C_COMPILER:FILEPATH=/usr/bin/cc\n\n//A wrapper around 'ar' adding the appropriate '--plugin' option\n// for the GCC compiler\nCMAKE_C_COMPILER_AR:FILEPATH=/usr/bin/gcc-ar-5\n\n//A wrapper around 'ranlib' adding the appropriate '--plugin' option\n// for the GCC compiler\nCMAKE_C_COMPILER_RANLIB:FILEPATH=/usr/bin/gcc-ranlib-5\n\n//Flags used by the compiler during all build types.\nCMAKE_C_FLAGS:STRING=\n\n//Flags used by the compiler during debug builds.\nCMAKE_C_FLAGS_DEBUG:STRING=-g\n\n//Flags used by the compiler during release builds for minimum\n// size.\nCMAKE_C_FLAGS_MINSIZEREL:STRING=-Os -DNDEBUG\n\n//Flags used by the compiler during release builds.\nCMAKE_C_FLAGS_RELEASE:STRING=-O3 -DNDEBUG\n\n//Flags used by the compiler during release builds with debug info.\nCMAKE_C_FLAGS_RELWITHDEBINFO:STRING=-O2 -g -DNDEBUG\n\n//Flags used by the linker.\nCMAKE_EXE_LINKER_FLAGS:STRING=\n\n//Flags used by the linker during debug builds.\nCMAKE_EXE_LINKER_FLAGS_DEBUG:STRING=\n\n//Flags used by the linker during release minsize builds.\nCMAKE_EXE_LINKER_FLAGS_MINSIZEREL:STRING=\n\n//Flags used by the linker during release builds.\nCMAKE_EXE_LINKER_FLAGS_RELEASE:STRING=\n\n//Flags used by the linker during Release with Debug Info builds.\nCMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO:STRING=\n\n//Enable/Disable output of compile commands during generation.\nCMAKE_EXPORT_COMPILE_COMMANDS:BOOL=OFF\n\n//Install path prefix, prepended onto install directories.\nCMAKE_INSTALL_PREFIX:PATH=/usr/local\n\n//Path to a program.\nCMAKE_LINKER:FILEPATH=/usr/bin/ld\n\n//Path to a program.\nCMAKE_MAKE_PROGRAM:FILEPATH=/usr/bin/make\n\n//Flags used by the linker during the creation of modules.\nCMAKE_MODULE_LINKER_FLAGS:STRING=\n\n//Flags used by the linker during debug builds.\nCMAKE_MODULE_LINKER_FLAGS_DEBUG:STRING=\n\n//Flags used by the linker during release minsize builds.\nCMAKE_MODULE_LINKER_FLAGS_MINSIZEREL:STRING=\n\n//Flags used by the linker during release builds.\nCMAKE_MODULE_LINKER_FLAGS_RELEASE:STRING=\n\n//Flags used by the linker during Release with Debug Info builds.\nCMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO:STRING=\n\n//Path to a program.\nCMAKE_NM:FILEPATH=/usr/bin/nm\n\n//Path to a program.\nCMAKE_OBJCOPY:FILEPATH=/usr/bin/objcopy\n\n//Path to a program.\nCMAKE_OBJDUMP:FILEPATH=/usr/bin/objdump\n\n//Value Computed by CMake\nCMAKE_PROJECT_NAME:STATIC=rf2o_laser_odometry\n\n//Path to a program.\nCMAKE_RANLIB:FILEPATH=/usr/bin/ranlib\n\n//Flags used by the linker during the creation of dll's.\nCMAKE_SHARED_LINKER_FLAGS:STRING=\n\n//Flags used by the linker during debug builds.\nCMAKE_SHARED_LINKER_FLAGS_DEBUG:STRING=\n\n//Flags used by the linker during release minsize builds.\nCMAKE_SHARED_LINKER_FLAGS_MINSIZEREL:STRING=\n\n//Flags used by the linker during release builds.\nCMAKE_SHARED_LINKER_FLAGS_RELEASE:STRING=\n\n//Flags used by the linker during Release with Debug Info builds.\nCMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO:STRING=\n\n//If set, runtime paths are not added when installing shared libraries,\n// but are added when building.\nCMAKE_SKIP_INSTALL_RPATH:BOOL=NO\n\n//If set, runtime paths are not added when using shared libraries.\nCMAKE_SKIP_RPATH:BOOL=NO\n\n//Flags used by the linker during the creation of static libraries.\nCMAKE_STATIC_LINKER_FLAGS:STRING=\n\n//Flags used by the linker during debug builds.\nCMAKE_STATIC_LINKER_FLAGS_DEBUG:STRING=\n\n//Flags used by the linker during release minsize builds.\nCMAKE_STATIC_LINKER_FLAGS_MINSIZEREL:STRING=\n\n//Flags used by the linker during release builds.\nCMAKE_STATIC_LINKER_FLAGS_RELEASE:STRING=\n\n//Flags used by the linker during Release with Debug Info builds.\nCMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO:STRING=\n\n//Path to a program.\nCMAKE_STRIP:FILEPATH=/usr/bin/strip\n\n//If this value is on, makefiles will be generated without the\n// .SILENT directive, and all commands will be echoed to the console\n// during the make.  This is useful for debugging only. With Visual\n// Studio IDE projects all commands are done without /nologo.\nCMAKE_VERBOSE_MAKEFILE:BOOL=FALSE\n\n//Path to a program.\nDOXYGEN_EXECUTABLE:FILEPATH=DOXYGEN_EXECUTABLE-NOTFOUND\n\n//Path to a program.\nEMPY_EXECUTABLE:FILEPATH=/usr/bin/empy\n\n//Empy script\nEMPY_SCRIPT:STRING=/usr/bin/empy\n\n//The directory containing a CMake configuration file for Eigen3.\nEigen3_DIR:PATH=/usr/lib/cmake/eigen3\n\n//The directory containing a CMake configuration file for GMock.\nGMock_DIR:PATH=GMock_DIR-NOTFOUND\n\n//Path to a file.\nGTEST_INCLUDE_DIR:PATH=/usr/local/include\n\n//Path to a library.\nGTEST_LIBRARY:FILEPATH=/usr/local/lib/libgtest.a\n\n//Path to a library.\nGTEST_LIBRARY_DEBUG:FILEPATH=GTEST_LIBRARY_DEBUG-NOTFOUND\n\n//Path to a library.\nGTEST_MAIN_LIBRARY:FILEPATH=/usr/local/lib/libgtest_main.a\n\n//Path to a library.\nGTEST_MAIN_LIBRARY_DEBUG:FILEPATH=GTEST_MAIN_LIBRARY_DEBUG-NOTFOUND\n\n//lsb_release executable was found\nLSB_FOUND:BOOL=TRUE\n\n//Path to a program.\nLSB_RELEASE_EXECUTABLE:FILEPATH=/usr/bin/lsb_release\n\n//The directory containing a CMake configuration file for MRPT.\nMRPT_DIR:PATH=/usr/share/mrpt\n\n//Path to a program.\nNOSETESTS:FILEPATH=/usr/bin/nosetests-2.7\n\n//Path to a program.\nPYTHON_EXECUTABLE:FILEPATH=/usr/bin/python\n\n//Specify specific Python version to use ('major.minor' or 'major')\nPYTHON_VERSION:STRING=\n\n//Path to a program.\nProcessorCount_cmd_getconf:FILEPATH=/usr/bin/getconf\n\n//Path to a program.\nProcessorCount_cmd_sysctl:FILEPATH=/sbin/sysctl\n\n//Path to a library.\nRT_LIBRARY:FILEPATH=/usr/lib/x86_64-linux-gnu/librt.so\n\n//Enable debian style python package layout\nSETUPTOOLS_DEB_LAYOUT:BOOL=ON\n\n//LSB Distrib tag\nUBUNTU:BOOL=TRUE\n\n//LSB Distrib - codename tag\nUBUNTU_XENIAL:BOOL=TRUE\n\n//The directory containing a CMake configuration file for actionlib.\nactionlib_DIR:PATH=/opt/ros/kinetic/share/actionlib/cmake\n\n//The directory containing a CMake configuration file for actionlib_msgs.\nactionlib_msgs_DIR:PATH=/opt/ros/kinetic/share/actionlib_msgs/cmake\n\n//The directory containing a CMake configuration file for catkin.\ncatkin_DIR:PATH=/opt/ros/kinetic/share/catkin/cmake\n\n//The directory containing a CMake configuration file for cmake_modules.\ncmake_modules_DIR:PATH=/opt/ros/kinetic/share/cmake_modules/cmake\n\n//The directory containing a CMake configuration file for cpp_common.\ncpp_common_DIR:PATH=/opt/ros/kinetic/share/cpp_common/cmake\n\n//The directory containing a CMake configuration file for gencpp.\ngencpp_DIR:PATH=/opt/ros/kinetic/share/gencpp/cmake\n\n//The directory containing a CMake configuration file for geneus.\ngeneus_DIR:PATH=/opt/ros/kinetic/share/geneus/cmake\n\n//The directory containing a CMake configuration file for genlisp.\ngenlisp_DIR:PATH=/opt/ros/kinetic/share/genlisp/cmake\n\n//The directory containing a CMake configuration file for genmsg.\ngenmsg_DIR:PATH=/opt/ros/kinetic/share/genmsg/cmake\n\n//The directory containing a CMake configuration file for gennodejs.\ngennodejs_DIR:PATH=/opt/ros/kinetic/share/gennodejs/cmake\n\n//The directory containing a CMake configuration file for genpy.\ngenpy_DIR:PATH=/opt/ros/kinetic/share/genpy/cmake\n\n//The directory containing a CMake configuration file for geometry_msgs.\ngeometry_msgs_DIR:PATH=/opt/ros/kinetic/share/geometry_msgs/cmake\n\n//Path to a library.\nlib:FILEPATH=/opt/ros/kinetic/lib/libtf2.so\n\n//The directory containing a CMake configuration file for message_filters.\nmessage_filters_DIR:PATH=/opt/ros/kinetic/share/message_filters/cmake\n\n//The directory containing a CMake configuration file for message_generation.\nmessage_generation_DIR:PATH=/opt/ros/kinetic/share/message_generation/cmake\n\n//The directory containing a CMake configuration file for message_runtime.\nmessage_runtime_DIR:PATH=/opt/ros/kinetic/share/message_runtime/cmake\n\n//The directory containing a CMake configuration file for nav_msgs.\nnav_msgs_DIR:PATH=/opt/ros/kinetic/share/nav_msgs/cmake\n\n//Value Computed by CMake\nrf2o_laser_odometry_BINARY_DIR:STATIC=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n//Value Computed by CMake\nrf2o_laser_odometry_SOURCE_DIR:STATIC=/home/zn/racecar/src/rf2o_laser_odometry\n\n//The directory containing a CMake configuration file for rosconsole.\nrosconsole_DIR:PATH=/opt/ros/kinetic/share/rosconsole/cmake\n\n//The directory containing a CMake configuration file for roscpp.\nroscpp_DIR:PATH=/opt/ros/kinetic/share/roscpp/cmake\n\n//The directory containing a CMake configuration file for roscpp_serialization.\nroscpp_serialization_DIR:PATH=/opt/ros/kinetic/share/roscpp_serialization/cmake\n\n//The directory containing a CMake configuration file for roscpp_traits.\nroscpp_traits_DIR:PATH=/opt/ros/kinetic/share/roscpp_traits/cmake\n\n//The directory containing a CMake configuration file for rosgraph.\nrosgraph_DIR:PATH=/opt/ros/kinetic/share/rosgraph/cmake\n\n//The directory containing a CMake configuration file for rosgraph_msgs.\nrosgraph_msgs_DIR:PATH=/opt/ros/kinetic/share/rosgraph_msgs/cmake\n\n//The directory containing a CMake configuration file for rospy.\nrospy_DIR:PATH=/opt/ros/kinetic/share/rospy/cmake\n\n//The directory containing a CMake configuration file for rostime.\nrostime_DIR:PATH=/opt/ros/kinetic/share/rostime/cmake\n\n//The directory containing a CMake configuration file for sensor_msgs.\nsensor_msgs_DIR:PATH=/opt/ros/kinetic/share/sensor_msgs/cmake\n\n//The directory containing a CMake configuration file for std_msgs.\nstd_msgs_DIR:PATH=/opt/ros/kinetic/share/std_msgs/cmake\n\n//The directory containing a CMake configuration file for tf2.\ntf2_DIR:PATH=/opt/ros/kinetic/share/tf2/cmake\n\n//The directory containing a CMake configuration file for tf2_msgs.\ntf2_msgs_DIR:PATH=/opt/ros/kinetic/share/tf2_msgs/cmake\n\n//The directory containing a CMake configuration file for tf2_py.\ntf2_py_DIR:PATH=/opt/ros/kinetic/share/tf2_py/cmake\n\n//The directory containing a CMake configuration file for tf2_ros.\ntf2_ros_DIR:PATH=/opt/ros/kinetic/share/tf2_ros/cmake\n\n//The directory containing a CMake configuration file for tf.\ntf_DIR:PATH=/opt/ros/kinetic/share/tf/cmake\n\n//The directory containing a CMake configuration file for xmlrpcpp.\nxmlrpcpp_DIR:PATH=/opt/ros/kinetic/share/xmlrpcpp/cmake\n\n\n########################\n# INTERNAL cache entries\n########################\n\n//ADVANCED property for variable: Boost_DIR\nBoost_DIR-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: Boost_INCLUDE_DIR\nBoost_INCLUDE_DIR-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: Boost_LIBRARY_DIR_DEBUG\nBoost_LIBRARY_DIR_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: Boost_LIBRARY_DIR_RELEASE\nBoost_LIBRARY_DIR_RELEASE-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: Boost_SYSTEM_LIBRARY_DEBUG\nBoost_SYSTEM_LIBRARY_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: Boost_SYSTEM_LIBRARY_RELEASE\nBoost_SYSTEM_LIBRARY_RELEASE-ADVANCED:INTERNAL=1\n//catkin environment\nCATKIN_ENV:INTERNAL=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/env_cached.sh\nCATKIN_TEST_RESULTS_DIR:INTERNAL=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/test_results\n//ADVANCED property for variable: CMAKE_AR\nCMAKE_AR-ADVANCED:INTERNAL=1\n//This is the directory where this CMakeCache.txt was created\nCMAKE_CACHEFILE_DIR:INTERNAL=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n//Major version of cmake used to create the current loaded cache\nCMAKE_CACHE_MAJOR_VERSION:INTERNAL=3\n//Minor version of cmake used to create the current loaded cache\nCMAKE_CACHE_MINOR_VERSION:INTERNAL=9\n//Patch version of cmake used to create the current loaded cache\nCMAKE_CACHE_PATCH_VERSION:INTERNAL=6\n//ADVANCED property for variable: CMAKE_COLOR_MAKEFILE\nCMAKE_COLOR_MAKEFILE-ADVANCED:INTERNAL=1\n//Path to CMake executable.\nCMAKE_COMMAND:INTERNAL=/home/zn/.ide/clion/bin/cmake/bin/cmake\n//Path to cpack program executable.\nCMAKE_CPACK_COMMAND:INTERNAL=/home/zn/.ide/clion/bin/cmake/bin/cpack\n//Path to ctest program executable.\nCMAKE_CTEST_COMMAND:INTERNAL=/home/zn/.ide/clion/bin/cmake/bin/ctest\n//ADVANCED property for variable: CMAKE_CXX_COMPILER\nCMAKE_CXX_COMPILER-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_CXX_COMPILER_AR\nCMAKE_CXX_COMPILER_AR-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_CXX_COMPILER_RANLIB\nCMAKE_CXX_COMPILER_RANLIB-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_CXX_FLAGS\nCMAKE_CXX_FLAGS-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_CXX_FLAGS_DEBUG\nCMAKE_CXX_FLAGS_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_CXX_FLAGS_MINSIZEREL\nCMAKE_CXX_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELEASE\nCMAKE_CXX_FLAGS_RELEASE-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_CXX_FLAGS_RELWITHDEBINFO\nCMAKE_CXX_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_C_COMPILER\nCMAKE_C_COMPILER-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_C_COMPILER_AR\nCMAKE_C_COMPILER_AR-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_C_COMPILER_RANLIB\nCMAKE_C_COMPILER_RANLIB-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_C_FLAGS\nCMAKE_C_FLAGS-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_C_FLAGS_DEBUG\nCMAKE_C_FLAGS_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_C_FLAGS_MINSIZEREL\nCMAKE_C_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_C_FLAGS_RELEASE\nCMAKE_C_FLAGS_RELEASE-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_C_FLAGS_RELWITHDEBINFO\nCMAKE_C_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1\n//Executable file format\nCMAKE_EXECUTABLE_FORMAT:INTERNAL=ELF\n//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS\nCMAKE_EXE_LINKER_FLAGS-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_DEBUG\nCMAKE_EXE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_MINSIZEREL\nCMAKE_EXE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELEASE\nCMAKE_EXE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO\nCMAKE_EXE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_EXPORT_COMPILE_COMMANDS\nCMAKE_EXPORT_COMPILE_COMMANDS-ADVANCED:INTERNAL=1\n//Name of external makefile project generator.\nCMAKE_EXTRA_GENERATOR:INTERNAL=CodeBlocks\n//CXX compiler system defined macros\nCMAKE_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\n//CXX compiler system include directories\nCMAKE_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\n//C compiler system defined macros\nCMAKE_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\n//C compiler system include directories\nCMAKE_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\n//Name of generator.\nCMAKE_GENERATOR:INTERNAL=Unix Makefiles\n//Name of generator platform.\nCMAKE_GENERATOR_PLATFORM:INTERNAL=\n//Name of generator toolset.\nCMAKE_GENERATOR_TOOLSET:INTERNAL=\n//Have symbol pthread_create\nCMAKE_HAVE_LIBC_CREATE:INTERNAL=\n//Have library pthreads\nCMAKE_HAVE_PTHREADS_CREATE:INTERNAL=\n//Have library pthread\nCMAKE_HAVE_PTHREAD_CREATE:INTERNAL=1\n//Have include pthread.h\nCMAKE_HAVE_PTHREAD_H:INTERNAL=1\n//Source directory with the top level CMakeLists.txt file for this\n// project\nCMAKE_HOME_DIRECTORY:INTERNAL=/home/zn/racecar/src/rf2o_laser_odometry\n//Install .so files without execute permission.\nCMAKE_INSTALL_SO_NO_EXE:INTERNAL=1\n//ADVANCED property for variable: CMAKE_LINKER\nCMAKE_LINKER-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_MAKE_PROGRAM\nCMAKE_MAKE_PROGRAM-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS\nCMAKE_MODULE_LINKER_FLAGS-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_DEBUG\nCMAKE_MODULE_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_MINSIZEREL\nCMAKE_MODULE_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELEASE\nCMAKE_MODULE_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO\nCMAKE_MODULE_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_NM\nCMAKE_NM-ADVANCED:INTERNAL=1\n//number of local generators\nCMAKE_NUMBER_OF_MAKEFILES:INTERNAL=1\n//ADVANCED property for variable: CMAKE_OBJCOPY\nCMAKE_OBJCOPY-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_OBJDUMP\nCMAKE_OBJDUMP-ADVANCED:INTERNAL=1\n//Platform information initialized\nCMAKE_PLATFORM_INFO_INITIALIZED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_RANLIB\nCMAKE_RANLIB-ADVANCED:INTERNAL=1\n//Path to CMake installation.\nCMAKE_ROOT:INTERNAL=/home/zn/.ide/clion/bin/cmake/share/cmake-3.9\n//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS\nCMAKE_SHARED_LINKER_FLAGS-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_DEBUG\nCMAKE_SHARED_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_MINSIZEREL\nCMAKE_SHARED_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELEASE\nCMAKE_SHARED_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO\nCMAKE_SHARED_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_SKIP_INSTALL_RPATH\nCMAKE_SKIP_INSTALL_RPATH-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_SKIP_RPATH\nCMAKE_SKIP_RPATH-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS\nCMAKE_STATIC_LINKER_FLAGS-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_DEBUG\nCMAKE_STATIC_LINKER_FLAGS_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_MINSIZEREL\nCMAKE_STATIC_LINKER_FLAGS_MINSIZEREL-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELEASE\nCMAKE_STATIC_LINKER_FLAGS_RELEASE-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO\nCMAKE_STATIC_LINKER_FLAGS_RELWITHDEBINFO-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: CMAKE_STRIP\nCMAKE_STRIP-ADVANCED:INTERNAL=1\n//uname command\nCMAKE_UNAME:INTERNAL=/bin/uname\n//ADVANCED property for variable: CMAKE_VERBOSE_MAKEFILE\nCMAKE_VERBOSE_MAKEFILE-ADVANCED:INTERNAL=1\n//Details about finding PythonInterp\nFIND_PACKAGE_MESSAGE_DETAILS_PythonInterp:INTERNAL=[/usr/bin/python][v2.7.12()]\nGTEST_BOTH_LIBRARIES:INTERNAL=/usr/local/lib/libgtest.a;/usr/local/lib/libgtest_main.a\nGTEST_FOUND:INTERNAL=TRUE\n//ADVANCED property for variable: GTEST_INCLUDE_DIR\nGTEST_INCLUDE_DIR-ADVANCED:INTERNAL=1\nGTEST_INCLUDE_DIRS:INTERNAL=/usr/local/include\nGTEST_LIBRARIES:INTERNAL=/usr/local/lib/libgtest.a\n//ADVANCED property for variable: GTEST_LIBRARY\nGTEST_LIBRARY-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: GTEST_LIBRARY_DEBUG\nGTEST_LIBRARY_DEBUG-ADVANCED:INTERNAL=1\nGTEST_MAIN_LIBRARIES:INTERNAL=/usr/local/lib/libgtest_main.a\n//ADVANCED property for variable: GTEST_MAIN_LIBRARY\nGTEST_MAIN_LIBRARY-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: GTEST_MAIN_LIBRARY_DEBUG\nGTEST_MAIN_LIBRARY_DEBUG-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: PYTHON_EXECUTABLE\nPYTHON_EXECUTABLE-ADVANCED:INTERNAL=1\n//This needs to be in PYTHONPATH when 'setup.py install' is called.\n//  And it needs to match.  But setuptools won't tell us where\n// it will install things.\nPYTHON_INSTALL_DIR:INTERNAL=lib/python2.7/dist-packages\n//ADVANCED property for variable: ProcessorCount_cmd_getconf\nProcessorCount_cmd_getconf-ADVANCED:INTERNAL=1\n//ADVANCED property for variable: ProcessorCount_cmd_sysctl\nProcessorCount_cmd_sysctl-ADVANCED:INTERNAL=1\n//Components requested for this build tree.\n_Boost_COMPONENTS_SEARCHED:INTERNAL=system\n//Last used Boost_INCLUDE_DIR value.\n_Boost_INCLUDE_DIR_LAST:INTERNAL=/usr/include\n//Last used Boost_LIBRARY_DIR_DEBUG value.\n_Boost_LIBRARY_DIR_DEBUG_LAST:INTERNAL=/usr/lib/x86_64-linux-gnu\n//Last used Boost_LIBRARY_DIR_RELEASE value.\n_Boost_LIBRARY_DIR_RELEASE_LAST:INTERNAL=/usr/lib/x86_64-linux-gnu\n//Last used Boost_NAMESPACE value.\n_Boost_NAMESPACE_LAST:INTERNAL=boost\n//Last used Boost_USE_MULTITHREADED value.\n_Boost_USE_MULTITHREADED_LAST:INTERNAL=TRUE\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CMakeCCompiler.cmake",
    "content": "set(CMAKE_C_COMPILER \"/usr/bin/cc\")\nset(CMAKE_C_COMPILER_ARG1 \"\")\nset(CMAKE_C_COMPILER_ID \"GNU\")\nset(CMAKE_C_COMPILER_VERSION \"5.4.0\")\nset(CMAKE_C_COMPILER_WRAPPER \"\")\nset(CMAKE_C_STANDARD_COMPUTED_DEFAULT \"11\")\nset(CMAKE_C_COMPILE_FEATURES \"c_std_90;c_function_prototypes;c_std_99;c_restrict;c_variadic_macros;c_std_11;c_static_assert\")\nset(CMAKE_C90_COMPILE_FEATURES \"c_std_90;c_function_prototypes\")\nset(CMAKE_C99_COMPILE_FEATURES \"c_std_99;c_restrict;c_variadic_macros\")\nset(CMAKE_C11_COMPILE_FEATURES \"c_std_11;c_static_assert\")\n\nset(CMAKE_C_PLATFORM_ID \"Linux\")\nset(CMAKE_C_SIMULATE_ID \"\")\nset(CMAKE_C_SIMULATE_VERSION \"\")\n\n\nset(CMAKE_AR \"/usr/bin/ar\")\nset(CMAKE_C_COMPILER_AR \"/usr/bin/gcc-ar-5\")\nset(CMAKE_RANLIB \"/usr/bin/ranlib\")\nset(CMAKE_C_COMPILER_RANLIB \"/usr/bin/gcc-ranlib-5\")\nset(CMAKE_LINKER \"/usr/bin/ld\")\nset(CMAKE_COMPILER_IS_GNUCC 1)\nset(CMAKE_C_COMPILER_LOADED 1)\nset(CMAKE_C_COMPILER_WORKS TRUE)\nset(CMAKE_C_ABI_COMPILED TRUE)\nset(CMAKE_COMPILER_IS_MINGW )\nset(CMAKE_COMPILER_IS_CYGWIN )\nif(CMAKE_COMPILER_IS_CYGWIN)\n  set(CYGWIN 1)\n  set(UNIX 1)\nendif()\n\nset(CMAKE_C_COMPILER_ENV_VAR \"CC\")\n\nif(CMAKE_COMPILER_IS_MINGW)\n  set(MINGW 1)\nendif()\nset(CMAKE_C_COMPILER_ID_RUN 1)\nset(CMAKE_C_SOURCE_FILE_EXTENSIONS c;m)\nset(CMAKE_C_IGNORE_EXTENSIONS h;H;o;O;obj;OBJ;def;DEF;rc;RC)\nset(CMAKE_C_LINKER_PREFERENCE 10)\n\n# Save compiler ABI information.\nset(CMAKE_C_SIZEOF_DATA_PTR \"8\")\nset(CMAKE_C_COMPILER_ABI \"ELF\")\nset(CMAKE_C_LIBRARY_ARCHITECTURE \"x86_64-linux-gnu\")\n\nif(CMAKE_C_SIZEOF_DATA_PTR)\n  set(CMAKE_SIZEOF_VOID_P \"${CMAKE_C_SIZEOF_DATA_PTR}\")\nendif()\n\nif(CMAKE_C_COMPILER_ABI)\n  set(CMAKE_INTERNAL_PLATFORM_ABI \"${CMAKE_C_COMPILER_ABI}\")\nendif()\n\nif(CMAKE_C_LIBRARY_ARCHITECTURE)\n  set(CMAKE_LIBRARY_ARCHITECTURE \"x86_64-linux-gnu\")\nendif()\n\nset(CMAKE_C_CL_SHOWINCLUDES_PREFIX \"\")\nif(CMAKE_C_CL_SHOWINCLUDES_PREFIX)\n  set(CMAKE_CL_SHOWINCLUDES_PREFIX \"${CMAKE_C_CL_SHOWINCLUDES_PREFIX}\")\nendif()\n\n\n\n\n\nset(CMAKE_C_IMPLICIT_LINK_LIBRARIES \"gcc;gcc_s;c;gcc;gcc_s\")\nset(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\")\nset(CMAKE_C_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CMakeCXXCompiler.cmake",
    "content": "set(CMAKE_CXX_COMPILER \"/usr/bin/c++\")\nset(CMAKE_CXX_COMPILER_ARG1 \"\")\nset(CMAKE_CXX_COMPILER_ID \"GNU\")\nset(CMAKE_CXX_COMPILER_VERSION \"5.4.0\")\nset(CMAKE_CXX_COMPILER_WRAPPER \"\")\nset(CMAKE_CXX_STANDARD_COMPUTED_DEFAULT \"98\")\nset(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\")\nset(CMAKE_CXX98_COMPILE_FEATURES \"cxx_std_98;cxx_template_template_parameters\")\nset(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\")\nset(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\")\nset(CMAKE_CXX17_COMPILE_FEATURES \"cxx_std_17\")\n\nset(CMAKE_CXX_PLATFORM_ID \"Linux\")\nset(CMAKE_CXX_SIMULATE_ID \"\")\nset(CMAKE_CXX_SIMULATE_VERSION \"\")\n\n\nset(CMAKE_AR \"/usr/bin/ar\")\nset(CMAKE_CXX_COMPILER_AR \"/usr/bin/gcc-ar-5\")\nset(CMAKE_RANLIB \"/usr/bin/ranlib\")\nset(CMAKE_CXX_COMPILER_RANLIB \"/usr/bin/gcc-ranlib-5\")\nset(CMAKE_LINKER \"/usr/bin/ld\")\nset(CMAKE_COMPILER_IS_GNUCXX 1)\nset(CMAKE_CXX_COMPILER_LOADED 1)\nset(CMAKE_CXX_COMPILER_WORKS TRUE)\nset(CMAKE_CXX_ABI_COMPILED TRUE)\nset(CMAKE_COMPILER_IS_MINGW )\nset(CMAKE_COMPILER_IS_CYGWIN )\nif(CMAKE_COMPILER_IS_CYGWIN)\n  set(CYGWIN 1)\n  set(UNIX 1)\nendif()\n\nset(CMAKE_CXX_COMPILER_ENV_VAR \"CXX\")\n\nif(CMAKE_COMPILER_IS_MINGW)\n  set(MINGW 1)\nendif()\nset(CMAKE_CXX_COMPILER_ID_RUN 1)\nset(CMAKE_CXX_IGNORE_EXTENSIONS inl;h;hpp;HPP;H;o;O;obj;OBJ;def;DEF;rc;RC)\nset(CMAKE_CXX_SOURCE_FILE_EXTENSIONS C;M;c++;cc;cpp;cxx;mm;CPP)\nset(CMAKE_CXX_LINKER_PREFERENCE 30)\nset(CMAKE_CXX_LINKER_PREFERENCE_PROPAGATES 1)\n\n# Save compiler ABI information.\nset(CMAKE_CXX_SIZEOF_DATA_PTR \"8\")\nset(CMAKE_CXX_COMPILER_ABI \"ELF\")\nset(CMAKE_CXX_LIBRARY_ARCHITECTURE \"x86_64-linux-gnu\")\n\nif(CMAKE_CXX_SIZEOF_DATA_PTR)\n  set(CMAKE_SIZEOF_VOID_P \"${CMAKE_CXX_SIZEOF_DATA_PTR}\")\nendif()\n\nif(CMAKE_CXX_COMPILER_ABI)\n  set(CMAKE_INTERNAL_PLATFORM_ABI \"${CMAKE_CXX_COMPILER_ABI}\")\nendif()\n\nif(CMAKE_CXX_LIBRARY_ARCHITECTURE)\n  set(CMAKE_LIBRARY_ARCHITECTURE \"x86_64-linux-gnu\")\nendif()\n\nset(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX \"\")\nif(CMAKE_CXX_CL_SHOWINCLUDES_PREFIX)\n  set(CMAKE_CL_SHOWINCLUDES_PREFIX \"${CMAKE_CXX_CL_SHOWINCLUDES_PREFIX}\")\nendif()\n\n\n\n\n\nset(CMAKE_CXX_IMPLICIT_LINK_LIBRARIES \"stdc++;m;gcc_s;gcc;c;gcc_s;gcc\")\nset(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\")\nset(CMAKE_CXX_IMPLICIT_LINK_FRAMEWORK_DIRECTORIES \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CMakeSystem.cmake",
    "content": "set(CMAKE_HOST_SYSTEM \"Linux-4.13.0-38-generic\")\nset(CMAKE_HOST_SYSTEM_NAME \"Linux\")\nset(CMAKE_HOST_SYSTEM_VERSION \"4.13.0-38-generic\")\nset(CMAKE_HOST_SYSTEM_PROCESSOR \"x86_64\")\n\n\n\nset(CMAKE_SYSTEM \"Linux-4.13.0-38-generic\")\nset(CMAKE_SYSTEM_NAME \"Linux\")\nset(CMAKE_SYSTEM_VERSION \"4.13.0-38-generic\")\nset(CMAKE_SYSTEM_PROCESSOR \"x86_64\")\n\nset(CMAKE_CROSSCOMPILING \"FALSE\")\n\nset(CMAKE_SYSTEM_LOADED 1)\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CompilerIdC/CMakeCCompilerId.c",
    "content": "#ifdef __cplusplus\n# error \"A C++ compiler has been selected for C.\"\n#endif\n\n#if defined(__18CXX)\n# define ID_VOID_MAIN\n#endif\n#if defined(__CLASSIC_C__)\n/* cv-qualifiers did not exist in K&R C */\n# define const\n# define volatile\n#endif\n\n\n/* Version number components: V=Version, R=Revision, P=Patch\n   Version date components:   YYYY=Year, MM=Month,   DD=Day  */\n\n#if defined(__INTEL_COMPILER) || defined(__ICC)\n# define COMPILER_ID \"Intel\"\n# if defined(_MSC_VER)\n#  define SIMULATE_ID \"MSVC\"\n# endif\n  /* __INTEL_COMPILER = VRP */\n# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100)\n# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10)\n# if defined(__INTEL_COMPILER_UPDATE)\n#  define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE)\n# else\n#  define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER   % 10)\n# endif\n# if defined(__INTEL_COMPILER_BUILD_DATE)\n  /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */\n#  define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE)\n# endif\n# if defined(_MSC_VER)\n   /* _MSC_VER = VVRR */\n#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)\n#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)\n# endif\n\n#elif defined(__PATHCC__)\n# define COMPILER_ID \"PathScale\"\n# define COMPILER_VERSION_MAJOR DEC(__PATHCC__)\n# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__)\n# if defined(__PATHCC_PATCHLEVEL__)\n#  define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__)\n# endif\n\n#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__)\n# define COMPILER_ID \"Embarcadero\"\n# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF)\n# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF)\n# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__     & 0xFFFF)\n\n#elif defined(__BORLANDC__)\n# define COMPILER_ID \"Borland\"\n  /* __BORLANDC__ = 0xVRR */\n# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8)\n# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF)\n\n#elif defined(__WATCOMC__) && __WATCOMC__ < 1200\n# define COMPILER_ID \"Watcom\"\n   /* __WATCOMC__ = VVRR */\n# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100)\n# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)\n# if (__WATCOMC__ % 10) > 0\n#  define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)\n# endif\n\n#elif defined(__WATCOMC__)\n# define COMPILER_ID \"OpenWatcom\"\n   /* __WATCOMC__ = VVRP + 1100 */\n# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100)\n# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)\n# if (__WATCOMC__ % 10) > 0\n#  define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)\n# endif\n\n#elif defined(__SUNPRO_C)\n# define COMPILER_ID \"SunPro\"\n# if __SUNPRO_C >= 0x5100\n   /* __SUNPRO_C = 0xVRRP */\n#  define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>12)\n#  define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xFF)\n#  define COMPILER_VERSION_PATCH HEX(__SUNPRO_C    & 0xF)\n# else\n   /* __SUNPRO_CC = 0xVRP */\n#  define COMPILER_VERSION_MAJOR HEX(__SUNPRO_C>>8)\n#  define COMPILER_VERSION_MINOR HEX(__SUNPRO_C>>4 & 0xF)\n#  define COMPILER_VERSION_PATCH HEX(__SUNPRO_C    & 0xF)\n# endif\n\n#elif defined(__HP_cc)\n# define COMPILER_ID \"HP\"\n  /* __HP_cc = VVRRPP */\n# define COMPILER_VERSION_MAJOR DEC(__HP_cc/10000)\n# define COMPILER_VERSION_MINOR DEC(__HP_cc/100 % 100)\n# define COMPILER_VERSION_PATCH DEC(__HP_cc     % 100)\n\n#elif defined(__DECC)\n# define COMPILER_ID \"Compaq\"\n  /* __DECC_VER = VVRRTPPPP */\n# define COMPILER_VERSION_MAJOR DEC(__DECC_VER/10000000)\n# define COMPILER_VERSION_MINOR DEC(__DECC_VER/100000  % 100)\n# define COMPILER_VERSION_PATCH DEC(__DECC_VER         % 10000)\n\n#elif defined(__IBMC__) && defined(__COMPILER_VER__)\n# define COMPILER_ID \"zOS\"\n  /* __IBMC__ = VRP */\n# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)\n# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)\n# define COMPILER_VERSION_PATCH DEC(__IBMC__    % 10)\n\n#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ >= 800\n# define COMPILER_ID \"XL\"\n  /* __IBMC__ = VRP */\n# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)\n# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)\n# define COMPILER_VERSION_PATCH DEC(__IBMC__    % 10)\n\n#elif defined(__IBMC__) && !defined(__COMPILER_VER__) && __IBMC__ < 800\n# define COMPILER_ID \"VisualAge\"\n  /* __IBMC__ = VRP */\n# define COMPILER_VERSION_MAJOR DEC(__IBMC__/100)\n# define COMPILER_VERSION_MINOR DEC(__IBMC__/10 % 10)\n# define COMPILER_VERSION_PATCH DEC(__IBMC__    % 10)\n\n#elif defined(__PGI)\n# define COMPILER_ID \"PGI\"\n# define COMPILER_VERSION_MAJOR DEC(__PGIC__)\n# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__)\n# if defined(__PGIC_PATCHLEVEL__)\n#  define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__)\n# endif\n\n#elif defined(_CRAYC)\n# define COMPILER_ID \"Cray\"\n# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR)\n# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR)\n\n#elif defined(__TI_COMPILER_VERSION__)\n# define COMPILER_ID \"TI\"\n  /* __TI_COMPILER_VERSION__ = VVVRRRPPP */\n# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000)\n# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000   % 1000)\n# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__        % 1000)\n\n#elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version)\n# define COMPILER_ID \"Fujitsu\"\n\n#elif defined(__TINYC__)\n# define COMPILER_ID \"TinyCC\"\n\n#elif defined(__BCC__)\n# define COMPILER_ID \"Bruce\"\n\n#elif defined(__SCO_VERSION__)\n# define COMPILER_ID \"SCO\"\n\n#elif defined(__clang__) && defined(__apple_build_version__)\n# define COMPILER_ID \"AppleClang\"\n# if defined(_MSC_VER)\n#  define SIMULATE_ID \"MSVC\"\n# endif\n# define COMPILER_VERSION_MAJOR DEC(__clang_major__)\n# define COMPILER_VERSION_MINOR DEC(__clang_minor__)\n# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)\n# if defined(_MSC_VER)\n   /* _MSC_VER = VVRR */\n#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)\n#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)\n# endif\n# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__)\n\n#elif defined(__clang__)\n# define COMPILER_ID \"Clang\"\n# if defined(_MSC_VER)\n#  define SIMULATE_ID \"MSVC\"\n# endif\n# define COMPILER_VERSION_MAJOR DEC(__clang_major__)\n# define COMPILER_VERSION_MINOR DEC(__clang_minor__)\n# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)\n# if defined(_MSC_VER)\n   /* _MSC_VER = VVRR */\n#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)\n#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)\n# endif\n\n#elif defined(__GNUC__)\n# define COMPILER_ID \"GNU\"\n# define COMPILER_VERSION_MAJOR DEC(__GNUC__)\n# if defined(__GNUC_MINOR__)\n#  define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__)\n# endif\n# if defined(__GNUC_PATCHLEVEL__)\n#  define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)\n# endif\n\n#elif defined(_MSC_VER)\n# define COMPILER_ID \"MSVC\"\n  /* _MSC_VER = VVRR */\n# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100)\n# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100)\n# if defined(_MSC_FULL_VER)\n#  if _MSC_VER >= 1400\n    /* _MSC_FULL_VER = VVRRPPPPP */\n#   define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000)\n#  else\n    /* _MSC_FULL_VER = VVRRPPPP */\n#   define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000)\n#  endif\n# endif\n# if defined(_MSC_BUILD)\n#  define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD)\n# endif\n\n#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__)\n# define COMPILER_ID \"ADSP\"\n#if defined(__VISUALDSPVERSION__)\n  /* __VISUALDSPVERSION__ = 0xVVRRPP00 */\n# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24)\n# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF)\n# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8  & 0xFF)\n#endif\n\n#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC)\n# define COMPILER_ID \"IAR\"\n\n#elif defined(__ARMCC_VERSION)\n# define COMPILER_ID \"ARMCC\"\n#if __ARMCC_VERSION >= 1000000\n  /* __ARMCC_VERSION = VRRPPPP */\n  # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000)\n  # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100)\n  # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION     % 10000)\n#else\n  /* __ARMCC_VERSION = VRPPPP */\n  # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000)\n  # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10)\n  # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION    % 10000)\n#endif\n\n\n#elif defined(__SDCC_VERSION_MAJOR) || defined(SDCC)\n# define COMPILER_ID \"SDCC\"\n# if defined(__SDCC_VERSION_MAJOR)\n#  define COMPILER_VERSION_MAJOR DEC(__SDCC_VERSION_MAJOR)\n#  define COMPILER_VERSION_MINOR DEC(__SDCC_VERSION_MINOR)\n#  define COMPILER_VERSION_PATCH DEC(__SDCC_VERSION_PATCH)\n# else\n  /* SDCC = VRP */\n#  define COMPILER_VERSION_MAJOR DEC(SDCC/100)\n#  define COMPILER_VERSION_MINOR DEC(SDCC/10 % 10)\n#  define COMPILER_VERSION_PATCH DEC(SDCC    % 10)\n# endif\n\n#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION)\n# define COMPILER_ID \"MIPSpro\"\n# if defined(_SGI_COMPILER_VERSION)\n  /* _SGI_COMPILER_VERSION = VRP */\n#  define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100)\n#  define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10)\n#  define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION    % 10)\n# else\n  /* _COMPILER_VERSION = VRP */\n#  define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100)\n#  define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10)\n#  define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION    % 10)\n# endif\n\n\n/* These compilers are either not known or too old to define an\n  identification macro.  Try to identify the platform and guess that\n  it is the native compiler.  */\n#elif defined(__sgi)\n# define COMPILER_ID \"MIPSpro\"\n\n#elif defined(__hpux) || defined(__hpua)\n# define COMPILER_ID \"HP\"\n\n#else /* unknown compiler */\n# define COMPILER_ID \"\"\n#endif\n\n/* Construct the string literal in pieces to prevent the source from\n   getting matched.  Store it in a pointer rather than an array\n   because some compilers will just produce instructions to fill the\n   array rather than assigning a pointer to a static array.  */\nchar const* info_compiler = \"INFO\" \":\" \"compiler[\" COMPILER_ID \"]\";\n#ifdef SIMULATE_ID\nchar const* info_simulate = \"INFO\" \":\" \"simulate[\" SIMULATE_ID \"]\";\n#endif\n\n#ifdef __QNXNTO__\nchar const* qnxnto = \"INFO\" \":\" \"qnxnto[]\";\n#endif\n\n#if defined(__CRAYXE) || defined(__CRAYXC)\nchar const *info_cray = \"INFO\" \":\" \"compiler_wrapper[CrayPrgEnv]\";\n#endif\n\n#define STRINGIFY_HELPER(X) #X\n#define STRINGIFY(X) STRINGIFY_HELPER(X)\n\n/* Identify known platforms by name.  */\n#if defined(__linux) || defined(__linux__) || defined(linux)\n# define PLATFORM_ID \"Linux\"\n\n#elif defined(__CYGWIN__)\n# define PLATFORM_ID \"Cygwin\"\n\n#elif defined(__MINGW32__)\n# define PLATFORM_ID \"MinGW\"\n\n#elif defined(__APPLE__)\n# define PLATFORM_ID \"Darwin\"\n\n#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32)\n# define PLATFORM_ID \"Windows\"\n\n#elif defined(__FreeBSD__) || defined(__FreeBSD)\n# define PLATFORM_ID \"FreeBSD\"\n\n#elif defined(__NetBSD__) || defined(__NetBSD)\n# define PLATFORM_ID \"NetBSD\"\n\n#elif defined(__OpenBSD__) || defined(__OPENBSD)\n# define PLATFORM_ID \"OpenBSD\"\n\n#elif defined(__sun) || defined(sun)\n# define PLATFORM_ID \"SunOS\"\n\n#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__)\n# define PLATFORM_ID \"AIX\"\n\n#elif defined(__sgi) || defined(__sgi__) || defined(_SGI)\n# define PLATFORM_ID \"IRIX\"\n\n#elif defined(__hpux) || defined(__hpux__)\n# define PLATFORM_ID \"HP-UX\"\n\n#elif defined(__HAIKU__)\n# define PLATFORM_ID \"Haiku\"\n\n#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS)\n# define PLATFORM_ID \"BeOS\"\n\n#elif defined(__QNX__) || defined(__QNXNTO__)\n# define PLATFORM_ID \"QNX\"\n\n#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__)\n# define PLATFORM_ID \"Tru64\"\n\n#elif defined(__riscos) || defined(__riscos__)\n# define PLATFORM_ID \"RISCos\"\n\n#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__)\n# define PLATFORM_ID \"SINIX\"\n\n#elif defined(__UNIX_SV__)\n# define PLATFORM_ID \"UNIX_SV\"\n\n#elif defined(__bsdos__)\n# define PLATFORM_ID \"BSDOS\"\n\n#elif defined(_MPRAS) || defined(MPRAS)\n# define PLATFORM_ID \"MP-RAS\"\n\n#elif defined(__osf) || defined(__osf__)\n# define PLATFORM_ID \"OSF1\"\n\n#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv)\n# define PLATFORM_ID \"SCO_SV\"\n\n#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX)\n# define PLATFORM_ID \"ULTRIX\"\n\n#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX)\n# define PLATFORM_ID \"Xenix\"\n\n#elif defined(__WATCOMC__)\n# if defined(__LINUX__)\n#  define PLATFORM_ID \"Linux\"\n\n# elif defined(__DOS__)\n#  define PLATFORM_ID \"DOS\"\n\n# elif defined(__OS2__)\n#  define PLATFORM_ID \"OS2\"\n\n# elif defined(__WINDOWS__)\n#  define PLATFORM_ID \"Windows3x\"\n\n# else /* unknown platform */\n#  define PLATFORM_ID\n# endif\n\n#else /* unknown platform */\n# define PLATFORM_ID\n\n#endif\n\n/* For windows compilers MSVC and Intel we can determine\n   the architecture of the compiler being used.  This is because\n   the compilers do not have flags that can change the architecture,\n   but rather depend on which compiler is being used\n*/\n#if defined(_WIN32) && defined(_MSC_VER)\n# if defined(_M_IA64)\n#  define ARCHITECTURE_ID \"IA64\"\n\n# elif defined(_M_X64) || defined(_M_AMD64)\n#  define ARCHITECTURE_ID \"x64\"\n\n# elif defined(_M_IX86)\n#  define ARCHITECTURE_ID \"X86\"\n\n# elif defined(_M_ARM)\n#  if _M_ARM == 4\n#   define ARCHITECTURE_ID \"ARMV4I\"\n#  elif _M_ARM == 5\n#   define ARCHITECTURE_ID \"ARMV5I\"\n#  else\n#   define ARCHITECTURE_ID \"ARMV\" STRINGIFY(_M_ARM)\n#  endif\n\n# elif defined(_M_MIPS)\n#  define ARCHITECTURE_ID \"MIPS\"\n\n# elif defined(_M_SH)\n#  define ARCHITECTURE_ID \"SHx\"\n\n# else /* unknown architecture */\n#  define ARCHITECTURE_ID \"\"\n# endif\n\n#elif defined(__WATCOMC__)\n# if defined(_M_I86)\n#  define ARCHITECTURE_ID \"I86\"\n\n# elif defined(_M_IX86)\n#  define ARCHITECTURE_ID \"X86\"\n\n# else /* unknown architecture */\n#  define ARCHITECTURE_ID \"\"\n# endif\n\n#else\n#  define ARCHITECTURE_ID\n#endif\n\n/* Convert integer to decimal digit literals.  */\n#define DEC(n)                   \\\n  ('0' + (((n) / 10000000)%10)), \\\n  ('0' + (((n) / 1000000)%10)),  \\\n  ('0' + (((n) / 100000)%10)),   \\\n  ('0' + (((n) / 10000)%10)),    \\\n  ('0' + (((n) / 1000)%10)),     \\\n  ('0' + (((n) / 100)%10)),      \\\n  ('0' + (((n) / 10)%10)),       \\\n  ('0' +  ((n) % 10))\n\n/* Convert integer to hex digit literals.  */\n#define HEX(n)             \\\n  ('0' + ((n)>>28 & 0xF)), \\\n  ('0' + ((n)>>24 & 0xF)), \\\n  ('0' + ((n)>>20 & 0xF)), \\\n  ('0' + ((n)>>16 & 0xF)), \\\n  ('0' + ((n)>>12 & 0xF)), \\\n  ('0' + ((n)>>8  & 0xF)), \\\n  ('0' + ((n)>>4  & 0xF)), \\\n  ('0' + ((n)     & 0xF))\n\n/* Construct a string literal encoding the version number components. */\n#ifdef COMPILER_VERSION_MAJOR\nchar const info_version[] = {\n  'I', 'N', 'F', 'O', ':',\n  'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[',\n  COMPILER_VERSION_MAJOR,\n# ifdef COMPILER_VERSION_MINOR\n  '.', COMPILER_VERSION_MINOR,\n#  ifdef COMPILER_VERSION_PATCH\n   '.', COMPILER_VERSION_PATCH,\n#   ifdef COMPILER_VERSION_TWEAK\n    '.', COMPILER_VERSION_TWEAK,\n#   endif\n#  endif\n# endif\n  ']','\\0'};\n#endif\n\n/* Construct a string literal encoding the version number components. */\n#ifdef SIMULATE_VERSION_MAJOR\nchar const info_simulate_version[] = {\n  'I', 'N', 'F', 'O', ':',\n  's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[',\n  SIMULATE_VERSION_MAJOR,\n# ifdef SIMULATE_VERSION_MINOR\n  '.', SIMULATE_VERSION_MINOR,\n#  ifdef SIMULATE_VERSION_PATCH\n   '.', SIMULATE_VERSION_PATCH,\n#   ifdef SIMULATE_VERSION_TWEAK\n    '.', SIMULATE_VERSION_TWEAK,\n#   endif\n#  endif\n# endif\n  ']','\\0'};\n#endif\n\n/* Construct the string literal in pieces to prevent the source from\n   getting matched.  Store it in a pointer rather than an array\n   because some compilers will just produce instructions to fill the\n   array rather than assigning a pointer to a static array.  */\nchar const* info_platform = \"INFO\" \":\" \"platform[\" PLATFORM_ID \"]\";\nchar const* info_arch = \"INFO\" \":\" \"arch[\" ARCHITECTURE_ID \"]\";\n\n\n\n\n#if !defined(__STDC__)\n# if defined(_MSC_VER) && !defined(__clang__)\n#  define C_DIALECT \"90\"\n# else\n#  define C_DIALECT\n# endif\n#elif __STDC_VERSION__ >= 201000L\n# define C_DIALECT \"11\"\n#elif __STDC_VERSION__ >= 199901L\n# define C_DIALECT \"99\"\n#else\n# define C_DIALECT \"90\"\n#endif\nconst char* info_language_dialect_default =\n  \"INFO\" \":\" \"dialect_default[\" C_DIALECT \"]\";\n\n/*--------------------------------------------------------------------------*/\n\n#ifdef ID_VOID_MAIN\nvoid main() {}\n#else\n# if defined(__CLASSIC_C__)\nint main(argc, argv) int argc; char *argv[];\n# else\nint main(int argc, char* argv[])\n# endif\n{\n  int require = 0;\n  require += info_compiler[argc];\n  require += info_platform[argc];\n  require += info_arch[argc];\n#ifdef COMPILER_VERSION_MAJOR\n  require += info_version[argc];\n#endif\n#ifdef SIMULATE_ID\n  require += info_simulate[argc];\n#endif\n#ifdef SIMULATE_VERSION_MAJOR\n  require += info_simulate_version[argc];\n#endif\n#if defined(__CRAYXE) || defined(__CRAYXC)\n  require += info_cray[argc];\n#endif\n  require += info_language_dialect_default[argc];\n  (void)argv;\n  return require;\n}\n#endif\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CompilerIdCXX/CMakeCXXCompilerId.cpp",
    "content": "/* This source file must have a .cpp extension so that all C++ compilers\n   recognize the extension without flags.  Borland does not know .cxx for\n   example.  */\n#ifndef __cplusplus\n# error \"A C compiler has been selected for C++.\"\n#endif\n\n\n/* Version number components: V=Version, R=Revision, P=Patch\n   Version date components:   YYYY=Year, MM=Month,   DD=Day  */\n\n#if defined(__COMO__)\n# define COMPILER_ID \"Comeau\"\n  /* __COMO_VERSION__ = VRR */\n# define COMPILER_VERSION_MAJOR DEC(__COMO_VERSION__ / 100)\n# define COMPILER_VERSION_MINOR DEC(__COMO_VERSION__ % 100)\n\n#elif defined(__INTEL_COMPILER) || defined(__ICC)\n# define COMPILER_ID \"Intel\"\n# if defined(_MSC_VER)\n#  define SIMULATE_ID \"MSVC\"\n# endif\n  /* __INTEL_COMPILER = VRP */\n# define COMPILER_VERSION_MAJOR DEC(__INTEL_COMPILER/100)\n# define COMPILER_VERSION_MINOR DEC(__INTEL_COMPILER/10 % 10)\n# if defined(__INTEL_COMPILER_UPDATE)\n#  define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER_UPDATE)\n# else\n#  define COMPILER_VERSION_PATCH DEC(__INTEL_COMPILER   % 10)\n# endif\n# if defined(__INTEL_COMPILER_BUILD_DATE)\n  /* __INTEL_COMPILER_BUILD_DATE = YYYYMMDD */\n#  define COMPILER_VERSION_TWEAK DEC(__INTEL_COMPILER_BUILD_DATE)\n# endif\n# if defined(_MSC_VER)\n   /* _MSC_VER = VVRR */\n#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)\n#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)\n# endif\n\n#elif defined(__PATHCC__)\n# define COMPILER_ID \"PathScale\"\n# define COMPILER_VERSION_MAJOR DEC(__PATHCC__)\n# define COMPILER_VERSION_MINOR DEC(__PATHCC_MINOR__)\n# if defined(__PATHCC_PATCHLEVEL__)\n#  define COMPILER_VERSION_PATCH DEC(__PATHCC_PATCHLEVEL__)\n# endif\n\n#elif defined(__BORLANDC__) && defined(__CODEGEARC_VERSION__)\n# define COMPILER_ID \"Embarcadero\"\n# define COMPILER_VERSION_MAJOR HEX(__CODEGEARC_VERSION__>>24 & 0x00FF)\n# define COMPILER_VERSION_MINOR HEX(__CODEGEARC_VERSION__>>16 & 0x00FF)\n# define COMPILER_VERSION_PATCH DEC(__CODEGEARC_VERSION__     & 0xFFFF)\n\n#elif defined(__BORLANDC__)\n# define COMPILER_ID \"Borland\"\n  /* __BORLANDC__ = 0xVRR */\n# define COMPILER_VERSION_MAJOR HEX(__BORLANDC__>>8)\n# define COMPILER_VERSION_MINOR HEX(__BORLANDC__ & 0xFF)\n\n#elif defined(__WATCOMC__) && __WATCOMC__ < 1200\n# define COMPILER_ID \"Watcom\"\n   /* __WATCOMC__ = VVRR */\n# define COMPILER_VERSION_MAJOR DEC(__WATCOMC__ / 100)\n# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)\n# if (__WATCOMC__ % 10) > 0\n#  define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)\n# endif\n\n#elif defined(__WATCOMC__)\n# define COMPILER_ID \"OpenWatcom\"\n   /* __WATCOMC__ = VVRP + 1100 */\n# define COMPILER_VERSION_MAJOR DEC((__WATCOMC__ - 1100) / 100)\n# define COMPILER_VERSION_MINOR DEC((__WATCOMC__ / 10) % 10)\n# if (__WATCOMC__ % 10) > 0\n#  define COMPILER_VERSION_PATCH DEC(__WATCOMC__ % 10)\n# endif\n\n#elif defined(__SUNPRO_CC)\n# define COMPILER_ID \"SunPro\"\n# if __SUNPRO_CC >= 0x5100\n   /* __SUNPRO_CC = 0xVRRP */\n#  define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>12)\n#  define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xFF)\n#  define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC    & 0xF)\n# else\n   /* __SUNPRO_CC = 0xVRP */\n#  define COMPILER_VERSION_MAJOR HEX(__SUNPRO_CC>>8)\n#  define COMPILER_VERSION_MINOR HEX(__SUNPRO_CC>>4 & 0xF)\n#  define COMPILER_VERSION_PATCH HEX(__SUNPRO_CC    & 0xF)\n# endif\n\n#elif defined(__HP_aCC)\n# define COMPILER_ID \"HP\"\n  /* __HP_aCC = VVRRPP */\n# define COMPILER_VERSION_MAJOR DEC(__HP_aCC/10000)\n# define COMPILER_VERSION_MINOR DEC(__HP_aCC/100 % 100)\n# define COMPILER_VERSION_PATCH DEC(__HP_aCC     % 100)\n\n#elif defined(__DECCXX)\n# define COMPILER_ID \"Compaq\"\n  /* __DECCXX_VER = VVRRTPPPP */\n# define COMPILER_VERSION_MAJOR DEC(__DECCXX_VER/10000000)\n# define COMPILER_VERSION_MINOR DEC(__DECCXX_VER/100000  % 100)\n# define COMPILER_VERSION_PATCH DEC(__DECCXX_VER         % 10000)\n\n#elif defined(__IBMCPP__) && defined(__COMPILER_VER__)\n# define COMPILER_ID \"zOS\"\n  /* __IBMCPP__ = VRP */\n# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)\n# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)\n# define COMPILER_VERSION_PATCH DEC(__IBMCPP__    % 10)\n\n#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ >= 800\n# define COMPILER_ID \"XL\"\n  /* __IBMCPP__ = VRP */\n# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)\n# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)\n# define COMPILER_VERSION_PATCH DEC(__IBMCPP__    % 10)\n\n#elif defined(__IBMCPP__) && !defined(__COMPILER_VER__) && __IBMCPP__ < 800\n# define COMPILER_ID \"VisualAge\"\n  /* __IBMCPP__ = VRP */\n# define COMPILER_VERSION_MAJOR DEC(__IBMCPP__/100)\n# define COMPILER_VERSION_MINOR DEC(__IBMCPP__/10 % 10)\n# define COMPILER_VERSION_PATCH DEC(__IBMCPP__    % 10)\n\n#elif defined(__PGI)\n# define COMPILER_ID \"PGI\"\n# define COMPILER_VERSION_MAJOR DEC(__PGIC__)\n# define COMPILER_VERSION_MINOR DEC(__PGIC_MINOR__)\n# if defined(__PGIC_PATCHLEVEL__)\n#  define COMPILER_VERSION_PATCH DEC(__PGIC_PATCHLEVEL__)\n# endif\n\n#elif defined(_CRAYC)\n# define COMPILER_ID \"Cray\"\n# define COMPILER_VERSION_MAJOR DEC(_RELEASE_MAJOR)\n# define COMPILER_VERSION_MINOR DEC(_RELEASE_MINOR)\n\n#elif defined(__TI_COMPILER_VERSION__)\n# define COMPILER_ID \"TI\"\n  /* __TI_COMPILER_VERSION__ = VVVRRRPPP */\n# define COMPILER_VERSION_MAJOR DEC(__TI_COMPILER_VERSION__/1000000)\n# define COMPILER_VERSION_MINOR DEC(__TI_COMPILER_VERSION__/1000   % 1000)\n# define COMPILER_VERSION_PATCH DEC(__TI_COMPILER_VERSION__        % 1000)\n\n#elif defined(__FUJITSU) || defined(__FCC_VERSION) || defined(__fcc_version)\n# define COMPILER_ID \"Fujitsu\"\n\n#elif defined(__SCO_VERSION__)\n# define COMPILER_ID \"SCO\"\n\n#elif defined(__clang__) && defined(__apple_build_version__)\n# define COMPILER_ID \"AppleClang\"\n# if defined(_MSC_VER)\n#  define SIMULATE_ID \"MSVC\"\n# endif\n# define COMPILER_VERSION_MAJOR DEC(__clang_major__)\n# define COMPILER_VERSION_MINOR DEC(__clang_minor__)\n# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)\n# if defined(_MSC_VER)\n   /* _MSC_VER = VVRR */\n#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)\n#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)\n# endif\n# define COMPILER_VERSION_TWEAK DEC(__apple_build_version__)\n\n#elif defined(__clang__)\n# define COMPILER_ID \"Clang\"\n# if defined(_MSC_VER)\n#  define SIMULATE_ID \"MSVC\"\n# endif\n# define COMPILER_VERSION_MAJOR DEC(__clang_major__)\n# define COMPILER_VERSION_MINOR DEC(__clang_minor__)\n# define COMPILER_VERSION_PATCH DEC(__clang_patchlevel__)\n# if defined(_MSC_VER)\n   /* _MSC_VER = VVRR */\n#  define SIMULATE_VERSION_MAJOR DEC(_MSC_VER / 100)\n#  define SIMULATE_VERSION_MINOR DEC(_MSC_VER % 100)\n# endif\n\n#elif defined(__GNUC__) || defined(__GNUG__)\n# define COMPILER_ID \"GNU\"\n# if defined(__GNUC__)\n#  define COMPILER_VERSION_MAJOR DEC(__GNUC__)\n# else\n#  define COMPILER_VERSION_MAJOR DEC(__GNUG__)\n# endif\n# if defined(__GNUC_MINOR__)\n#  define COMPILER_VERSION_MINOR DEC(__GNUC_MINOR__)\n# endif\n# if defined(__GNUC_PATCHLEVEL__)\n#  define COMPILER_VERSION_PATCH DEC(__GNUC_PATCHLEVEL__)\n# endif\n\n#elif defined(_MSC_VER)\n# define COMPILER_ID \"MSVC\"\n  /* _MSC_VER = VVRR */\n# define COMPILER_VERSION_MAJOR DEC(_MSC_VER / 100)\n# define COMPILER_VERSION_MINOR DEC(_MSC_VER % 100)\n# if defined(_MSC_FULL_VER)\n#  if _MSC_VER >= 1400\n    /* _MSC_FULL_VER = VVRRPPPPP */\n#   define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 100000)\n#  else\n    /* _MSC_FULL_VER = VVRRPPPP */\n#   define COMPILER_VERSION_PATCH DEC(_MSC_FULL_VER % 10000)\n#  endif\n# endif\n# if defined(_MSC_BUILD)\n#  define COMPILER_VERSION_TWEAK DEC(_MSC_BUILD)\n# endif\n\n#elif defined(__VISUALDSPVERSION__) || defined(__ADSPBLACKFIN__) || defined(__ADSPTS__) || defined(__ADSP21000__)\n# define COMPILER_ID \"ADSP\"\n#if defined(__VISUALDSPVERSION__)\n  /* __VISUALDSPVERSION__ = 0xVVRRPP00 */\n# define COMPILER_VERSION_MAJOR HEX(__VISUALDSPVERSION__>>24)\n# define COMPILER_VERSION_MINOR HEX(__VISUALDSPVERSION__>>16 & 0xFF)\n# define COMPILER_VERSION_PATCH HEX(__VISUALDSPVERSION__>>8  & 0xFF)\n#endif\n\n#elif defined(__IAR_SYSTEMS_ICC__ ) || defined(__IAR_SYSTEMS_ICC)\n# define COMPILER_ID \"IAR\"\n\n#elif defined(__ARMCC_VERSION)\n# define COMPILER_ID \"ARMCC\"\n#if __ARMCC_VERSION >= 1000000\n  /* __ARMCC_VERSION = VRRPPPP */\n  # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/1000000)\n  # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 100)\n  # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION     % 10000)\n#else\n  /* __ARMCC_VERSION = VRPPPP */\n  # define COMPILER_VERSION_MAJOR DEC(__ARMCC_VERSION/100000)\n  # define COMPILER_VERSION_MINOR DEC(__ARMCC_VERSION/10000 % 10)\n  # define COMPILER_VERSION_PATCH DEC(__ARMCC_VERSION    % 10000)\n#endif\n\n\n#elif defined(_SGI_COMPILER_VERSION) || defined(_COMPILER_VERSION)\n# define COMPILER_ID \"MIPSpro\"\n# if defined(_SGI_COMPILER_VERSION)\n  /* _SGI_COMPILER_VERSION = VRP */\n#  define COMPILER_VERSION_MAJOR DEC(_SGI_COMPILER_VERSION/100)\n#  define COMPILER_VERSION_MINOR DEC(_SGI_COMPILER_VERSION/10 % 10)\n#  define COMPILER_VERSION_PATCH DEC(_SGI_COMPILER_VERSION    % 10)\n# else\n  /* _COMPILER_VERSION = VRP */\n#  define COMPILER_VERSION_MAJOR DEC(_COMPILER_VERSION/100)\n#  define COMPILER_VERSION_MINOR DEC(_COMPILER_VERSION/10 % 10)\n#  define COMPILER_VERSION_PATCH DEC(_COMPILER_VERSION    % 10)\n# endif\n\n\n/* These compilers are either not known or too old to define an\n  identification macro.  Try to identify the platform and guess that\n  it is the native compiler.  */\n#elif defined(__sgi)\n# define COMPILER_ID \"MIPSpro\"\n\n#elif defined(__hpux) || defined(__hpua)\n# define COMPILER_ID \"HP\"\n\n#else /* unknown compiler */\n# define COMPILER_ID \"\"\n#endif\n\n/* Construct the string literal in pieces to prevent the source from\n   getting matched.  Store it in a pointer rather than an array\n   because some compilers will just produce instructions to fill the\n   array rather than assigning a pointer to a static array.  */\nchar const* info_compiler = \"INFO\" \":\" \"compiler[\" COMPILER_ID \"]\";\n#ifdef SIMULATE_ID\nchar const* info_simulate = \"INFO\" \":\" \"simulate[\" SIMULATE_ID \"]\";\n#endif\n\n#ifdef __QNXNTO__\nchar const* qnxnto = \"INFO\" \":\" \"qnxnto[]\";\n#endif\n\n#if defined(__CRAYXE) || defined(__CRAYXC)\nchar const *info_cray = \"INFO\" \":\" \"compiler_wrapper[CrayPrgEnv]\";\n#endif\n\n#define STRINGIFY_HELPER(X) #X\n#define STRINGIFY(X) STRINGIFY_HELPER(X)\n\n/* Identify known platforms by name.  */\n#if defined(__linux) || defined(__linux__) || defined(linux)\n# define PLATFORM_ID \"Linux\"\n\n#elif defined(__CYGWIN__)\n# define PLATFORM_ID \"Cygwin\"\n\n#elif defined(__MINGW32__)\n# define PLATFORM_ID \"MinGW\"\n\n#elif defined(__APPLE__)\n# define PLATFORM_ID \"Darwin\"\n\n#elif defined(_WIN32) || defined(__WIN32__) || defined(WIN32)\n# define PLATFORM_ID \"Windows\"\n\n#elif defined(__FreeBSD__) || defined(__FreeBSD)\n# define PLATFORM_ID \"FreeBSD\"\n\n#elif defined(__NetBSD__) || defined(__NetBSD)\n# define PLATFORM_ID \"NetBSD\"\n\n#elif defined(__OpenBSD__) || defined(__OPENBSD)\n# define PLATFORM_ID \"OpenBSD\"\n\n#elif defined(__sun) || defined(sun)\n# define PLATFORM_ID \"SunOS\"\n\n#elif defined(_AIX) || defined(__AIX) || defined(__AIX__) || defined(__aix) || defined(__aix__)\n# define PLATFORM_ID \"AIX\"\n\n#elif defined(__sgi) || defined(__sgi__) || defined(_SGI)\n# define PLATFORM_ID \"IRIX\"\n\n#elif defined(__hpux) || defined(__hpux__)\n# define PLATFORM_ID \"HP-UX\"\n\n#elif defined(__HAIKU__)\n# define PLATFORM_ID \"Haiku\"\n\n#elif defined(__BeOS) || defined(__BEOS__) || defined(_BEOS)\n# define PLATFORM_ID \"BeOS\"\n\n#elif defined(__QNX__) || defined(__QNXNTO__)\n# define PLATFORM_ID \"QNX\"\n\n#elif defined(__tru64) || defined(_tru64) || defined(__TRU64__)\n# define PLATFORM_ID \"Tru64\"\n\n#elif defined(__riscos) || defined(__riscos__)\n# define PLATFORM_ID \"RISCos\"\n\n#elif defined(__sinix) || defined(__sinix__) || defined(__SINIX__)\n# define PLATFORM_ID \"SINIX\"\n\n#elif defined(__UNIX_SV__)\n# define PLATFORM_ID \"UNIX_SV\"\n\n#elif defined(__bsdos__)\n# define PLATFORM_ID \"BSDOS\"\n\n#elif defined(_MPRAS) || defined(MPRAS)\n# define PLATFORM_ID \"MP-RAS\"\n\n#elif defined(__osf) || defined(__osf__)\n# define PLATFORM_ID \"OSF1\"\n\n#elif defined(_SCO_SV) || defined(SCO_SV) || defined(sco_sv)\n# define PLATFORM_ID \"SCO_SV\"\n\n#elif defined(__ultrix) || defined(__ultrix__) || defined(_ULTRIX)\n# define PLATFORM_ID \"ULTRIX\"\n\n#elif defined(__XENIX__) || defined(_XENIX) || defined(XENIX)\n# define PLATFORM_ID \"Xenix\"\n\n#elif defined(__WATCOMC__)\n# if defined(__LINUX__)\n#  define PLATFORM_ID \"Linux\"\n\n# elif defined(__DOS__)\n#  define PLATFORM_ID \"DOS\"\n\n# elif defined(__OS2__)\n#  define PLATFORM_ID \"OS2\"\n\n# elif defined(__WINDOWS__)\n#  define PLATFORM_ID \"Windows3x\"\n\n# else /* unknown platform */\n#  define PLATFORM_ID\n# endif\n\n#else /* unknown platform */\n# define PLATFORM_ID\n\n#endif\n\n/* For windows compilers MSVC and Intel we can determine\n   the architecture of the compiler being used.  This is because\n   the compilers do not have flags that can change the architecture,\n   but rather depend on which compiler is being used\n*/\n#if defined(_WIN32) && defined(_MSC_VER)\n# if defined(_M_IA64)\n#  define ARCHITECTURE_ID \"IA64\"\n\n# elif defined(_M_X64) || defined(_M_AMD64)\n#  define ARCHITECTURE_ID \"x64\"\n\n# elif defined(_M_IX86)\n#  define ARCHITECTURE_ID \"X86\"\n\n# elif defined(_M_ARM)\n#  if _M_ARM == 4\n#   define ARCHITECTURE_ID \"ARMV4I\"\n#  elif _M_ARM == 5\n#   define ARCHITECTURE_ID \"ARMV5I\"\n#  else\n#   define ARCHITECTURE_ID \"ARMV\" STRINGIFY(_M_ARM)\n#  endif\n\n# elif defined(_M_MIPS)\n#  define ARCHITECTURE_ID \"MIPS\"\n\n# elif defined(_M_SH)\n#  define ARCHITECTURE_ID \"SHx\"\n\n# else /* unknown architecture */\n#  define ARCHITECTURE_ID \"\"\n# endif\n\n#elif defined(__WATCOMC__)\n# if defined(_M_I86)\n#  define ARCHITECTURE_ID \"I86\"\n\n# elif defined(_M_IX86)\n#  define ARCHITECTURE_ID \"X86\"\n\n# else /* unknown architecture */\n#  define ARCHITECTURE_ID \"\"\n# endif\n\n#else\n#  define ARCHITECTURE_ID\n#endif\n\n/* Convert integer to decimal digit literals.  */\n#define DEC(n)                   \\\n  ('0' + (((n) / 10000000)%10)), \\\n  ('0' + (((n) / 1000000)%10)),  \\\n  ('0' + (((n) / 100000)%10)),   \\\n  ('0' + (((n) / 10000)%10)),    \\\n  ('0' + (((n) / 1000)%10)),     \\\n  ('0' + (((n) / 100)%10)),      \\\n  ('0' + (((n) / 10)%10)),       \\\n  ('0' +  ((n) % 10))\n\n/* Convert integer to hex digit literals.  */\n#define HEX(n)             \\\n  ('0' + ((n)>>28 & 0xF)), \\\n  ('0' + ((n)>>24 & 0xF)), \\\n  ('0' + ((n)>>20 & 0xF)), \\\n  ('0' + ((n)>>16 & 0xF)), \\\n  ('0' + ((n)>>12 & 0xF)), \\\n  ('0' + ((n)>>8  & 0xF)), \\\n  ('0' + ((n)>>4  & 0xF)), \\\n  ('0' + ((n)     & 0xF))\n\n/* Construct a string literal encoding the version number components. */\n#ifdef COMPILER_VERSION_MAJOR\nchar const info_version[] = {\n  'I', 'N', 'F', 'O', ':',\n  'c','o','m','p','i','l','e','r','_','v','e','r','s','i','o','n','[',\n  COMPILER_VERSION_MAJOR,\n# ifdef COMPILER_VERSION_MINOR\n  '.', COMPILER_VERSION_MINOR,\n#  ifdef COMPILER_VERSION_PATCH\n   '.', COMPILER_VERSION_PATCH,\n#   ifdef COMPILER_VERSION_TWEAK\n    '.', COMPILER_VERSION_TWEAK,\n#   endif\n#  endif\n# endif\n  ']','\\0'};\n#endif\n\n/* Construct a string literal encoding the version number components. */\n#ifdef SIMULATE_VERSION_MAJOR\nchar const info_simulate_version[] = {\n  'I', 'N', 'F', 'O', ':',\n  's','i','m','u','l','a','t','e','_','v','e','r','s','i','o','n','[',\n  SIMULATE_VERSION_MAJOR,\n# ifdef SIMULATE_VERSION_MINOR\n  '.', SIMULATE_VERSION_MINOR,\n#  ifdef SIMULATE_VERSION_PATCH\n   '.', SIMULATE_VERSION_PATCH,\n#   ifdef SIMULATE_VERSION_TWEAK\n    '.', SIMULATE_VERSION_TWEAK,\n#   endif\n#  endif\n# endif\n  ']','\\0'};\n#endif\n\n/* Construct the string literal in pieces to prevent the source from\n   getting matched.  Store it in a pointer rather than an array\n   because some compilers will just produce instructions to fill the\n   array rather than assigning a pointer to a static array.  */\nchar const* info_platform = \"INFO\" \":\" \"platform[\" PLATFORM_ID \"]\";\nchar const* info_arch = \"INFO\" \":\" \"arch[\" ARCHITECTURE_ID \"]\";\n\n\n\n\nconst char* info_language_dialect_default = \"INFO\" \":\" \"dialect_default[\"\n#if __cplusplus > 201402L\n  \"17\"\n#elif __cplusplus >= 201402L\n  \"14\"\n#elif __cplusplus >= 201103L\n  \"11\"\n#else\n  \"98\"\n#endif\n\"]\";\n\n/*--------------------------------------------------------------------------*/\n\nint main(int argc, char* argv[])\n{\n  int require = 0;\n  require += info_compiler[argc];\n  require += info_platform[argc];\n#ifdef COMPILER_VERSION_MAJOR\n  require += info_version[argc];\n#endif\n#ifdef SIMULATE_ID\n  require += info_simulate[argc];\n#endif\n#ifdef SIMULATE_VERSION_MAJOR\n  require += info_simulate_version[argc];\n#endif\n#if defined(__CRAYXE) || defined(__CRAYXC)\n  require += info_cray[argc];\n#endif\n  require += info_language_dialect_default[argc];\n  (void)argv;\n  return require;\n}\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeDirectoryInformation.cmake",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Relative path conversion top directories.\nset(CMAKE_RELATIVE_PATH_TOP_SOURCE \"/home/zn/racecar/src/rf2o_laser_odometry\")\nset(CMAKE_RELATIVE_PATH_TOP_BINARY \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\")\n\n# Force unix paths in dependencies.\nset(CMAKE_FORCE_UNIX_PATHS 1)\n\n\n# The C and CXX include file regular expressions for this directory.\nset(CMAKE_C_INCLUDE_REGEX_SCAN \"^.*$\")\nset(CMAKE_C_INCLUDE_REGEX_COMPLAIN \"^$\")\nset(CMAKE_CXX_INCLUDE_REGEX_SCAN ${CMAKE_C_INCLUDE_REGEX_SCAN})\nset(CMAKE_CXX_INCLUDE_REGEX_COMPLAIN ${CMAKE_C_INCLUDE_REGEX_COMPLAIN})\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeError.log",
    "content": "Determining if the pthread_create exist failed with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_a87d6/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_a87d6.dir/build.make CMakeFiles/cmTC_a87d6.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_a87d6.dir/CheckSymbolExists.c.o\n/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\nLinking C executable cmTC_a87d6\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_a87d6.dir/link.txt --verbose=1\n/usr/bin/cc      -rdynamic CMakeFiles/cmTC_a87d6.dir/CheckSymbolExists.c.o  -o cmTC_a87d6 \nCMakeFiles/cmTC_a87d6.dir/CheckSymbolExists.c.o: In function `main':\nCheckSymbolExists.c:(.text+0x16): undefined reference to `pthread_create'\ncollect2: error: ld returned 1 exit status\nCMakeFiles/cmTC_a87d6.dir/build.make:97: recipe for target 'cmTC_a87d6' failed\nmake[1]: *** [cmTC_a87d6] Error 1\nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nMakefile:126: recipe for target 'cmTC_a87d6/fast' failed\nmake: *** [cmTC_a87d6/fast] Error 2\n\nFile /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp/CheckSymbolExists.c:\n/* */\n#include <pthread.h>\n\nint main(int argc, char** argv)\n{\n  (void)argv;\n#ifndef pthread_create\n  return ((int*)(&pthread_create))[argc];\n#else\n  (void)argc;\n  return 0;\n#endif\n}\n\nDetermining if the function pthread_create exists in the pthreads failed with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_20b42/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_20b42.dir/build.make CMakeFiles/cmTC_20b42.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_20b42.dir/CheckFunctionExists.c.o\n/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\nLinking C executable cmTC_20b42\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_20b42.dir/link.txt --verbose=1\n/usr/bin/cc  -DCHECK_FUNCTION_EXISTS=pthread_create    -rdynamic CMakeFiles/cmTC_20b42.dir/CheckFunctionExists.c.o  -o cmTC_20b42 -lpthreads \n/usr/bin/ld: cannot find -lpthreads\ncollect2: error: ld returned 1 exit status\nCMakeFiles/cmTC_20b42.dir/build.make:97: recipe for target 'cmTC_20b42' failed\nmake[1]: *** [cmTC_20b42] Error 1\nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nMakefile:126: recipe for target 'cmTC_20b42/fast' failed\nmake: *** [cmTC_20b42/fast] Error 2\n\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeOutput.log",
    "content": "The system is: Linux - 4.13.0-38-generic - x86_64\nCompiling the C compiler identification source file \"CMakeCCompilerId.c\" succeeded.\nCompiler: /usr/bin/cc \nBuild flags: \nId flags:  \n\nThe output was:\n0\n\n\nCompilation of the C compiler identification source \"CMakeCCompilerId.c\" produced \"a.out\"\n\nThe C compiler identification is GNU, found in \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CompilerIdC/a.out\"\n\nCompiling the CXX compiler identification source file \"CMakeCXXCompilerId.cpp\" succeeded.\nCompiler: /usr/bin/c++ \nBuild flags: \nId flags:  \n\nThe output was:\n0\n\n\nCompilation of the CXX compiler identification source \"CMakeCXXCompilerId.cpp\" produced \"a.out\"\n\nThe CXX compiler identification is GNU, found in \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/3.9.6/CompilerIdCXX/a.out\"\n\nDetermining if the C compiler works passed with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_e13f3/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_e13f3.dir/build.make CMakeFiles/cmTC_e13f3.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_e13f3.dir/testCCompiler.c.o\n/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\nLinking C executable cmTC_e13f3\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_e13f3.dir/link.txt --verbose=1\n/usr/bin/cc      -rdynamic CMakeFiles/cmTC_e13f3.dir/testCCompiler.c.o  -o cmTC_e13f3 \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\nDetecting C compiler ABI info compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_1b6e6/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_1b6e6.dir/build.make CMakeFiles/cmTC_1b6e6.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o\n/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\nLinking C executable cmTC_1b6e6\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_1b6e6.dir/link.txt --verbose=1\n/usr/bin/cc     -v -rdynamic CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o  -o cmTC_1b6e6 \nUsing built-in specs.\nCOLLECT_GCC=/usr/bin/cc\nCOLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper\nTarget: x86_64-linux-gnu\nConfigured 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\nThread model: posix\ngcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.9) \nCOMPILER_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/\nLIBRARY_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/\nCOLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_1b6e6' '-mtune=generic' '-march=x86-64'\n /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\nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\nParsed C implicit link information from above output:\n  link line regex: [^( *|.*[/\\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\\]+-)?ld|collect2)[^/\\]*( |$)]\n  ignore line: [Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp]\n  ignore line: []\n  ignore line: [Run Build Command:\"/usr/bin/make\" \"cmTC_1b6e6/fast\"]\n  ignore line: [/usr/bin/make -f CMakeFiles/cmTC_1b6e6.dir/build.make CMakeFiles/cmTC_1b6e6.dir/build]\n  ignore line: [make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp']\n  ignore line: [Building C object CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o]\n  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]\n  ignore line: [Linking C executable cmTC_1b6e6]\n  ignore line: [/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_1b6e6.dir/link.txt --verbose=1]\n  ignore line: [/usr/bin/cc     -v -rdynamic CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o  -o cmTC_1b6e6 ]\n  ignore line: [Using built-in specs.]\n  ignore line: [COLLECT_GCC=/usr/bin/cc]\n  ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper]\n  ignore line: [Target: x86_64-linux-gnu]\n  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]\n  ignore line: [Thread model: posix]\n  ignore line: [gcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.9) ]\n  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/]\n  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/]\n  ignore line: [COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_1b6e6' '-mtune=generic' '-march=x86-64']\n  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]\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/collect2] ==> ignore\n    arg [-plugin] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/liblto_plugin.so] ==> ignore\n    arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper] ==> ignore\n    arg [-plugin-opt=-fresolution=/tmp/ccGW6Hat.res] ==> ignore\n    arg [-plugin-opt=-pass-through=-lgcc] ==> ignore\n    arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore\n    arg [-plugin-opt=-pass-through=-lc] ==> ignore\n    arg [-plugin-opt=-pass-through=-lgcc] ==> ignore\n    arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore\n    arg [--sysroot=/] ==> ignore\n    arg [--build-id] ==> ignore\n    arg [--eh-frame-hdr] ==> ignore\n    arg [-m] ==> ignore\n    arg [elf_x86_64] ==> ignore\n    arg [--hash-style=gnu] ==> ignore\n    arg [--as-needed] ==> ignore\n    arg [-export-dynamic] ==> ignore\n    arg [-dynamic-linker] ==> ignore\n    arg [/lib64/ld-linux-x86-64.so.2] ==> ignore\n    arg [-zrelro] ==> ignore\n    arg [-o] ==> ignore\n    arg [cmTC_1b6e6] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crt1.o] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crti.o] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/crtbegin.o] ==> ignore\n    arg [-L/usr/lib/gcc/x86_64-linux-gnu/5] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5]\n    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]\n    arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib]\n    arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu]\n    arg [-L/lib/../lib] ==> dir [/lib/../lib]\n    arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu]\n    arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib]\n    arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../..]\n    arg [CMakeFiles/cmTC_1b6e6.dir/CMakeCCompilerABI.c.o] ==> ignore\n    arg [-lgcc] ==> lib [gcc]\n    arg [--as-needed] ==> ignore\n    arg [-lgcc_s] ==> lib [gcc_s]\n    arg [--no-as-needed] ==> ignore\n    arg [-lc] ==> lib [c]\n    arg [-lgcc] ==> lib [gcc]\n    arg [--as-needed] ==> ignore\n    arg [-lgcc_s] ==> lib [gcc_s]\n    arg [--no-as-needed] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/crtend.o] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crtn.o] ==> ignore\n  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5] ==> [/usr/lib/gcc/x86_64-linux-gnu/5]\n  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]\n  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] ==> [/usr/lib]\n  collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu]\n  collapse library dir [/lib/../lib] ==> [/lib]\n  collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]\n  collapse library dir [/usr/lib/../lib] ==> [/usr/lib]\n  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../..] ==> [/usr/lib]\n  implicit libs: [gcc;gcc_s;c;gcc;gcc_s]\n  implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/5;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib]\n  implicit fwks: []\n\n\n\n\nDetecting C [-std=c11] compiler features compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_d3b2f/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_d3b2f.dir/build.make CMakeFiles/cmTC_d3b2f.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_d3b2f.dir/feature_tests.c.o\n/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\nLinking C executable cmTC_d3b2f\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d3b2f.dir/link.txt --verbose=1\n/usr/bin/cc      -rdynamic CMakeFiles/cmTC_d3b2f.dir/feature_tests.c.o  -o cmTC_d3b2f \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\n    Feature record: C_FEATURE:1c_function_prototypes\n    Feature record: C_FEATURE:1c_restrict\n    Feature record: C_FEATURE:1c_static_assert\n    Feature record: C_FEATURE:1c_variadic_macros\n\n\nDetecting C [-std=c99] compiler features compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_71a21/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_71a21.dir/build.make CMakeFiles/cmTC_71a21.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_71a21.dir/feature_tests.c.o\n/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\nLinking C executable cmTC_71a21\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_71a21.dir/link.txt --verbose=1\n/usr/bin/cc      -rdynamic CMakeFiles/cmTC_71a21.dir/feature_tests.c.o  -o cmTC_71a21 \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\n    Feature record: C_FEATURE:1c_function_prototypes\n    Feature record: C_FEATURE:1c_restrict\n    Feature record: C_FEATURE:0c_static_assert\n    Feature record: C_FEATURE:1c_variadic_macros\n\n\nDetecting C [-std=c90] compiler features compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_2eb43/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_2eb43.dir/build.make CMakeFiles/cmTC_2eb43.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_2eb43.dir/feature_tests.c.o\n/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\nLinking C executable cmTC_2eb43\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_2eb43.dir/link.txt --verbose=1\n/usr/bin/cc      -rdynamic CMakeFiles/cmTC_2eb43.dir/feature_tests.c.o  -o cmTC_2eb43 \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\n    Feature record: C_FEATURE:1c_function_prototypes\n    Feature record: C_FEATURE:0c_restrict\n    Feature record: C_FEATURE:0c_static_assert\n    Feature record: C_FEATURE:0c_variadic_macros\nDetermining if the CXX compiler works passed with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_c6cd7/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_c6cd7.dir/build.make CMakeFiles/cmTC_c6cd7.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding CXX object CMakeFiles/cmTC_c6cd7.dir/testCXXCompiler.cxx.o\n/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\nLinking CXX executable cmTC_c6cd7\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_c6cd7.dir/link.txt --verbose=1\n/usr/bin/c++       -rdynamic CMakeFiles/cmTC_c6cd7.dir/testCXXCompiler.cxx.o  -o cmTC_c6cd7 \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\nDetecting CXX compiler ABI info compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_d3f63/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_d3f63.dir/build.make CMakeFiles/cmTC_d3f63.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding CXX object CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o\n/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\nLinking CXX executable cmTC_d3f63\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d3f63.dir/link.txt --verbose=1\n/usr/bin/c++      -v -rdynamic CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o  -o cmTC_d3f63 \nUsing built-in specs.\nCOLLECT_GCC=/usr/bin/c++\nCOLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper\nTarget: x86_64-linux-gnu\nConfigured 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\nThread model: posix\ngcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.9) \nCOMPILER_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/\nLIBRARY_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/\nCOLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_d3f63' '-shared-libgcc' '-mtune=generic' '-march=x86-64'\n /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\nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\nParsed CXX implicit link information from above output:\n  link line regex: [^( *|.*[/\\])(ld|CMAKE_LINK_STARTFILE-NOTFOUND|([^/\\]+-)?ld|collect2)[^/\\]*( |$)]\n  ignore line: [Change Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp]\n  ignore line: []\n  ignore line: [Run Build Command:\"/usr/bin/make\" \"cmTC_d3f63/fast\"]\n  ignore line: [/usr/bin/make -f CMakeFiles/cmTC_d3f63.dir/build.make CMakeFiles/cmTC_d3f63.dir/build]\n  ignore line: [make[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp']\n  ignore line: [Building CXX object CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o]\n  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]\n  ignore line: [Linking CXX executable cmTC_d3f63]\n  ignore line: [/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d3f63.dir/link.txt --verbose=1]\n  ignore line: [/usr/bin/c++      -v -rdynamic CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o  -o cmTC_d3f63 ]\n  ignore line: [Using built-in specs.]\n  ignore line: [COLLECT_GCC=/usr/bin/c++]\n  ignore line: [COLLECT_LTO_WRAPPER=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper]\n  ignore line: [Target: x86_64-linux-gnu]\n  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]\n  ignore line: [Thread model: posix]\n  ignore line: [gcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.9) ]\n  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/]\n  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/]\n  ignore line: [COLLECT_GCC_OPTIONS='-v' '-rdynamic' '-o' 'cmTC_d3f63' '-shared-libgcc' '-mtune=generic' '-march=x86-64']\n  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]\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/collect2] ==> ignore\n    arg [-plugin] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/liblto_plugin.so] ==> ignore\n    arg [-plugin-opt=/usr/lib/gcc/x86_64-linux-gnu/5/lto-wrapper] ==> ignore\n    arg [-plugin-opt=-fresolution=/tmp/ccHH93NP.res] ==> ignore\n    arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore\n    arg [-plugin-opt=-pass-through=-lgcc] ==> ignore\n    arg [-plugin-opt=-pass-through=-lc] ==> ignore\n    arg [-plugin-opt=-pass-through=-lgcc_s] ==> ignore\n    arg [-plugin-opt=-pass-through=-lgcc] ==> ignore\n    arg [--sysroot=/] ==> ignore\n    arg [--build-id] ==> ignore\n    arg [--eh-frame-hdr] ==> ignore\n    arg [-m] ==> ignore\n    arg [elf_x86_64] ==> ignore\n    arg [--hash-style=gnu] ==> ignore\n    arg [--as-needed] ==> ignore\n    arg [-export-dynamic] ==> ignore\n    arg [-dynamic-linker] ==> ignore\n    arg [/lib64/ld-linux-x86-64.so.2] ==> ignore\n    arg [-zrelro] ==> ignore\n    arg [-o] ==> ignore\n    arg [cmTC_d3f63] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crt1.o] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crti.o] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/crtbegin.o] ==> ignore\n    arg [-L/usr/lib/gcc/x86_64-linux-gnu/5] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5]\n    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]\n    arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib]\n    arg [-L/lib/x86_64-linux-gnu] ==> dir [/lib/x86_64-linux-gnu]\n    arg [-L/lib/../lib] ==> dir [/lib/../lib]\n    arg [-L/usr/lib/x86_64-linux-gnu] ==> dir [/usr/lib/x86_64-linux-gnu]\n    arg [-L/usr/lib/../lib] ==> dir [/usr/lib/../lib]\n    arg [-L/usr/lib/gcc/x86_64-linux-gnu/5/../../..] ==> dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../..]\n    arg [CMakeFiles/cmTC_d3f63.dir/CMakeCXXCompilerABI.cpp.o] ==> ignore\n    arg [-lstdc++] ==> lib [stdc++]\n    arg [-lm] ==> lib [m]\n    arg [-lgcc_s] ==> lib [gcc_s]\n    arg [-lgcc] ==> lib [gcc]\n    arg [-lc] ==> lib [c]\n    arg [-lgcc_s] ==> lib [gcc_s]\n    arg [-lgcc] ==> lib [gcc]\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/crtend.o] ==> ignore\n    arg [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu/crtn.o] ==> ignore\n  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5] ==> [/usr/lib/gcc/x86_64-linux-gnu/5]\n  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]\n  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../../../lib] ==> [/usr/lib]\n  collapse library dir [/lib/x86_64-linux-gnu] ==> [/lib/x86_64-linux-gnu]\n  collapse library dir [/lib/../lib] ==> [/lib]\n  collapse library dir [/usr/lib/x86_64-linux-gnu] ==> [/usr/lib/x86_64-linux-gnu]\n  collapse library dir [/usr/lib/../lib] ==> [/usr/lib]\n  collapse library dir [/usr/lib/gcc/x86_64-linux-gnu/5/../../..] ==> [/usr/lib]\n  implicit libs: [stdc++;m;gcc_s;gcc;c;gcc_s;gcc]\n  implicit dirs: [/usr/lib/gcc/x86_64-linux-gnu/5;/usr/lib/x86_64-linux-gnu;/usr/lib;/lib/x86_64-linux-gnu;/lib]\n  implicit fwks: []\n\n\n\n\nDetecting CXX [-std=c++1z] compiler features compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_07712/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_07712.dir/build.make CMakeFiles/cmTC_07712.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding CXX object CMakeFiles/cmTC_07712.dir/feature_tests.cxx.o\n/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\nLinking CXX executable cmTC_07712\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_07712.dir/link.txt --verbose=1\n/usr/bin/c++       -rdynamic CMakeFiles/cmTC_07712.dir/feature_tests.cxx.o  -o cmTC_07712 \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\n    Feature record: CXX_FEATURE:1cxx_aggregate_default_initializers\n    Feature record: CXX_FEATURE:1cxx_alias_templates\n    Feature record: CXX_FEATURE:1cxx_alignas\n    Feature record: CXX_FEATURE:1cxx_alignof\n    Feature record: CXX_FEATURE:1cxx_attributes\n    Feature record: CXX_FEATURE:1cxx_attribute_deprecated\n    Feature record: CXX_FEATURE:1cxx_auto_type\n    Feature record: CXX_FEATURE:1cxx_binary_literals\n    Feature record: CXX_FEATURE:1cxx_constexpr\n    Feature record: CXX_FEATURE:1cxx_contextual_conversions\n    Feature record: CXX_FEATURE:1cxx_decltype\n    Feature record: CXX_FEATURE:1cxx_decltype_auto\n    Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types\n    Feature record: CXX_FEATURE:1cxx_default_function_template_args\n    Feature record: CXX_FEATURE:1cxx_defaulted_functions\n    Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers\n    Feature record: CXX_FEATURE:1cxx_delegating_constructors\n    Feature record: CXX_FEATURE:1cxx_deleted_functions\n    Feature record: CXX_FEATURE:1cxx_digit_separators\n    Feature record: CXX_FEATURE:1cxx_enum_forward_declarations\n    Feature record: CXX_FEATURE:1cxx_explicit_conversions\n    Feature record: CXX_FEATURE:1cxx_extended_friend_declarations\n    Feature record: CXX_FEATURE:1cxx_extern_templates\n    Feature record: CXX_FEATURE:1cxx_final\n    Feature record: CXX_FEATURE:1cxx_func_identifier\n    Feature record: CXX_FEATURE:1cxx_generalized_initializers\n    Feature record: CXX_FEATURE:1cxx_generic_lambdas\n    Feature record: CXX_FEATURE:1cxx_inheriting_constructors\n    Feature record: CXX_FEATURE:1cxx_inline_namespaces\n    Feature record: CXX_FEATURE:1cxx_lambdas\n    Feature record: CXX_FEATURE:1cxx_lambda_init_captures\n    Feature record: CXX_FEATURE:1cxx_local_type_template_args\n    Feature record: CXX_FEATURE:1cxx_long_long_type\n    Feature record: CXX_FEATURE:1cxx_noexcept\n    Feature record: CXX_FEATURE:1cxx_nonstatic_member_init\n    Feature record: CXX_FEATURE:1cxx_nullptr\n    Feature record: CXX_FEATURE:1cxx_override\n    Feature record: CXX_FEATURE:1cxx_range_for\n    Feature record: CXX_FEATURE:1cxx_raw_string_literals\n    Feature record: CXX_FEATURE:1cxx_reference_qualified_functions\n    Feature record: CXX_FEATURE:1cxx_relaxed_constexpr\n    Feature record: CXX_FEATURE:1cxx_return_type_deduction\n    Feature record: CXX_FEATURE:1cxx_right_angle_brackets\n    Feature record: CXX_FEATURE:1cxx_rvalue_references\n    Feature record: CXX_FEATURE:1cxx_sizeof_member\n    Feature record: CXX_FEATURE:1cxx_static_assert\n    Feature record: CXX_FEATURE:1cxx_strong_enums\n    Feature record: CXX_FEATURE:1cxx_template_template_parameters\n    Feature record: CXX_FEATURE:1cxx_thread_local\n    Feature record: CXX_FEATURE:1cxx_trailing_return_types\n    Feature record: CXX_FEATURE:1cxx_unicode_literals\n    Feature record: CXX_FEATURE:1cxx_uniform_initialization\n    Feature record: CXX_FEATURE:1cxx_unrestricted_unions\n    Feature record: CXX_FEATURE:1cxx_user_literals\n    Feature record: CXX_FEATURE:1cxx_variable_templates\n    Feature record: CXX_FEATURE:1cxx_variadic_macros\n    Feature record: CXX_FEATURE:1cxx_variadic_templates\n\n\nDetecting CXX [-std=c++14] compiler features compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_d0df9/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_d0df9.dir/build.make CMakeFiles/cmTC_d0df9.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding CXX object CMakeFiles/cmTC_d0df9.dir/feature_tests.cxx.o\n/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\nLinking CXX executable cmTC_d0df9\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d0df9.dir/link.txt --verbose=1\n/usr/bin/c++       -rdynamic CMakeFiles/cmTC_d0df9.dir/feature_tests.cxx.o  -o cmTC_d0df9 \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\n    Feature record: CXX_FEATURE:1cxx_aggregate_default_initializers\n    Feature record: CXX_FEATURE:1cxx_alias_templates\n    Feature record: CXX_FEATURE:1cxx_alignas\n    Feature record: CXX_FEATURE:1cxx_alignof\n    Feature record: CXX_FEATURE:1cxx_attributes\n    Feature record: CXX_FEATURE:1cxx_attribute_deprecated\n    Feature record: CXX_FEATURE:1cxx_auto_type\n    Feature record: CXX_FEATURE:1cxx_binary_literals\n    Feature record: CXX_FEATURE:1cxx_constexpr\n    Feature record: CXX_FEATURE:1cxx_contextual_conversions\n    Feature record: CXX_FEATURE:1cxx_decltype\n    Feature record: CXX_FEATURE:1cxx_decltype_auto\n    Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types\n    Feature record: CXX_FEATURE:1cxx_default_function_template_args\n    Feature record: CXX_FEATURE:1cxx_defaulted_functions\n    Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers\n    Feature record: CXX_FEATURE:1cxx_delegating_constructors\n    Feature record: CXX_FEATURE:1cxx_deleted_functions\n    Feature record: CXX_FEATURE:1cxx_digit_separators\n    Feature record: CXX_FEATURE:1cxx_enum_forward_declarations\n    Feature record: CXX_FEATURE:1cxx_explicit_conversions\n    Feature record: CXX_FEATURE:1cxx_extended_friend_declarations\n    Feature record: CXX_FEATURE:1cxx_extern_templates\n    Feature record: CXX_FEATURE:1cxx_final\n    Feature record: CXX_FEATURE:1cxx_func_identifier\n    Feature record: CXX_FEATURE:1cxx_generalized_initializers\n    Feature record: CXX_FEATURE:1cxx_generic_lambdas\n    Feature record: CXX_FEATURE:1cxx_inheriting_constructors\n    Feature record: CXX_FEATURE:1cxx_inline_namespaces\n    Feature record: CXX_FEATURE:1cxx_lambdas\n    Feature record: CXX_FEATURE:1cxx_lambda_init_captures\n    Feature record: CXX_FEATURE:1cxx_local_type_template_args\n    Feature record: CXX_FEATURE:1cxx_long_long_type\n    Feature record: CXX_FEATURE:1cxx_noexcept\n    Feature record: CXX_FEATURE:1cxx_nonstatic_member_init\n    Feature record: CXX_FEATURE:1cxx_nullptr\n    Feature record: CXX_FEATURE:1cxx_override\n    Feature record: CXX_FEATURE:1cxx_range_for\n    Feature record: CXX_FEATURE:1cxx_raw_string_literals\n    Feature record: CXX_FEATURE:1cxx_reference_qualified_functions\n    Feature record: CXX_FEATURE:1cxx_relaxed_constexpr\n    Feature record: CXX_FEATURE:1cxx_return_type_deduction\n    Feature record: CXX_FEATURE:1cxx_right_angle_brackets\n    Feature record: CXX_FEATURE:1cxx_rvalue_references\n    Feature record: CXX_FEATURE:1cxx_sizeof_member\n    Feature record: CXX_FEATURE:1cxx_static_assert\n    Feature record: CXX_FEATURE:1cxx_strong_enums\n    Feature record: CXX_FEATURE:1cxx_template_template_parameters\n    Feature record: CXX_FEATURE:1cxx_thread_local\n    Feature record: CXX_FEATURE:1cxx_trailing_return_types\n    Feature record: CXX_FEATURE:1cxx_unicode_literals\n    Feature record: CXX_FEATURE:1cxx_uniform_initialization\n    Feature record: CXX_FEATURE:1cxx_unrestricted_unions\n    Feature record: CXX_FEATURE:1cxx_user_literals\n    Feature record: CXX_FEATURE:1cxx_variable_templates\n    Feature record: CXX_FEATURE:1cxx_variadic_macros\n    Feature record: CXX_FEATURE:1cxx_variadic_templates\n\n\nDetecting CXX [-std=c++11] compiler features compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_a7bdf/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_a7bdf.dir/build.make CMakeFiles/cmTC_a7bdf.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding CXX object CMakeFiles/cmTC_a7bdf.dir/feature_tests.cxx.o\n/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\nLinking CXX executable cmTC_a7bdf\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_a7bdf.dir/link.txt --verbose=1\n/usr/bin/c++       -rdynamic CMakeFiles/cmTC_a7bdf.dir/feature_tests.cxx.o  -o cmTC_a7bdf \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\n    Feature record: CXX_FEATURE:0cxx_aggregate_default_initializers\n    Feature record: CXX_FEATURE:1cxx_alias_templates\n    Feature record: CXX_FEATURE:1cxx_alignas\n    Feature record: CXX_FEATURE:1cxx_alignof\n    Feature record: CXX_FEATURE:1cxx_attributes\n    Feature record: CXX_FEATURE:0cxx_attribute_deprecated\n    Feature record: CXX_FEATURE:1cxx_auto_type\n    Feature record: CXX_FEATURE:0cxx_binary_literals\n    Feature record: CXX_FEATURE:1cxx_constexpr\n    Feature record: CXX_FEATURE:0cxx_contextual_conversions\n    Feature record: CXX_FEATURE:1cxx_decltype\n    Feature record: CXX_FEATURE:0cxx_decltype_auto\n    Feature record: CXX_FEATURE:1cxx_decltype_incomplete_return_types\n    Feature record: CXX_FEATURE:1cxx_default_function_template_args\n    Feature record: CXX_FEATURE:1cxx_defaulted_functions\n    Feature record: CXX_FEATURE:1cxx_defaulted_move_initializers\n    Feature record: CXX_FEATURE:1cxx_delegating_constructors\n    Feature record: CXX_FEATURE:1cxx_deleted_functions\n    Feature record: CXX_FEATURE:0cxx_digit_separators\n    Feature record: CXX_FEATURE:1cxx_enum_forward_declarations\n    Feature record: CXX_FEATURE:1cxx_explicit_conversions\n    Feature record: CXX_FEATURE:1cxx_extended_friend_declarations\n    Feature record: CXX_FEATURE:1cxx_extern_templates\n    Feature record: CXX_FEATURE:1cxx_final\n    Feature record: CXX_FEATURE:1cxx_func_identifier\n    Feature record: CXX_FEATURE:1cxx_generalized_initializers\n    Feature record: CXX_FEATURE:0cxx_generic_lambdas\n    Feature record: CXX_FEATURE:1cxx_inheriting_constructors\n    Feature record: CXX_FEATURE:1cxx_inline_namespaces\n    Feature record: CXX_FEATURE:1cxx_lambdas\n    Feature record: CXX_FEATURE:0cxx_lambda_init_captures\n    Feature record: CXX_FEATURE:1cxx_local_type_template_args\n    Feature record: CXX_FEATURE:1cxx_long_long_type\n    Feature record: CXX_FEATURE:1cxx_noexcept\n    Feature record: CXX_FEATURE:1cxx_nonstatic_member_init\n    Feature record: CXX_FEATURE:1cxx_nullptr\n    Feature record: CXX_FEATURE:1cxx_override\n    Feature record: CXX_FEATURE:1cxx_range_for\n    Feature record: CXX_FEATURE:1cxx_raw_string_literals\n    Feature record: CXX_FEATURE:1cxx_reference_qualified_functions\n    Feature record: CXX_FEATURE:0cxx_relaxed_constexpr\n    Feature record: CXX_FEATURE:0cxx_return_type_deduction\n    Feature record: CXX_FEATURE:1cxx_right_angle_brackets\n    Feature record: CXX_FEATURE:1cxx_rvalue_references\n    Feature record: CXX_FEATURE:1cxx_sizeof_member\n    Feature record: CXX_FEATURE:1cxx_static_assert\n    Feature record: CXX_FEATURE:1cxx_strong_enums\n    Feature record: CXX_FEATURE:1cxx_template_template_parameters\n    Feature record: CXX_FEATURE:1cxx_thread_local\n    Feature record: CXX_FEATURE:1cxx_trailing_return_types\n    Feature record: CXX_FEATURE:1cxx_unicode_literals\n    Feature record: CXX_FEATURE:1cxx_uniform_initialization\n    Feature record: CXX_FEATURE:1cxx_unrestricted_unions\n    Feature record: CXX_FEATURE:1cxx_user_literals\n    Feature record: CXX_FEATURE:0cxx_variable_templates\n    Feature record: CXX_FEATURE:1cxx_variadic_macros\n    Feature record: CXX_FEATURE:1cxx_variadic_templates\n\n\nDetecting CXX [-std=c++98] compiler features compiled with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_73896/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_73896.dir/build.make CMakeFiles/cmTC_73896.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding CXX object CMakeFiles/cmTC_73896.dir/feature_tests.cxx.o\n/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\nLinking CXX executable cmTC_73896\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_73896.dir/link.txt --verbose=1\n/usr/bin/c++       -rdynamic CMakeFiles/cmTC_73896.dir/feature_tests.cxx.o  -o cmTC_73896 \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\n    Feature record: CXX_FEATURE:0cxx_aggregate_default_initializers\n    Feature record: CXX_FEATURE:0cxx_alias_templates\n    Feature record: CXX_FEATURE:0cxx_alignas\n    Feature record: CXX_FEATURE:0cxx_alignof\n    Feature record: CXX_FEATURE:0cxx_attributes\n    Feature record: CXX_FEATURE:0cxx_attribute_deprecated\n    Feature record: CXX_FEATURE:0cxx_auto_type\n    Feature record: CXX_FEATURE:0cxx_binary_literals\n    Feature record: CXX_FEATURE:0cxx_constexpr\n    Feature record: CXX_FEATURE:0cxx_contextual_conversions\n    Feature record: CXX_FEATURE:0cxx_decltype\n    Feature record: CXX_FEATURE:0cxx_decltype_auto\n    Feature record: CXX_FEATURE:0cxx_decltype_incomplete_return_types\n    Feature record: CXX_FEATURE:0cxx_default_function_template_args\n    Feature record: CXX_FEATURE:0cxx_defaulted_functions\n    Feature record: CXX_FEATURE:0cxx_defaulted_move_initializers\n    Feature record: CXX_FEATURE:0cxx_delegating_constructors\n    Feature record: CXX_FEATURE:0cxx_deleted_functions\n    Feature record: CXX_FEATURE:0cxx_digit_separators\n    Feature record: CXX_FEATURE:0cxx_enum_forward_declarations\n    Feature record: CXX_FEATURE:0cxx_explicit_conversions\n    Feature record: CXX_FEATURE:0cxx_extended_friend_declarations\n    Feature record: CXX_FEATURE:0cxx_extern_templates\n    Feature record: CXX_FEATURE:0cxx_final\n    Feature record: CXX_FEATURE:0cxx_func_identifier\n    Feature record: CXX_FEATURE:0cxx_generalized_initializers\n    Feature record: CXX_FEATURE:0cxx_generic_lambdas\n    Feature record: CXX_FEATURE:0cxx_inheriting_constructors\n    Feature record: CXX_FEATURE:0cxx_inline_namespaces\n    Feature record: CXX_FEATURE:0cxx_lambdas\n    Feature record: CXX_FEATURE:0cxx_lambda_init_captures\n    Feature record: CXX_FEATURE:0cxx_local_type_template_args\n    Feature record: CXX_FEATURE:0cxx_long_long_type\n    Feature record: CXX_FEATURE:0cxx_noexcept\n    Feature record: CXX_FEATURE:0cxx_nonstatic_member_init\n    Feature record: CXX_FEATURE:0cxx_nullptr\n    Feature record: CXX_FEATURE:0cxx_override\n    Feature record: CXX_FEATURE:0cxx_range_for\n    Feature record: CXX_FEATURE:0cxx_raw_string_literals\n    Feature record: CXX_FEATURE:0cxx_reference_qualified_functions\n    Feature record: CXX_FEATURE:0cxx_relaxed_constexpr\n    Feature record: CXX_FEATURE:0cxx_return_type_deduction\n    Feature record: CXX_FEATURE:0cxx_right_angle_brackets\n    Feature record: CXX_FEATURE:0cxx_rvalue_references\n    Feature record: CXX_FEATURE:0cxx_sizeof_member\n    Feature record: CXX_FEATURE:0cxx_static_assert\n    Feature record: CXX_FEATURE:0cxx_strong_enums\n    Feature record: CXX_FEATURE:1cxx_template_template_parameters\n    Feature record: CXX_FEATURE:0cxx_thread_local\n    Feature record: CXX_FEATURE:0cxx_trailing_return_types\n    Feature record: CXX_FEATURE:0cxx_unicode_literals\n    Feature record: CXX_FEATURE:0cxx_uniform_initialization\n    Feature record: CXX_FEATURE:0cxx_unrestricted_unions\n    Feature record: CXX_FEATURE:0cxx_user_literals\n    Feature record: CXX_FEATURE:0cxx_variable_templates\n    Feature record: CXX_FEATURE:0cxx_variadic_macros\n    Feature record: CXX_FEATURE:0cxx_variadic_templates\nDetermining if the include file pthread.h exists passed with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_d2f5c/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_d2f5c.dir/build.make CMakeFiles/cmTC_d2f5c.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_d2f5c.dir/CheckIncludeFile.c.o\n/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\nLinking C executable cmTC_d2f5c\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_d2f5c.dir/link.txt --verbose=1\n/usr/bin/cc      -rdynamic CMakeFiles/cmTC_d2f5c.dir/CheckIncludeFile.c.o  -o cmTC_d2f5c \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\nDetermining if the function pthread_create exists in the pthread passed with the following output:\nChange Dir: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp\n\nRun Build Command:\"/usr/bin/make\" \"cmTC_c1478/fast\"\n/usr/bin/make -f CMakeFiles/cmTC_c1478.dir/build.make CMakeFiles/cmTC_c1478.dir/build\nmake[1]: Entering directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\nBuilding C object CMakeFiles/cmTC_c1478.dir/CheckFunctionExists.c.o\n/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\nLinking C executable cmTC_c1478\n/home/zn/.ide/clion/bin/cmake/bin/cmake -E cmake_link_script CMakeFiles/cmTC_c1478.dir/link.txt --verbose=1\n/usr/bin/cc  -DCHECK_FUNCTION_EXISTS=pthread_create    -rdynamic CMakeFiles/cmTC_c1478.dir/CheckFunctionExists.c.o  -o cmTC_c1478 -lpthread \nmake[1]: Leaving directory '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeTmp'\n\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/CMakeRuleHashes.txt",
    "content": "# Hashes of file build rules.\n2c614c39f77a5e21e00ecd0f46df5d82 CMakeFiles/clean_test_results\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/Makefile.cmake",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# The generator used is:\nset(CMAKE_DEPENDS_GENERATOR \"Unix Makefiles\")\n\n# The top level Makefile was generated from the following files:\nset(CMAKE_MAKEFILE_DEPENDS\n  \"CMakeCache.txt\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCCompiler.cmake.in\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCCompilerABI.c\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCInformation.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCXXCompiler.cmake.in\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCXXCompilerABI.cpp\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCXXInformation.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCommonLanguageInclude.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeCompilerIdDetection.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeConfigurableFile.in\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCXXCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCompileFeatures.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCompilerABI.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineCompilerId.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeDetermineSystem.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeExtraGeneratorDetermineCompilerMacrosAndIncludeDirs.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeFindBinUtils.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeFindCodeBlocks.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeFindDependencyMacro.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeGenericSystem.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeLanguageInformation.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeParseArguments.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeParseImplicitLinkInfo.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeSystem.cmake.in\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeSystemSpecificInformation.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeSystemSpecificInitialize.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeTestCCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeTestCXXCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeTestCompilerCommon.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CMakeUnixFindMake.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckFunctionExists.c\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckIncludeFile.c.in\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckIncludeFile.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckLibraryExists.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/CheckSymbolExists.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/ADSP-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/ARMCC-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/AppleClang-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Borland-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Bruce-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/CMakeCommonCompilerMacros.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Clang-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Clang-DetermineCompilerInternal.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Comeau-CXX-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Compaq-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Compaq-CXX-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Cray-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Embarcadero-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Fujitsu-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GHS-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-C-FeatureTests.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-C.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-CXX-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-CXX-FeatureTests.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-CXX.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU-FindBinUtils.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/GNU.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/HP-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/HP-CXX-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/IAR-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/IBMCPP-C-DetermineVersionInternal.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/IBMCPP-CXX-DetermineVersionInternal.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Intel-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/MIPSpro-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/MSVC-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/NVIDIA-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/OpenWatcom-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/PGI-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/PathScale-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/SCO-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/SDCC-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/SunPro-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/SunPro-CXX-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/TI-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/TinyCC-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/VisualAge-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/VisualAge-CXX-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/Watcom-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/XL-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/XL-CXX-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/zOS-C-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Compiler/zOS-CXX-DetermineCompiler.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindBoost.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindGTest.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindPackageHandleStandardArgs.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindPackageMessage.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindPythonInterp.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/FindThreads.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/GoogleTest.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Internal/FeatureTesting.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux-Determine-CXX.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux-GNU-C.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux-GNU-CXX.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux-GNU.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/Linux.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/Platform/UnixPaths.cmake\"\n  \"/home/zn/.ide/clion/bin/cmake/share/cmake-3.9/Modules/ProcessorCount.cmake\"\n  \"../CMakeLists.txt\"\n  \"CMakeFiles/3.9.6/CMakeCCompiler.cmake\"\n  \"CMakeFiles/3.9.6/CMakeCXXCompiler.cmake\"\n  \"CMakeFiles/3.9.6/CMakeSystem.cmake\"\n  \"CMakeFiles/feature_tests.c\"\n  \"CMakeFiles/feature_tests.cxx\"\n  \"catkin/catkin_generated/version/package.cmake\"\n  \"catkin_generated/installspace/_setup_util.py\"\n  \"catkin_generated/ordered_paths.cmake\"\n  \"catkin_generated/package.cmake\"\n  \"../package.xml\"\n  \"/opt/ros/kinetic/share/actionlib/cmake/actionlib-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/actionlib/cmake/actionlibConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/actionlib/cmake/actionlibConfig.cmake\"\n  \"/opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgs-extras.cmake\"\n  \"/opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgs-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgsConfig.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/../package.xml\"\n  \"/opt/ros/kinetic/share/catkin/cmake/all.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/assert.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/atomic_configure_file.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkinConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_add_env_hooks.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_destinations.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_download.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_generate_environment.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_install_python.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_libraries.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_metapackage.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_package.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_package_xml.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_python_setup.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/catkin_workspace.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/debug_message.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/em/pkg.pc.em\"\n  \"/opt/ros/kinetic/share/catkin/cmake/em_expand.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/empy.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/find_program_required.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/interrogate_setup_dot_py.py\"\n  \"/opt/ros/kinetic/share/catkin/cmake/legacy.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/list_append_deduplicate.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/list_append_unique.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/list_insert_in_workspace_order.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/platform/lsb.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/platform/ubuntu.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/platform/windows.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/python.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/safe_execute_process.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/stamp.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/string_starts_with.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/_setup_util.py.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/env.sh.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/generate_cached_setup.py.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/pkg.context.pc.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/pkgConfig-version.cmake.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/pkgConfig.cmake.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/rosinstall.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/setup.bash.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/setup.sh.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/templates/setup.zsh.in\"\n  \"/opt/ros/kinetic/share/catkin/cmake/test/catkin_download_test_data.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/test/gtest.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/test/nosetests.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/test/tests.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/tools/doxygen.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/tools/libraries.cmake\"\n  \"/opt/ros/kinetic/share/catkin/cmake/tools/rt.cmake\"\n  \"/opt/ros/kinetic/share/cmake_modules/cmake/cmake_modules-extras.cmake\"\n  \"/opt/ros/kinetic/share/cmake_modules/cmake/cmake_modulesConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/cmake_modules/cmake/cmake_modulesConfig.cmake\"\n  \"/opt/ros/kinetic/share/cpp_common/cmake/cpp_commonConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/cpp_common/cmake/cpp_commonConfig.cmake\"\n  \"/opt/ros/kinetic/share/gencpp/cmake/gencpp-extras.cmake\"\n  \"/opt/ros/kinetic/share/gencpp/cmake/gencppConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/gencpp/cmake/gencppConfig.cmake\"\n  \"/opt/ros/kinetic/share/geneus/cmake/geneus-extras.cmake\"\n  \"/opt/ros/kinetic/share/geneus/cmake/geneusConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/geneus/cmake/geneusConfig.cmake\"\n  \"/opt/ros/kinetic/share/genlisp/cmake/genlisp-extras.cmake\"\n  \"/opt/ros/kinetic/share/genlisp/cmake/genlispConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/genlisp/cmake/genlispConfig.cmake\"\n  \"/opt/ros/kinetic/share/genmsg/cmake/genmsg-extras.cmake\"\n  \"/opt/ros/kinetic/share/genmsg/cmake/genmsgConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/genmsg/cmake/genmsgConfig.cmake\"\n  \"/opt/ros/kinetic/share/gennodejs/cmake/gennodejs-extras.cmake\"\n  \"/opt/ros/kinetic/share/gennodejs/cmake/gennodejsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/gennodejs/cmake/gennodejsConfig.cmake\"\n  \"/opt/ros/kinetic/share/genpy/cmake/genpy-extras.cmake\"\n  \"/opt/ros/kinetic/share/genpy/cmake/genpyConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/genpy/cmake/genpyConfig.cmake\"\n  \"/opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgs-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgsConfig.cmake\"\n  \"/opt/ros/kinetic/share/message_filters/cmake/message_filtersConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/message_filters/cmake/message_filtersConfig.cmake\"\n  \"/opt/ros/kinetic/share/message_generation/cmake/message_generationConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/message_generation/cmake/message_generationConfig.cmake\"\n  \"/opt/ros/kinetic/share/message_runtime/cmake/message_runtimeConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/message_runtime/cmake/message_runtimeConfig.cmake\"\n  \"/opt/ros/kinetic/share/nav_msgs/cmake/nav_msgs-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/nav_msgs/cmake/nav_msgsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/nav_msgs/cmake/nav_msgsConfig.cmake\"\n  \"/opt/ros/kinetic/share/rosconsole/cmake/rosconsole-extras.cmake\"\n  \"/opt/ros/kinetic/share/rosconsole/cmake/rosconsoleConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/rosconsole/cmake/rosconsoleConfig.cmake\"\n  \"/opt/ros/kinetic/share/roscpp/cmake/roscpp-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/roscpp/cmake/roscppConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/roscpp/cmake/roscppConfig.cmake\"\n  \"/opt/ros/kinetic/share/roscpp_serialization/cmake/roscpp_serializationConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/roscpp_serialization/cmake/roscpp_serializationConfig.cmake\"\n  \"/opt/ros/kinetic/share/roscpp_traits/cmake/roscpp_traitsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/roscpp_traits/cmake/roscpp_traitsConfig.cmake\"\n  \"/opt/ros/kinetic/share/rosgraph/cmake/rosgraphConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/rosgraph/cmake/rosgraphConfig.cmake\"\n  \"/opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgs-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgsConfig.cmake\"\n  \"/opt/ros/kinetic/share/rospy/cmake/rospyConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/rospy/cmake/rospyConfig.cmake\"\n  \"/opt/ros/kinetic/share/rostime/cmake/rostimeConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/rostime/cmake/rostimeConfig.cmake\"\n  \"/opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgs-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgsConfig.cmake\"\n  \"/opt/ros/kinetic/share/std_msgs/cmake/std_msgs-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/std_msgs/cmake/std_msgsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/std_msgs/cmake/std_msgsConfig.cmake\"\n  \"/opt/ros/kinetic/share/tf/cmake/tf-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/tf/cmake/tfConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/tf/cmake/tfConfig.cmake\"\n  \"/opt/ros/kinetic/share/tf2/cmake/tf2Config-version.cmake\"\n  \"/opt/ros/kinetic/share/tf2/cmake/tf2Config.cmake\"\n  \"/opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgs-msg-extras.cmake\"\n  \"/opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgsConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgsConfig.cmake\"\n  \"/opt/ros/kinetic/share/tf2_py/cmake/tf2_pyConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/tf2_py/cmake/tf2_pyConfig.cmake\"\n  \"/opt/ros/kinetic/share/tf2_ros/cmake/tf2_rosConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/tf2_ros/cmake/tf2_rosConfig.cmake\"\n  \"/opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcpp-extras.cmake\"\n  \"/opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcppConfig-version.cmake\"\n  \"/opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcppConfig.cmake\"\n  \"/usr/lib/cmake/eigen3/Eigen3Config.cmake\"\n  \"/usr/share/mrpt/MRPTConfig-version.cmake\"\n  \"/usr/share/mrpt/MRPTConfig.cmake\"\n  )\n\n# The corresponding makefile is:\nset(CMAKE_MAKEFILE_OUTPUTS\n  \"Makefile\"\n  \"CMakeFiles/cmake.check_cache\"\n  )\n\n# Byproducts of CMake generate step:\nset(CMAKE_MAKEFILE_PRODUCTS\n  \"CMakeFiles/3.9.6/CMakeSystem.cmake\"\n  \"CMakeFiles/3.9.6/CMakeCCompiler.cmake\"\n  \"CMakeFiles/3.9.6/CMakeCXXCompiler.cmake\"\n  \"CMakeFiles/3.9.6/CMakeCCompiler.cmake\"\n  \"CMakeFiles/3.9.6/CMakeCXXCompiler.cmake\"\n  \"catkin_generated/stamps/rf2o_laser_odometry/package.xml.stamp\"\n  \"catkin_generated/installspace/_setup_util.py\"\n  \"catkin_generated/stamps/rf2o_laser_odometry/_setup_util.py.stamp\"\n  \"catkin_generated/installspace/env.sh\"\n  \"catkin_generated/installspace/setup.bash\"\n  \"catkin_generated/installspace/setup.sh\"\n  \"catkin_generated/installspace/setup.zsh\"\n  \"catkin_generated/installspace/.rosinstall\"\n  \"catkin_generated/generate_cached_setup.py\"\n  \"catkin_generated/env_cached.sh\"\n  \"catkin_generated/stamps/rf2o_laser_odometry/interrogate_setup_dot_py.py.stamp\"\n  \"catkin_generated/stamps/rf2o_laser_odometry/package.xml.stamp\"\n  \"catkin_generated/pkg.develspace.context.pc.py\"\n  \"catkin_generated/stamps/rf2o_laser_odometry/pkg.pc.em.stamp\"\n  \"devel/share/rf2o_laser_odometry/cmake/rf2o_laser_odometryConfig.cmake\"\n  \"devel/share/rf2o_laser_odometry/cmake/rf2o_laser_odometryConfig-version.cmake\"\n  \"catkin_generated/pkg.installspace.context.pc.py\"\n  \"catkin_generated/stamps/rf2o_laser_odometry/pkg.pc.em.stamp\"\n  \"catkin_generated/installspace/rf2o_laser_odometryConfig.cmake\"\n  \"catkin_generated/installspace/rf2o_laser_odometryConfig-version.cmake\"\n  \"CMakeFiles/CMakeDirectoryInformation.cmake\"\n  )\n\n# Dependency information for all targets:\nset(CMAKE_DEPEND_INFO_FILES\n  \"CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/nav_msgs_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/tests.dir/DependInfo.cmake\"\n  \"CMakeFiles/rf2o_laser_odometry_node.dir/DependInfo.cmake\"\n  \"CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/nav_msgs_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/run_tests.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/clean_test_results.dir/DependInfo.cmake\"\n  \"CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/doxygen.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/nav_msgs_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/nav_msgs_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/nav_msgs_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake\"\n  \"CMakeFiles/download_extra_data.dir/DependInfo.cmake\"\n  \"CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake\"\n  \"CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake\"\n  \"CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake\"\n  \"CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake\"\n  )\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/Makefile2",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Default target executed when no arguments are given to make.\ndefault_target: all\n\n.PHONY : default_target\n\n# The main recursive all target\nall:\n\n.PHONY : all\n\n# The main recursive preinstall target\npreinstall:\n\n.PHONY : preinstall\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf2_msgs_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\ntf2_msgs_generate_messages_nodejs: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/rule\n\n.PHONY : tf2_msgs_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf2_msgs_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/tf2_msgs_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\ntf2_msgs_generate_messages_lisp: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/rule\n\n.PHONY : tf2_msgs_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf2_msgs_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/tf2_msgs_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf2_msgs_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/rule\n\n# Convenience name for target.\ntf2_msgs_generate_messages_eus: CMakeFiles/tf2_msgs_generate_messages_eus.dir/rule\n\n.PHONY : tf2_msgs_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/tf2_msgs_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf2_msgs_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/tf2_msgs_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\ntf2_msgs_generate_messages_cpp: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/rule\n\n.PHONY : tf2_msgs_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/rule\n\n# Convenience name for target.\nactionlib_generate_messages_py: CMakeFiles/actionlib_generate_messages_py.dir/rule\n\n.PHONY : actionlib_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/actionlib_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/rule\n\n# Convenience name for target.\nactionlib_generate_messages_eus: CMakeFiles/actionlib_generate_messages_eus.dir/rule\n\n.PHONY : actionlib_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/actionlib_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/nav_msgs_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/nav_msgs_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make CMakeFiles/nav_msgs_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make CMakeFiles/nav_msgs_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/nav_msgs_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/rule\n\n# Convenience name for target.\nnav_msgs_generate_messages_eus: CMakeFiles/nav_msgs_generate_messages_eus.dir/rule\n\n.PHONY : nav_msgs_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/nav_msgs_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make CMakeFiles/nav_msgs_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/nav_msgs_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/std_msgs_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/std_msgs_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/std_msgs_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/rule\n\n# Convenience name for target.\nstd_msgs_generate_messages_eus: CMakeFiles/std_msgs_generate_messages_eus.dir/rule\n\n.PHONY : std_msgs_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/std_msgs_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/std_msgs_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/roscpp_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/roscpp_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/roscpp_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\nroscpp_generate_messages_lisp: CMakeFiles/roscpp_generate_messages_lisp.dir/rule\n\n.PHONY : roscpp_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/roscpp_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/roscpp_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\nrosgraph_msgs_generate_messages_lisp: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/rule\n\n.PHONY : rosgraph_msgs_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tests.dir\n\n# All Build rule for target.\nCMakeFiles/tests.dir/all:\n\t$(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/depend\n\t$(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tests.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tests.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tests.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tests.dir/rule\n\n# Convenience name for target.\ntests: CMakeFiles/tests.dir/rule\n\n.PHONY : tests\n\n# clean rule for target.\nCMakeFiles/tests.dir/clean:\n\t$(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/clean\n.PHONY : CMakeFiles/tests.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tests.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/rf2o_laser_odometry_node.dir\n\n# All Build rule for target.\nCMakeFiles/rf2o_laser_odometry_node.dir/all:\n\t$(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/depend\n\t$(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/all\n\n# Include target in all.\nall: CMakeFiles/rf2o_laser_odometry_node.dir/all\n\n.PHONY : all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/rf2o_laser_odometry_node.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 2\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rf2o_laser_odometry_node.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/rule\n\n# Convenience name for target.\nrf2o_laser_odometry_node: CMakeFiles/rf2o_laser_odometry_node.dir/rule\n\n.PHONY : rf2o_laser_odometry_node\n\n# clean rule for target.\nCMakeFiles/rf2o_laser_odometry_node.dir/clean:\n\t$(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/clean\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/rf2o_laser_odometry_node.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/roscpp_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/roscpp_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/roscpp_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\nroscpp_generate_messages_nodejs: CMakeFiles/roscpp_generate_messages_nodejs.dir/rule\n\n.PHONY : roscpp_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/roscpp_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/roscpp_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/tf_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf_generate_messages_eus.dir/rule\n\n# Convenience name for target.\ntf_generate_messages_eus: CMakeFiles/tf_generate_messages_eus.dir/rule\n\n.PHONY : tf_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/tf_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/tf_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\nrosgraph_msgs_generate_messages_nodejs: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/rule\n\n.PHONY : rosgraph_msgs_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/nav_msgs_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/nav_msgs_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make CMakeFiles/nav_msgs_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make CMakeFiles/nav_msgs_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/nav_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\nnav_msgs_generate_messages_cpp: CMakeFiles/nav_msgs_generate_messages_cpp.dir/rule\n\n.PHONY : nav_msgs_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/nav_msgs_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/std_msgs_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/std_msgs_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/std_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\nstd_msgs_generate_messages_lisp: CMakeFiles/std_msgs_generate_messages_lisp.dir/rule\n\n.PHONY : std_msgs_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/std_msgs_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/std_msgs_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/geometry_msgs_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/geometry_msgs_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\ngeometry_msgs_generate_messages_lisp: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/rule\n\n.PHONY : geometry_msgs_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\nrosgraph_msgs_generate_messages_cpp: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/rule\n\n.PHONY : rosgraph_msgs_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/run_tests.dir\n\n# All Build rule for target.\nCMakeFiles/run_tests.dir/all:\n\t$(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/depend\n\t$(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/run_tests.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/run_tests.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/run_tests.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/run_tests.dir/rule\n\n# Convenience name for target.\nrun_tests: CMakeFiles/run_tests.dir/rule\n\n.PHONY : run_tests\n\n# clean rule for target.\nCMakeFiles/run_tests.dir/clean:\n\t$(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/clean\n.PHONY : CMakeFiles/run_tests.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/run_tests.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\nactionlib_generate_messages_lisp: CMakeFiles/actionlib_generate_messages_lisp.dir/rule\n\n.PHONY : actionlib_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/actionlib_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule\n\n# Convenience name for target.\nactionlib_msgs_generate_messages_eus: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/rule\n\n.PHONY : actionlib_msgs_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/roscpp_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/roscpp_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/roscpp_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/rule\n\n# Convenience name for target.\nroscpp_generate_messages_eus: CMakeFiles/roscpp_generate_messages_eus.dir/rule\n\n.PHONY : roscpp_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/roscpp_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/roscpp_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/roscpp_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/roscpp_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/roscpp_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\nroscpp_generate_messages_cpp: CMakeFiles/roscpp_generate_messages_cpp.dir/rule\n\n.PHONY : roscpp_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/roscpp_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/roscpp_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/geometry_msgs_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/geometry_msgs_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/geometry_msgs_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/rule\n\n# Convenience name for target.\ngeometry_msgs_generate_messages_eus: CMakeFiles/geometry_msgs_generate_messages_eus.dir/rule\n\n.PHONY : geometry_msgs_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/geometry_msgs_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_msgs_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/rule\n\n# Convenience name for target.\nactionlib_msgs_generate_messages_py: CMakeFiles/actionlib_msgs_generate_messages_py.dir/rule\n\n.PHONY : actionlib_msgs_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/clean_test_results.dir\n\n# All Build rule for target.\nCMakeFiles/clean_test_results.dir/all:\n\t$(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/depend\n\t$(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/clean_test_results.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/clean_test_results.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/clean_test_results.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/clean_test_results.dir/rule\n\n# Convenience name for target.\nclean_test_results: CMakeFiles/clean_test_results.dir/rule\n\n.PHONY : clean_test_results\n\n# clean rule for target.\nCMakeFiles/clean_test_results.dir/clean:\n\t$(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/clean\n.PHONY : CMakeFiles/clean_test_results.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/clean_test_results.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/geometry_msgs_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\ngeometry_msgs_generate_messages_nodejs: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/rule\n\n.PHONY : geometry_msgs_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule\n\n# Convenience name for target.\nrosgraph_msgs_generate_messages_eus: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/rule\n\n.PHONY : rosgraph_msgs_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/doxygen.dir\n\n# All Build rule for target.\nCMakeFiles/doxygen.dir/all:\n\t$(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/depend\n\t$(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/doxygen.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/doxygen.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/doxygen.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/doxygen.dir/rule\n\n# Convenience name for target.\ndoxygen: CMakeFiles/doxygen.dir/rule\n\n.PHONY : doxygen\n\n# clean rule for target.\nCMakeFiles/doxygen.dir/clean:\n\t$(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/clean\n.PHONY : CMakeFiles/doxygen.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/doxygen.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/tf_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\ntf_generate_messages_cpp: CMakeFiles/tf_generate_messages_cpp.dir/rule\n\n.PHONY : tf_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/tf_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/nav_msgs_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/nav_msgs_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make CMakeFiles/nav_msgs_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make CMakeFiles/nav_msgs_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/nav_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\nnav_msgs_generate_messages_lisp: CMakeFiles/nav_msgs_generate_messages_lisp.dir/rule\n\n.PHONY : nav_msgs_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/nav_msgs_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/nav_msgs_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/nav_msgs_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/nav_msgs_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/nav_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\nnav_msgs_generate_messages_nodejs: CMakeFiles/nav_msgs_generate_messages_nodejs.dir/rule\n\n.PHONY : nav_msgs_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/std_msgs_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/std_msgs_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/std_msgs_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/rule\n\n# Convenience name for target.\nstd_msgs_generate_messages_py: CMakeFiles/std_msgs_generate_messages_py.dir/rule\n\n.PHONY : std_msgs_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/std_msgs_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/std_msgs_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/nav_msgs_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/nav_msgs_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_py.dir/build.make CMakeFiles/nav_msgs_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_py.dir/build.make CMakeFiles/nav_msgs_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/nav_msgs_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/nav_msgs_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/rule\n\n# Convenience name for target.\nnav_msgs_generate_messages_py: CMakeFiles/nav_msgs_generate_messages_py.dir/rule\n\n.PHONY : nav_msgs_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/nav_msgs_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_py.dir/build.make CMakeFiles/nav_msgs_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/nav_msgs_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/geometry_msgs_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/geometry_msgs_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\ngeometry_msgs_generate_messages_cpp: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/rule\n\n.PHONY : geometry_msgs_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/sensor_msgs_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\nsensor_msgs_generate_messages_nodejs: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/rule\n\n.PHONY : sensor_msgs_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/std_msgs_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/std_msgs_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/std_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\nstd_msgs_generate_messages_nodejs: CMakeFiles/std_msgs_generate_messages_nodejs.dir/rule\n\n.PHONY : std_msgs_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/std_msgs_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/geometry_msgs_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/geometry_msgs_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/geometry_msgs_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/geometry_msgs_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/rule\n\n# Convenience name for target.\ngeometry_msgs_generate_messages_py: CMakeFiles/geometry_msgs_generate_messages_py.dir/rule\n\n.PHONY : geometry_msgs_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/geometry_msgs_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/geometry_msgs_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\nactionlib_msgs_generate_messages_lisp: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/rule\n\n.PHONY : actionlib_msgs_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf2_msgs_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/tf2_msgs_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf2_msgs_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf2_msgs_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/rule\n\n# Convenience name for target.\ntf2_msgs_generate_messages_py: CMakeFiles/tf2_msgs_generate_messages_py.dir/rule\n\n.PHONY : tf2_msgs_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/tf2_msgs_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf2_msgs_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\nactionlib_msgs_generate_messages_nodejs: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/rule\n\n.PHONY : actionlib_msgs_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/sensor_msgs_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/sensor_msgs_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\nsensor_msgs_generate_messages_cpp: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/rule\n\n.PHONY : sensor_msgs_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\nactionlib_generate_messages_nodejs: CMakeFiles/actionlib_generate_messages_nodejs.dir/rule\n\n.PHONY : actionlib_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/actionlib_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_msgs_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\nactionlib_msgs_generate_messages_cpp: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/rule\n\n.PHONY : actionlib_msgs_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/std_msgs_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/std_msgs_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/std_msgs_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/std_msgs_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\nstd_msgs_generate_messages_cpp: CMakeFiles/std_msgs_generate_messages_cpp.dir/rule\n\n.PHONY : std_msgs_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/std_msgs_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/std_msgs_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/sensor_msgs_generate_messages_eus.dir\n\n# All Build rule for target.\nCMakeFiles/sensor_msgs_generate_messages_eus.dir/all:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/sensor_msgs_generate_messages_eus.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_eus.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/rule\n\n# Convenience name for target.\nsensor_msgs_generate_messages_eus: CMakeFiles/sensor_msgs_generate_messages_eus.dir/rule\n\n.PHONY : sensor_msgs_generate_messages_eus\n\n# clean rule for target.\nCMakeFiles/sensor_msgs_generate_messages_eus.dir/clean:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/download_extra_data.dir\n\n# All Build rule for target.\nCMakeFiles/download_extra_data.dir/all:\n\t$(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/depend\n\t$(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/download_extra_data.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/download_extra_data.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/download_extra_data.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/download_extra_data.dir/rule\n\n# Convenience name for target.\ndownload_extra_data: CMakeFiles/download_extra_data.dir/rule\n\n.PHONY : download_extra_data\n\n# clean rule for target.\nCMakeFiles/download_extra_data.dir/clean:\n\t$(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/clean\n.PHONY : CMakeFiles/download_extra_data.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/download_extra_data.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/sensor_msgs_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/sensor_msgs_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\nsensor_msgs_generate_messages_lisp: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/rule\n\n.PHONY : sensor_msgs_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/actionlib_generate_messages_cpp.dir\n\n# All Build rule for target.\nCMakeFiles/actionlib_generate_messages_cpp.dir/all:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/depend\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/actionlib_generate_messages_cpp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/actionlib_generate_messages_cpp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/rule\n\n# Convenience name for target.\nactionlib_generate_messages_cpp: CMakeFiles/actionlib_generate_messages_cpp.dir/rule\n\n.PHONY : actionlib_generate_messages_cpp\n\n# clean rule for target.\nCMakeFiles/actionlib_generate_messages_cpp.dir/clean:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/clean\n.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/actionlib_generate_messages_cpp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/sensor_msgs_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/sensor_msgs_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/sensor_msgs_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/sensor_msgs_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/rule\n\n# Convenience name for target.\nsensor_msgs_generate_messages_py: CMakeFiles/sensor_msgs_generate_messages_py.dir/rule\n\n.PHONY : sensor_msgs_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/sensor_msgs_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/sensor_msgs_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/rosgraph_msgs_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/rosgraph_msgs_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule\n\n# Convenience name for target.\nrosgraph_msgs_generate_messages_py: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/rule\n\n.PHONY : rosgraph_msgs_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf_generate_messages_lisp.dir\n\n# All Build rule for target.\nCMakeFiles/tf_generate_messages_lisp.dir/all:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/depend\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf_generate_messages_lisp.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_lisp.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/rule\n\n# Convenience name for target.\ntf_generate_messages_lisp: CMakeFiles/tf_generate_messages_lisp.dir/rule\n\n.PHONY : tf_generate_messages_lisp\n\n# clean rule for target.\nCMakeFiles/tf_generate_messages_lisp.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/clean\n.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf_generate_messages_lisp.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/roscpp_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/roscpp_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/roscpp_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/roscpp_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/rule\n\n# Convenience name for target.\nroscpp_generate_messages_py: CMakeFiles/roscpp_generate_messages_py.dir/rule\n\n.PHONY : roscpp_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/roscpp_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/roscpp_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf_generate_messages_nodejs.dir\n\n# All Build rule for target.\nCMakeFiles/tf_generate_messages_nodejs.dir/all:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/depend\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf_generate_messages_nodejs.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_nodejs.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/rule\n\n# Convenience name for target.\ntf_generate_messages_nodejs: CMakeFiles/tf_generate_messages_nodejs.dir/rule\n\n.PHONY : tf_generate_messages_nodejs\n\n# clean rule for target.\nCMakeFiles/tf_generate_messages_nodejs.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/clean\n.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf_generate_messages_nodejs.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Target rules for target CMakeFiles/tf_generate_messages_py.dir\n\n# All Build rule for target.\nCMakeFiles/tf_generate_messages_py.dir/all:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/depend\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/build\n\t@$(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\"\n.PHONY : CMakeFiles/tf_generate_messages_py.dir/all\n\n# Build rule for subdir invocation for target.\nCMakeFiles/tf_generate_messages_py.dir/rule: cmake_check_build_system\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n\t$(MAKE) -f CMakeFiles/Makefile2 CMakeFiles/tf_generate_messages_py.dir/all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : CMakeFiles/tf_generate_messages_py.dir/rule\n\n# Convenience name for target.\ntf_generate_messages_py: CMakeFiles/tf_generate_messages_py.dir/rule\n\n.PHONY : tf_generate_messages_py\n\n# clean rule for target.\nCMakeFiles/tf_generate_messages_py.dir/clean:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/clean\n.PHONY : CMakeFiles/tf_generate_messages_py.dir/clean\n\n# clean rule for target.\nclean: CMakeFiles/tf_generate_messages_py.dir/clean\n\n.PHONY : clean\n\n#=============================================================================\n# Special targets to cleanup operation of make.\n\n# Special rule to run CMake to check the build system integrity.\n# No rule that depends on this can have commands that come from listfiles\n# because they might be regenerated.\ncmake_check_build_system:\n\t$(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0\n.PHONY : cmake_check_build_system\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/Progress/2",
    "content": "empty"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/Progress/count.txt",
    "content": "2\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/TargetDirectories.txt",
    "content": "/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/install/local.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/edit_cache.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/install/strip.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rebuild_cache.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/install.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/list_install_components.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/test.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir\n/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_generate_messages_cpp.dir/progress.make\n\nactionlib_generate_messages_cpp: CMakeFiles/actionlib_generate_messages_cpp.dir/build.make\n\n.PHONY : actionlib_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_generate_messages_cpp.dir/build: actionlib_generate_messages_cpp\n\n.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/build\n\nCMakeFiles/actionlib_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/clean\n\nCMakeFiles/actionlib_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_generate_messages_eus.dir/progress.make\n\nactionlib_generate_messages_eus: CMakeFiles/actionlib_generate_messages_eus.dir/build.make\n\n.PHONY : actionlib_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_generate_messages_eus.dir/build: actionlib_generate_messages_eus\n\n.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/build\n\nCMakeFiles/actionlib_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/clean\n\nCMakeFiles/actionlib_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_generate_messages_lisp.dir/progress.make\n\nactionlib_generate_messages_lisp: CMakeFiles/actionlib_generate_messages_lisp.dir/build.make\n\n.PHONY : actionlib_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_generate_messages_lisp.dir/build: actionlib_generate_messages_lisp\n\n.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/build\n\nCMakeFiles/actionlib_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/clean\n\nCMakeFiles/actionlib_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_generate_messages_nodejs.dir/progress.make\n\nactionlib_generate_messages_nodejs: CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make\n\n.PHONY : actionlib_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_generate_messages_nodejs.dir/build: actionlib_generate_messages_nodejs\n\n.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/build\n\nCMakeFiles/actionlib_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/clean\n\nCMakeFiles/actionlib_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_generate_messages_py.dir/progress.make\n\nactionlib_generate_messages_py: CMakeFiles/actionlib_generate_messages_py.dir/build.make\n\n.PHONY : actionlib_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_generate_messages_py.dir/build: actionlib_generate_messages_py\n\n.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/build\n\nCMakeFiles/actionlib_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/clean\n\nCMakeFiles/actionlib_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_msgs_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/progress.make\n\nactionlib_msgs_generate_messages_cpp: CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make\n\n.PHONY : actionlib_msgs_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build: actionlib_msgs_generate_messages_cpp\n\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build\n\nCMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/clean\n\nCMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_msgs_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_msgs_generate_messages_eus.dir/progress.make\n\nactionlib_msgs_generate_messages_eus: CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make\n\n.PHONY : actionlib_msgs_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_msgs_generate_messages_eus.dir/build: actionlib_msgs_generate_messages_eus\n\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build\n\nCMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/clean\n\nCMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_msgs_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/progress.make\n\nactionlib_msgs_generate_messages_lisp: CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make\n\n.PHONY : actionlib_msgs_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build: actionlib_msgs_generate_messages_lisp\n\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build\n\nCMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/clean\n\nCMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_msgs_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/progress.make\n\nactionlib_msgs_generate_messages_nodejs: CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make\n\n.PHONY : actionlib_msgs_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build: actionlib_msgs_generate_messages_nodejs\n\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build\n\nCMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/clean\n\nCMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for actionlib_msgs_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/actionlib_msgs_generate_messages_py.dir/progress.make\n\nactionlib_msgs_generate_messages_py: CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make\n\n.PHONY : actionlib_msgs_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/actionlib_msgs_generate_messages_py.dir/build: actionlib_msgs_generate_messages_py\n\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/build\n\nCMakeFiles/actionlib_msgs_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/clean\n\nCMakeFiles/actionlib_msgs_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/actionlib_msgs_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/actionlib_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/actionlib_msgs_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for clean_test_results.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/clean_test_results.dir/progress.make\n\nCMakeFiles/clean_test_results:\n\t/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\n\nclean_test_results: CMakeFiles/clean_test_results\nclean_test_results: CMakeFiles/clean_test_results.dir/build.make\n\n.PHONY : clean_test_results\n\n# Rule to build all files generated by this target.\nCMakeFiles/clean_test_results.dir/build: clean_test_results\n\n.PHONY : CMakeFiles/clean_test_results.dir/build\n\nCMakeFiles/clean_test_results.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/clean_test_results.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/clean_test_results.dir/clean\n\nCMakeFiles/clean_test_results.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/clean_test_results.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/cmake_clean.cmake",
    "content": "file(REMOVE_RECURSE\n  \"CMakeFiles/clean_test_results\"\n)\n\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/clean_test_results.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clean_test_results.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clion-environment.txt",
    "content": "Options: \n\nOptions:"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/clion-log.txt",
    "content": "/home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_BUILD_TYPE=Debug -G \"CodeBlocks - Unix Makefiles\" /home/zn/racecar/src/rf2o_laser_odometry\n-- The C compiler identification is GNU 5.4.0\n-- The CXX compiler identification is GNU 5.4.0\n-- Check for working C compiler: /usr/bin/cc\n-- Check for working C compiler: /usr/bin/cc -- works\n-- Detecting C compiler ABI info\n-- Detecting C compiler ABI info - done\n-- Detecting C compile features\n-- Detecting C compile features - done\n-- Check for working CXX compiler: /usr/bin/c++\n-- Check for working CXX compiler: /usr/bin/c++ -- works\n-- Detecting CXX compiler ABI info\n-- Detecting CXX compiler ABI info - done\n-- Detecting CXX compile features\n-- Detecting CXX compile features - done\n-- Using CATKIN_DEVEL_PREFIX: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel\n-- Using CMAKE_PREFIX_PATH: /home/zn/artrobot/devel;/opt/ros/kinetic\n-- This workspace overlays: /home/zn/artrobot/devel;/opt/ros/kinetic\n-- Found PythonInterp: /usr/bin/python (found version \"2.7.12\") \n-- Using PYTHON_EXECUTABLE: /usr/bin/python\n-- Using Debian Python package layout\n-- Using empy: /usr/bin/empy\n-- Using CATKIN_ENABLE_TESTING: ON\n-- Call enable_testing()\n-- Using CATKIN_TEST_RESULTS_DIR: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/test_results\n-- Found gtest: gtests will be built\n-- Using Python nosetests: /usr/bin/nosetests-2.7\n-- catkin 0.7.11\n-- Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy\n-- Boost version: 1.58.0\n-- Found the following Boost libraries:\n--   system\n-- Found MRPT: 1.3.2\n-- Configuring done\n-- Generating done\n-- Build files have been written to: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/cmake.check_cache",
    "content": "# This file is generated by cmake for dependency checking of the CMakeCache.txt file\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for download_extra_data.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/download_extra_data.dir/progress.make\n\ndownload_extra_data: CMakeFiles/download_extra_data.dir/build.make\n\n.PHONY : download_extra_data\n\n# Rule to build all files generated by this target.\nCMakeFiles/download_extra_data.dir/build: download_extra_data\n\n.PHONY : CMakeFiles/download_extra_data.dir/build\n\nCMakeFiles/download_extra_data.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/download_extra_data.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/download_extra_data.dir/clean\n\nCMakeFiles/download_extra_data.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/download_extra_data.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/download_extra_data.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/download_extra_data.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for doxygen.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/doxygen.dir/progress.make\n\ndoxygen: CMakeFiles/doxygen.dir/build.make\n\n.PHONY : doxygen\n\n# Rule to build all files generated by this target.\nCMakeFiles/doxygen.dir/build: doxygen\n\n.PHONY : CMakeFiles/doxygen.dir/build\n\nCMakeFiles/doxygen.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/doxygen.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/doxygen.dir/clean\n\nCMakeFiles/doxygen.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/doxygen.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/doxygen.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/doxygen.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.c",
    "content": "\n  const char features[] = {\"\\n\"\n\"C_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304\n\"1\"\n#else\n\"0\"\n#endif\n\"c_function_prototypes\\n\"\n\"C_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L\n\"1\"\n#else\n\"0\"\n#endif\n\"c_restrict\\n\"\n\"C_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 201000L\n\"1\"\n#else\n\"0\"\n#endif\n\"c_static_assert\\n\"\n\"C_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 304 && defined(__STDC_VERSION__) && __STDC_VERSION__ >= 199901L\n\"1\"\n#else\n\"0\"\n#endif\n\"c_variadic_macros\\n\"\n\n};\n\nint main(int argc, char** argv) { (void)argv; return features[argc]; }\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/feature_tests.cxx",
    "content": "\n  const char features[] = {\"\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 500 && __cplusplus >= 201402L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_aggregate_default_initializers\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_alias_templates\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_alignas\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_alignof\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_attributes\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_attribute_deprecated\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_auto_type\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_binary_literals\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_constexpr\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_contextual_conversions\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_decltype\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_decltype_auto\\n\"\n\"CXX_FEATURE:\"\n#if ((__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) >= 40801) && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_decltype_incomplete_return_types\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_default_function_template_args\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_defaulted_functions\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_defaulted_move_initializers\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_delegating_constructors\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_deleted_functions\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_digit_separators\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_enum_forward_declarations\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 405 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_explicit_conversions\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_extended_friend_declarations\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_extern_templates\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_final\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_func_identifier\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_generalized_initializers\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_generic_lambdas\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_inheriting_constructors\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_inline_namespaces\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 405 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_lambdas\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_lambda_init_captures\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 405 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_local_type_template_args\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_long_long_type\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_noexcept\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_nonstatic_member_init\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_nullptr\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_override\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_range_for\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 405 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_raw_string_literals\\n\"\n\"CXX_FEATURE:\"\n#if ((__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) >= 40801) && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_reference_qualified_functions\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 500 && __cplusplus >= 201402L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_relaxed_constexpr\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 409 && __cplusplus > 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_return_type_deduction\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_right_angle_brackets\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_rvalue_references\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_sizeof_member\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_static_assert\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_strong_enums\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && __cplusplus\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_template_template_parameters\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 408 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_thread_local\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_trailing_return_types\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_unicode_literals\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_uniform_initialization\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 406 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_unrestricted_unions\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 407 && __cplusplus >= 201103L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_user_literals\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 500 && __cplusplus >= 201402L\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_variable_templates\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_variadic_macros\\n\"\n\"CXX_FEATURE:\"\n#if (__GNUC__ * 100 + __GNUC_MINOR__) >= 404 && (__cplusplus >= 201103L || (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GXX_EXPERIMENTAL_CXX0X__))\n\"1\"\n#else\n\"0\"\n#endif\n\"cxx_variadic_templates\\n\"\n\n};\n\nint main(int argc, char** argv) { (void)argv; return features[argc]; }\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for geometry_msgs_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/geometry_msgs_generate_messages_cpp.dir/progress.make\n\ngeometry_msgs_generate_messages_cpp: CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make\n\n.PHONY : geometry_msgs_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/geometry_msgs_generate_messages_cpp.dir/build: geometry_msgs_generate_messages_cpp\n\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build\n\nCMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/clean\n\nCMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/geometry_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for geometry_msgs_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/geometry_msgs_generate_messages_eus.dir/progress.make\n\ngeometry_msgs_generate_messages_eus: CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make\n\n.PHONY : geometry_msgs_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/geometry_msgs_generate_messages_eus.dir/build: geometry_msgs_generate_messages_eus\n\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/build\n\nCMakeFiles/geometry_msgs_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/clean\n\nCMakeFiles/geometry_msgs_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/geometry_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for geometry_msgs_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/geometry_msgs_generate_messages_lisp.dir/progress.make\n\ngeometry_msgs_generate_messages_lisp: CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make\n\n.PHONY : geometry_msgs_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/geometry_msgs_generate_messages_lisp.dir/build: geometry_msgs_generate_messages_lisp\n\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build\n\nCMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/clean\n\nCMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/geometry_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for geometry_msgs_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/progress.make\n\ngeometry_msgs_generate_messages_nodejs: CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make\n\n.PHONY : geometry_msgs_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build: geometry_msgs_generate_messages_nodejs\n\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build\n\nCMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/clean\n\nCMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for geometry_msgs_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/geometry_msgs_generate_messages_py.dir/progress.make\n\ngeometry_msgs_generate_messages_py: CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make\n\n.PHONY : geometry_msgs_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/geometry_msgs_generate_messages_py.dir/build: geometry_msgs_generate_messages_py\n\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/build\n\nCMakeFiles/geometry_msgs_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/clean\n\nCMakeFiles/geometry_msgs_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/geometry_msgs_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/geometry_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/geometry_msgs_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for nav_msgs_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/nav_msgs_generate_messages_cpp.dir/progress.make\n\nnav_msgs_generate_messages_cpp: CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make\n\n.PHONY : nav_msgs_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/nav_msgs_generate_messages_cpp.dir/build: nav_msgs_generate_messages_cpp\n\n.PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/build\n\nCMakeFiles/nav_msgs_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/clean\n\nCMakeFiles/nav_msgs_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/nav_msgs_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/nav_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for nav_msgs_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/nav_msgs_generate_messages_eus.dir/progress.make\n\nnav_msgs_generate_messages_eus: CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make\n\n.PHONY : nav_msgs_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/nav_msgs_generate_messages_eus.dir/build: nav_msgs_generate_messages_eus\n\n.PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/build\n\nCMakeFiles/nav_msgs_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/clean\n\nCMakeFiles/nav_msgs_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/nav_msgs_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/nav_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for nav_msgs_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/nav_msgs_generate_messages_lisp.dir/progress.make\n\nnav_msgs_generate_messages_lisp: CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make\n\n.PHONY : nav_msgs_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/nav_msgs_generate_messages_lisp.dir/build: nav_msgs_generate_messages_lisp\n\n.PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/build\n\nCMakeFiles/nav_msgs_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/clean\n\nCMakeFiles/nav_msgs_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/nav_msgs_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/nav_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for nav_msgs_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/nav_msgs_generate_messages_nodejs.dir/progress.make\n\nnav_msgs_generate_messages_nodejs: CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make\n\n.PHONY : nav_msgs_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/nav_msgs_generate_messages_nodejs.dir/build: nav_msgs_generate_messages_nodejs\n\n.PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build\n\nCMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/clean\n\nCMakeFiles/nav_msgs_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/nav_msgs_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/nav_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for nav_msgs_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/nav_msgs_generate_messages_py.dir/progress.make\n\nnav_msgs_generate_messages_py: CMakeFiles/nav_msgs_generate_messages_py.dir/build.make\n\n.PHONY : nav_msgs_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/nav_msgs_generate_messages_py.dir/build: nav_msgs_generate_messages_py\n\n.PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/build\n\nCMakeFiles/nav_msgs_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/nav_msgs_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/clean\n\nCMakeFiles/nav_msgs_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/nav_msgs_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/nav_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/nav_msgs_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/progress.marks",
    "content": "2\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/CXX.includecache",
    "content": "#IncludeRegexLine: ^[ \t]*[#%][ \t]*(include|import)[ \t]*[<\"]([^\">]+)([\">])\n\n#IncludeRegexScan: ^.*$\n\n#IncludeRegexComplain: ^$\n\n#IncludeRegexTransform: \n\n../include/rf2o_laser_odometry/CLaserOdometry2D.h\nros/ros.h\n-\ntf/transform_broadcaster.h\n-\ntf/transform_listener.h\n-\nnav_msgs/Odometry.h\n-\nsensor_msgs/LaserScan.h\n-\ngeometry_msgs/Twist.h\n-\nmrpt/version.h\n-\nmrpt/obs/CObservation2DRangeScan.h\n-\nmrpt/obs/CObservationOdometry.h\n-\nmrpt/utils/CTicTac.h\n-\nmrpt/slam/CObservation2DRangeScan.h\n-\nmrpt/slam/CObservationOdometry.h\n-\nmrpt/utils.h\n-\nmrpt/system/threads.h\n-\nmrpt/system/os.h\n-\nmrpt/poses/CPose3D.h\n-\nmrpt/opengl.h\n-\nmrpt/math/CHistogram.h\n-\nboost/bind.hpp\n-\nEigen/Dense\n-\nunsupported/Eigen/MatrixFunctions\n-\niostream\n-\nfstream\n-\nnumeric\n-\n\n/home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp\nrf2o_laser_odometry/CLaserOdometry2D.h\n/home/zn/racecar/src/rf2o_laser_odometry/src/rf2o_laser_odometry/CLaserOdometry2D.h\n\n/opt/ros/kinetic/include/boost_161_condition_variable.h\nboost/thread/detail/platform.hpp\n-\nboost/thread/win32/condition_variable.hpp\n-\nboost_161_pthread_condition_variable.h\n/opt/ros/kinetic/include/boost_161_pthread_condition_variable.h\n\n/opt/ros/kinetic/include/boost_161_pthread_condition_variable.h\nboost_161_pthread_condition_variable_fwd.h\n/opt/ros/kinetic/include/boost_161_pthread_condition_variable_fwd.h\nboost/thread/pthread/timespec.hpp\n-\nboost/thread/pthread/pthread_mutex_scoped_lock.hpp\n-\nboost/thread/pthread/thread_data.hpp\n-\nboost/chrono/system_clocks.hpp\n-\nboost/chrono/ceil.hpp\n-\nboost/thread/detail/delete.hpp\n-\nboost/config/abi_prefix.hpp\n-\nboost/config/abi_suffix.hpp\n-\n\n/opt/ros/kinetic/include/boost_161_pthread_condition_variable_fwd.h\nboost/assert.hpp\n-\nboost/throw_exception.hpp\n-\npthread.h\n-\nboost/thread/cv_status.hpp\n-\nboost/thread/mutex.hpp\n-\nboost/thread/lock_types.hpp\n-\nboost/thread/thread_time.hpp\n-\nboost/thread/pthread/timespec.hpp\n-\nboost/thread/xtime.hpp\n-\nboost/chrono/system_clocks.hpp\n-\nboost/chrono/ceil.hpp\n-\nboost/thread/detail/delete.hpp\n-\nboost/date_time/posix_time/posix_time_duration.hpp\n-\nboost/config/abi_prefix.hpp\n-\nboost/config/abi_suffix.hpp\n-\n\n/opt/ros/kinetic/include/geometry_msgs/Point.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/Point32.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/PointStamped.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\ngeometry_msgs/Point.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/Pose.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\ngeometry_msgs/Point.h\n-\ngeometry_msgs/Quaternion.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/PoseStamped.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\ngeometry_msgs/Pose.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/PoseWithCovariance.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\ngeometry_msgs/Pose.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/Quaternion.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/QuaternionStamped.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\ngeometry_msgs/Quaternion.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/Transform.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\ngeometry_msgs/Vector3.h\n-\ngeometry_msgs/Quaternion.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/TransformStamped.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\ngeometry_msgs/Transform.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/Twist.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\ngeometry_msgs/Vector3.h\n-\ngeometry_msgs/Vector3.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/TwistStamped.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\ngeometry_msgs/Twist.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/TwistWithCovariance.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\ngeometry_msgs/Twist.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/Vector3.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/geometry_msgs/Vector3Stamped.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\ngeometry_msgs/Vector3.h\n-\n\n/opt/ros/kinetic/include/nav_msgs/Odometry.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\ngeometry_msgs/PoseWithCovariance.h\n-\ngeometry_msgs/TwistWithCovariance.h\n-\n\n/opt/ros/kinetic/include/ros/advertise_options.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/message_traits.h\n/opt/ros/kinetic/include/ros/ros/message_traits.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\n\n/opt/ros/kinetic/include/ros/advertise_service_options.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/service_callback_helper.h\n/opt/ros/kinetic/include/ros/ros/service_callback_helper.h\nros/service_traits.h\n/opt/ros/kinetic/include/ros/ros/service_traits.h\nros/message_traits.h\n/opt/ros/kinetic/include/ros/ros/message_traits.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\n\n/opt/ros/kinetic/include/ros/assert.h\nros/console.h\n/opt/ros/kinetic/include/ros/ros/console.h\nros/static_assert.h\n/opt/ros/kinetic/include/ros/ros/static_assert.h\nros/platform.h\n-\nstdlib.h\n-\n\n/opt/ros/kinetic/include/ros/builtin_message_traits.h\nmessage_traits.h\n/opt/ros/kinetic/include/ros/message_traits.h\nros/time.h\n/opt/ros/kinetic/include/ros/ros/time.h\n\n/opt/ros/kinetic/include/ros/callback_queue.h\nboost/version.hpp\n-\nboost_161_condition_variable.h\n/opt/ros/kinetic/include/ros/boost_161_condition_variable.h\nboost/thread/condition_variable.hpp\n-\nboost/thread/condition_variable.hpp\n-\nros/callback_queue_interface.h\n/opt/ros/kinetic/include/ros/ros/callback_queue_interface.h\nros/time.h\n/opt/ros/kinetic/include/ros/ros/time.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nboost/shared_ptr.hpp\n-\nboost/thread/mutex.hpp\n-\nboost/thread/shared_mutex.hpp\n-\nboost/thread/tss.hpp\n-\nlist\n-\ndeque\n-\n\n/opt/ros/kinetic/include/ros/callback_queue_interface.h\nboost/shared_ptr.hpp\n-\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/types.h\n/opt/ros/kinetic/include/ros/ros/types.h\n\n/opt/ros/kinetic/include/ros/common.h\nstdint.h\n-\nassert.h\n-\nstddef.h\n-\nstring\n-\nros/assert.h\n/opt/ros/kinetic/include/ros/ros/assert.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/serialized_message.h\n/opt/ros/kinetic/include/ros/ros/serialized_message.h\nboost/shared_array.hpp\n-\nros/macros.h\n-\n\n/opt/ros/kinetic/include/ros/console.h\nconsole_backend.h\n/opt/ros/kinetic/include/ros/console_backend.h\ncstdio\n-\nsstream\n-\nros/time.h\n-\ncstdarg\n-\nros/macros.h\n-\nmap\n-\nvector\n-\nlog4cxx/level.h\n/opt/ros/kinetic/include/ros/log4cxx/level.h\nrosconsole/macros_generated.h\n/opt/ros/kinetic/include/ros/rosconsole/macros_generated.h\n\n/opt/ros/kinetic/include/ros/console_backend.h\n\n/opt/ros/kinetic/include/ros/datatypes.h\nstring\n-\nvector\n-\nmap\n-\nset\n-\nlist\n-\nboost/shared_ptr.hpp\n-\n\n/opt/ros/kinetic/include/ros/duration.h\niostream\n-\nmath.h\n-\nstdexcept\n-\nclimits\n-\nstdint.h\n-\nrostime_decl.h\n/opt/ros/kinetic/include/ros/rostime_decl.h\n\n/opt/ros/kinetic/include/ros/exception.h\nstdexcept\n-\n\n/opt/ros/kinetic/include/ros/exceptions.h\nros/exception.h\n-\n\n/opt/ros/kinetic/include/ros/forwards.h\nstring\n-\nvector\n-\nmap\n-\nset\n-\nlist\n-\nboost/shared_ptr.hpp\n-\nboost/make_shared.hpp\n-\nboost/weak_ptr.hpp\n-\nboost/function.hpp\n-\nros/time.h\n-\nros/macros.h\n-\nexceptions.h\n/opt/ros/kinetic/include/ros/exceptions.h\nros/datatypes.h\n/opt/ros/kinetic/include/ros/ros/datatypes.h\n\n/opt/ros/kinetic/include/ros/init.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/spinner.h\n/opt/ros/kinetic/include/ros/ros/spinner.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\n\n/opt/ros/kinetic/include/ros/macros.h\n\n/opt/ros/kinetic/include/ros/master.h\nforwards.h\n/opt/ros/kinetic/include/ros/forwards.h\nxmlrpcpp/XmlRpcValue.h\n/opt/ros/kinetic/include/ros/xmlrpcpp/XmlRpcValue.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\n\n/opt/ros/kinetic/include/ros/message.h\nros/macros.h\n/opt/ros/kinetic/include/ros/ros/macros.h\nros/assert.h\n/opt/ros/kinetic/include/ros/ros/assert.h\nstring\n-\nstring.h\n-\nboost/shared_ptr.hpp\n-\nboost/array.hpp\n-\nstdint.h\n-\n\n/opt/ros/kinetic/include/ros/message_event.h\nros/time.h\n/opt/ros/kinetic/include/ros/ros/time.h\nros/datatypes.h\n-\nros/message_traits.h\n-\nboost/type_traits/is_void.hpp\n-\nboost/type_traits/is_base_of.hpp\n-\nboost/type_traits/is_const.hpp\n-\nboost/type_traits/add_const.hpp\n-\nboost/type_traits/remove_const.hpp\n-\nboost/utility/enable_if.hpp\n-\nboost/function.hpp\n-\nboost/make_shared.hpp\n-\n\n/opt/ros/kinetic/include/ros/message_forward.h\ncstddef\n-\nmemory\n-\n\n/opt/ros/kinetic/include/ros/message_operations.h\nostream\n-\n\n/opt/ros/kinetic/include/ros/message_traits.h\nmessage_forward.h\n/opt/ros/kinetic/include/ros/message_forward.h\nros/time.h\n-\nstring\n-\nboost/utility/enable_if.hpp\n-\nboost/type_traits/remove_const.hpp\n-\nboost/type_traits/remove_reference.hpp\n-\n\n/opt/ros/kinetic/include/ros/names.h\nforwards.h\n/opt/ros/kinetic/include/ros/forwards.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\n\n/opt/ros/kinetic/include/ros/node_handle.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/publisher.h\n/opt/ros/kinetic/include/ros/ros/publisher.h\nros/subscriber.h\n/opt/ros/kinetic/include/ros/ros/subscriber.h\nros/service_server.h\n/opt/ros/kinetic/include/ros/ros/service_server.h\nros/service_client.h\n/opt/ros/kinetic/include/ros/ros/service_client.h\nros/timer.h\n/opt/ros/kinetic/include/ros/ros/timer.h\nros/rate.h\n/opt/ros/kinetic/include/ros/ros/rate.h\nros/wall_timer.h\n/opt/ros/kinetic/include/ros/ros/wall_timer.h\nros/steady_timer.h\n/opt/ros/kinetic/include/ros/ros/steady_timer.h\nros/advertise_options.h\n/opt/ros/kinetic/include/ros/ros/advertise_options.h\nros/advertise_service_options.h\n/opt/ros/kinetic/include/ros/ros/advertise_service_options.h\nros/subscribe_options.h\n/opt/ros/kinetic/include/ros/ros/subscribe_options.h\nros/service_client_options.h\n/opt/ros/kinetic/include/ros/ros/service_client_options.h\nros/timer_options.h\n/opt/ros/kinetic/include/ros/ros/timer_options.h\nros/wall_timer_options.h\n/opt/ros/kinetic/include/ros/ros/wall_timer_options.h\nros/spinner.h\n/opt/ros/kinetic/include/ros/ros/spinner.h\nros/init.h\n/opt/ros/kinetic/include/ros/ros/init.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nboost/bind.hpp\n-\nxmlrpcpp/XmlRpcValue.h\n-\n\n/opt/ros/kinetic/include/ros/param.h\nforwards.h\n/opt/ros/kinetic/include/ros/forwards.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nxmlrpcpp/XmlRpcValue.h\n/opt/ros/kinetic/include/ros/xmlrpcpp/XmlRpcValue.h\nvector\n-\nmap\n-\n\n/opt/ros/kinetic/include/ros/parameter_adapter.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/message_event.h\n/opt/ros/kinetic/include/ros/ros/message_event.h\nros/static_assert.h\n-\nboost/type_traits/add_const.hpp\n-\nboost/type_traits/remove_const.hpp\n-\nboost/type_traits/remove_reference.hpp\n-\n\n/opt/ros/kinetic/include/ros/platform.h\nwindows.h\n-\nstdlib.h\n-\nstring\n-\n\n/opt/ros/kinetic/include/ros/publisher.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/common.h\n/opt/ros/kinetic/include/ros/ros/common.h\nros/message.h\n/opt/ros/kinetic/include/ros/ros/message.h\nros/serialization.h\n/opt/ros/kinetic/include/ros/ros/serialization.h\nboost/bind.hpp\n-\n\n/opt/ros/kinetic/include/ros/rate.h\nros/time.h\n/opt/ros/kinetic/include/ros/ros/time.h\nrostime_decl.h\n/opt/ros/kinetic/include/ros/rostime_decl.h\n\n/opt/ros/kinetic/include/ros/ros.h\nros/time.h\n/opt/ros/kinetic/include/ros/ros/time.h\nros/rate.h\n/opt/ros/kinetic/include/ros/ros/rate.h\nros/console.h\n/opt/ros/kinetic/include/ros/ros/console.h\nros/assert.h\n/opt/ros/kinetic/include/ros/ros/assert.h\nros/common.h\n/opt/ros/kinetic/include/ros/ros/common.h\nros/types.h\n/opt/ros/kinetic/include/ros/ros/types.h\nros/node_handle.h\n/opt/ros/kinetic/include/ros/ros/node_handle.h\nros/publisher.h\n/opt/ros/kinetic/include/ros/ros/publisher.h\nros/single_subscriber_publisher.h\n/opt/ros/kinetic/include/ros/ros/single_subscriber_publisher.h\nros/service_server.h\n/opt/ros/kinetic/include/ros/ros/service_server.h\nros/subscriber.h\n/opt/ros/kinetic/include/ros/ros/subscriber.h\nros/service.h\n/opt/ros/kinetic/include/ros/ros/service.h\nros/init.h\n/opt/ros/kinetic/include/ros/ros/init.h\nros/master.h\n/opt/ros/kinetic/include/ros/ros/master.h\nros/this_node.h\n/opt/ros/kinetic/include/ros/ros/this_node.h\nros/param.h\n/opt/ros/kinetic/include/ros/ros/param.h\nros/topic.h\n/opt/ros/kinetic/include/ros/ros/topic.h\nros/names.h\n/opt/ros/kinetic/include/ros/ros/names.h\n\n/opt/ros/kinetic/include/ros/roscpp_serialization_macros.h\nros/macros.h\n-\n\n/opt/ros/kinetic/include/ros/rostime_decl.h\nros/macros.h\n-\n\n/opt/ros/kinetic/include/ros/serialization.h\nroscpp_serialization_macros.h\n/opt/ros/kinetic/include/ros/roscpp_serialization_macros.h\nros/types.h\n-\nros/time.h\n-\nserialized_message.h\n/opt/ros/kinetic/include/ros/serialized_message.h\nros/message_traits.h\n/opt/ros/kinetic/include/ros/ros/message_traits.h\nros/builtin_message_traits.h\n/opt/ros/kinetic/include/ros/ros/builtin_message_traits.h\nros/exception.h\n/opt/ros/kinetic/include/ros/ros/exception.h\nros/datatypes.h\n/opt/ros/kinetic/include/ros/ros/datatypes.h\nvector\n-\nmap\n-\nboost/array.hpp\n-\nboost/call_traits.hpp\n-\nboost/utility/enable_if.hpp\n-\nboost/mpl/and.hpp\n-\nboost/mpl/or.hpp\n-\nboost/mpl/not.hpp\n-\ncstring\n-\n\n/opt/ros/kinetic/include/ros/serialized_message.h\nroscpp_serialization_macros.h\n/opt/ros/kinetic/include/ros/roscpp_serialization_macros.h\nboost/shared_array.hpp\n-\nboost/shared_ptr.hpp\n-\n\n/opt/ros/kinetic/include/ros/service.h\nstring\n-\nros/common.h\n/opt/ros/kinetic/include/ros/ros/common.h\nros/message.h\n/opt/ros/kinetic/include/ros/ros/message.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/node_handle.h\n/opt/ros/kinetic/include/ros/ros/node_handle.h\nros/service_traits.h\n/opt/ros/kinetic/include/ros/ros/service_traits.h\nros/names.h\n/opt/ros/kinetic/include/ros/ros/names.h\nboost/shared_ptr.hpp\n-\n\n/opt/ros/kinetic/include/ros/service_callback_helper.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/common.h\n/opt/ros/kinetic/include/ros/ros/common.h\nros/message.h\n/opt/ros/kinetic/include/ros/ros/message.h\nros/message_traits.h\n/opt/ros/kinetic/include/ros/ros/message_traits.h\nros/service_traits.h\n/opt/ros/kinetic/include/ros/ros/service_traits.h\nros/serialization.h\n/opt/ros/kinetic/include/ros/ros/serialization.h\nboost/type_traits/is_base_of.hpp\n-\nboost/utility/enable_if.hpp\n-\n\n/opt/ros/kinetic/include/ros/service_client.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/common.h\n/opt/ros/kinetic/include/ros/ros/common.h\nros/service_traits.h\n/opt/ros/kinetic/include/ros/ros/service_traits.h\nros/serialization.h\n/opt/ros/kinetic/include/ros/ros/serialization.h\n\n/opt/ros/kinetic/include/ros/service_client_options.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/service_traits.h\n/opt/ros/kinetic/include/ros/ros/service_traits.h\n\n/opt/ros/kinetic/include/ros/service_server.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\n\n/opt/ros/kinetic/include/ros/service_traits.h\nboost/type_traits/remove_reference.hpp\n-\nboost/type_traits/remove_const.hpp\n-\n\n/opt/ros/kinetic/include/ros/single_subscriber_publisher.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/serialization.h\n/opt/ros/kinetic/include/ros/ros/serialization.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nboost/utility.hpp\n-\n\n/opt/ros/kinetic/include/ros/spinner.h\nros/types.h\n/opt/ros/kinetic/include/ros/ros/types.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nboost/shared_ptr.hpp\n-\n\n/opt/ros/kinetic/include/ros/static_assert.h\nboost/static_assert.hpp\n-\n\n/opt/ros/kinetic/include/ros/steady_timer.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nforwards.h\n/opt/ros/kinetic/include/ros/forwards.h\nsteady_timer_options.h\n/opt/ros/kinetic/include/ros/steady_timer_options.h\n\n/opt/ros/kinetic/include/ros/steady_timer_options.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\n\n/opt/ros/kinetic/include/ros/subscribe_options.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/transport_hints.h\n/opt/ros/kinetic/include/ros/ros/transport_hints.h\nros/message_traits.h\n/opt/ros/kinetic/include/ros/ros/message_traits.h\nsubscription_callback_helper.h\n/opt/ros/kinetic/include/ros/subscription_callback_helper.h\n\n/opt/ros/kinetic/include/ros/subscriber.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/subscription_callback_helper.h\n/opt/ros/kinetic/include/ros/ros/subscription_callback_helper.h\n\n/opt/ros/kinetic/include/ros/subscription_callback_helper.h\ntypeinfo\n-\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nros/parameter_adapter.h\n/opt/ros/kinetic/include/ros/ros/parameter_adapter.h\nros/message_traits.h\n/opt/ros/kinetic/include/ros/ros/message_traits.h\nros/builtin_message_traits.h\n/opt/ros/kinetic/include/ros/ros/builtin_message_traits.h\nros/serialization.h\n/opt/ros/kinetic/include/ros/ros/serialization.h\nros/message_event.h\n/opt/ros/kinetic/include/ros/ros/message_event.h\nros/static_assert.h\n-\nboost/type_traits/add_const.hpp\n-\nboost/type_traits/remove_const.hpp\n-\nboost/type_traits/remove_reference.hpp\n-\nboost/type_traits/is_base_of.hpp\n-\nboost/utility/enable_if.hpp\n-\nboost/make_shared.hpp\n-\n\n/opt/ros/kinetic/include/ros/this_node.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nforwards.h\n/opt/ros/kinetic/include/ros/forwards.h\n\n/opt/ros/kinetic/include/ros/time.h\nros/platform.h\n-\niostream\n-\ncmath\n-\nros/exception.h\n-\nduration.h\n/opt/ros/kinetic/include/ros/duration.h\nboost/math/special_functions/round.hpp\n-\nrostime_decl.h\n/opt/ros/kinetic/include/ros/rostime_decl.h\nsys/timeb.h\n-\nsys/time.h\n-\n\n/opt/ros/kinetic/include/ros/timer.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nforwards.h\n/opt/ros/kinetic/include/ros/forwards.h\ntimer_options.h\n/opt/ros/kinetic/include/ros/timer_options.h\n\n/opt/ros/kinetic/include/ros/timer_options.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\n\n/opt/ros/kinetic/include/ros/topic.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nnode_handle.h\n/opt/ros/kinetic/include/ros/node_handle.h\nboost/shared_ptr.hpp\n-\n\n/opt/ros/kinetic/include/ros/transport_hints.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\nboost/lexical_cast.hpp\n-\n\n/opt/ros/kinetic/include/ros/types.h\nstdint.h\n-\n\n/opt/ros/kinetic/include/ros/wall_timer.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nforwards.h\n/opt/ros/kinetic/include/ros/forwards.h\nwall_timer_options.h\n/opt/ros/kinetic/include/ros/wall_timer_options.h\n\n/opt/ros/kinetic/include/ros/wall_timer_options.h\ncommon.h\n/opt/ros/kinetic/include/ros/common.h\nros/forwards.h\n/opt/ros/kinetic/include/ros/ros/forwards.h\n\n/opt/ros/kinetic/include/rosconsole/macros_generated.h\n\n/opt/ros/kinetic/include/sensor_msgs/ChannelFloat32.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/sensor_msgs/LaserScan.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\n\n/opt/ros/kinetic/include/sensor_msgs/PointCloud.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\nstd_msgs/Header.h\n-\ngeometry_msgs/Point32.h\n-\nsensor_msgs/ChannelFloat32.h\n-\n\n/opt/ros/kinetic/include/std_msgs/Empty.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/std_msgs/Header.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/tf/FrameGraph.h\nros/service_traits.h\n-\ntf/FrameGraphRequest.h\n-\ntf/FrameGraphResponse.h\n-\n\n/opt/ros/kinetic/include/tf/FrameGraphRequest.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/tf/FrameGraphResponse.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/tf/LinearMath/Matrix3x3.h\nVector3.h\n/opt/ros/kinetic/include/tf/LinearMath/Vector3.h\nQuaternion.h\n/opt/ros/kinetic/include/tf/LinearMath/Quaternion.h\n\n/opt/ros/kinetic/include/tf/LinearMath/MinMax.h\n\n/opt/ros/kinetic/include/tf/LinearMath/QuadWord.h\nScalar.h\n/opt/ros/kinetic/include/tf/LinearMath/Scalar.h\nMinMax.h\n/opt/ros/kinetic/include/tf/LinearMath/MinMax.h\naltivec.h\n-\n\n/opt/ros/kinetic/include/tf/LinearMath/Quaternion.h\nVector3.h\n/opt/ros/kinetic/include/tf/LinearMath/Vector3.h\nQuadWord.h\n/opt/ros/kinetic/include/tf/LinearMath/QuadWord.h\n\n/opt/ros/kinetic/include/tf/LinearMath/Scalar.h\nmath.h\n-\nstdlib.h\n-\ncstdlib\n-\ncfloat\n-\nfloat.h\n-\nppcintrinsics.h\n-\nassert.h\n-\nassert.h\n-\nassert.h\n-\nassert.h\n-\n\n/opt/ros/kinetic/include/tf/LinearMath/Transform.h\nMatrix3x3.h\n/opt/ros/kinetic/include/tf/LinearMath/Matrix3x3.h\n\n/opt/ros/kinetic/include/tf/LinearMath/Vector3.h\nScalar.h\n/opt/ros/kinetic/include/tf/LinearMath/Scalar.h\nMinMax.h\n/opt/ros/kinetic/include/tf/LinearMath/MinMax.h\n\n/opt/ros/kinetic/include/tf/exceptions.h\nstdexcept\n-\ntf2/exceptions.h\n-\n\n/opt/ros/kinetic/include/tf/tf.h\niostream\n-\niomanip\n-\ncmath\n-\nvector\n-\nsstream\n-\nmap\n-\ntf/exceptions.h\n-\ntf/time_cache.h\n/opt/ros/kinetic/include/tf/tf/time_cache.h\nboost/unordered_map.hpp\n-\nboost/signals2.hpp\n-\ngeometry_msgs/TwistStamped.h\n/opt/ros/kinetic/include/tf/geometry_msgs/TwistStamped.h\ntf2_ros/buffer.h\n-\n\n/opt/ros/kinetic/include/tf/tfMessage.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\ngeometry_msgs/TransformStamped.h\n-\n\n/opt/ros/kinetic/include/tf/time_cache.h\nset\n-\nboost/thread/mutex.hpp\n-\ntf/transform_datatypes.h\n/opt/ros/kinetic/include/tf/tf/transform_datatypes.h\ntf/exceptions.h\n/opt/ros/kinetic/include/tf/tf/exceptions.h\ntf/LinearMath/Transform.h\n/opt/ros/kinetic/include/tf/tf/LinearMath/Transform.h\nsstream\n-\n\n/opt/ros/kinetic/include/tf/transform_broadcaster.h\ntf/tf.h\n/opt/ros/kinetic/include/tf/tf/tf.h\ntf/tfMessage.h\n/opt/ros/kinetic/include/tf/tf/tfMessage.h\ntf2_ros/transform_broadcaster.h\n-\n\n/opt/ros/kinetic/include/tf/transform_datatypes.h\nstring\n-\ngeometry_msgs/PointStamped.h\n/opt/ros/kinetic/include/tf/geometry_msgs/PointStamped.h\ngeometry_msgs/Vector3Stamped.h\n/opt/ros/kinetic/include/tf/geometry_msgs/Vector3Stamped.h\ngeometry_msgs/QuaternionStamped.h\n/opt/ros/kinetic/include/tf/geometry_msgs/QuaternionStamped.h\ngeometry_msgs/TransformStamped.h\n/opt/ros/kinetic/include/tf/geometry_msgs/TransformStamped.h\ngeometry_msgs/PoseStamped.h\n/opt/ros/kinetic/include/tf/geometry_msgs/PoseStamped.h\ntf/LinearMath/Transform.h\n/opt/ros/kinetic/include/tf/tf/LinearMath/Transform.h\nros/time.h\n/opt/ros/kinetic/include/tf/ros/time.h\nros/console.h\n/opt/ros/kinetic/include/tf/ros/console.h\n\n/opt/ros/kinetic/include/tf/transform_listener.h\nsensor_msgs/PointCloud.h\n/opt/ros/kinetic/include/tf/sensor_msgs/PointCloud.h\nstd_msgs/Empty.h\n/opt/ros/kinetic/include/tf/std_msgs/Empty.h\ntf/tfMessage.h\n/opt/ros/kinetic/include/tf/tf/tfMessage.h\ntf/tf.h\n/opt/ros/kinetic/include/tf/tf/tf.h\nros/ros.h\n/opt/ros/kinetic/include/tf/ros/ros.h\nros/callback_queue.h\n/opt/ros/kinetic/include/tf/ros/callback_queue.h\ntf/FrameGraph.h\n/opt/ros/kinetic/include/tf/tf/FrameGraph.h\nboost/thread.hpp\n/opt/ros/kinetic/include/tf/boost/thread.hpp\ntf2_ros/transform_listener.h\n-\n\n/opt/ros/kinetic/include/tf2/LinearMath/Quaternion.h\nVector3.h\n/opt/ros/kinetic/include/tf2/LinearMath/Vector3.h\nQuadWord.h\n/opt/ros/kinetic/include/tf2/LinearMath/QuadWord.h\n\n/opt/ros/kinetic/include/tf2/LinearMath/Vector3.h\nScalar.h\n/opt/ros/kinetic/include/tf2/LinearMath/Scalar.h\nMinMax.h\n/opt/ros/kinetic/include/tf2/LinearMath/MinMax.h\n\n/opt/ros/kinetic/include/tf2/buffer_core.h\ntransform_storage.h\n/opt/ros/kinetic/include/tf2/transform_storage.h\nboost/signals2.hpp\n-\nstring\n-\nros/duration.h\n/opt/ros/kinetic/include/tf2/ros/duration.h\nros/time.h\n/opt/ros/kinetic/include/tf2/ros/time.h\ngeometry_msgs/TransformStamped.h\n/opt/ros/kinetic/include/tf2/geometry_msgs/TransformStamped.h\nboost/unordered_map.hpp\n-\nboost/thread/mutex.hpp\n-\nboost/function.hpp\n-\nboost/shared_ptr.hpp\n-\n\n/opt/ros/kinetic/include/tf2/convert.h\ntf2/transform_datatypes.h\n-\ntf2/exceptions.h\n-\ngeometry_msgs/TransformStamped.h\n-\ntf2/impl/convert.h\n-\n\n/opt/ros/kinetic/include/tf2/exceptions.h\nstdexcept\n-\n\n/opt/ros/kinetic/include/tf2/impl/convert.h\n\n/opt/ros/kinetic/include/tf2/transform_datatypes.h\nstring\n-\nros/time.h\n/opt/ros/kinetic/include/tf2/ros/time.h\n\n/opt/ros/kinetic/include/tf2/transform_storage.h\ntf2/LinearMath/Vector3.h\n-\ntf2/LinearMath/Quaternion.h\n-\nros/message_forward.h\n-\nros/time.h\n-\nros/types.h\n-\n\n/opt/ros/kinetic/include/tf2_msgs/FrameGraph.h\nros/service_traits.h\n-\ntf2_msgs/FrameGraphRequest.h\n-\ntf2_msgs/FrameGraphResponse.h\n-\n\n/opt/ros/kinetic/include/tf2_msgs/FrameGraphRequest.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/tf2_msgs/FrameGraphResponse.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\n\n/opt/ros/kinetic/include/tf2_msgs/TFMessage.h\nstring\n-\nvector\n-\nmap\n-\nros/types.h\n-\nros/serialization.h\n-\nros/builtin_message_traits.h\n-\nros/message_operations.h\n-\ngeometry_msgs/TransformStamped.h\n-\n\n/opt/ros/kinetic/include/tf2_ros/buffer.h\ntf2_ros/buffer_interface.h\n-\ntf2/buffer_core.h\n-\ntf2_msgs/FrameGraph.h\n-\nros/ros.h\n-\ntf2/convert.h\n-\n\n/opt/ros/kinetic/include/tf2_ros/buffer_interface.h\ntf2/buffer_core.h\n-\ntf2/transform_datatypes.h\n-\ntf2/exceptions.h\n-\ngeometry_msgs/TransformStamped.h\n-\nsstream\n-\ntf2/convert.h\n-\n\n/opt/ros/kinetic/include/tf2_ros/transform_broadcaster.h\nros/ros.h\n/opt/ros/kinetic/include/tf2_ros/ros/ros.h\ngeometry_msgs/TransformStamped.h\n/opt/ros/kinetic/include/tf2_ros/geometry_msgs/TransformStamped.h\n\n/opt/ros/kinetic/include/tf2_ros/transform_listener.h\nstd_msgs/Empty.h\n/opt/ros/kinetic/include/tf2_ros/std_msgs/Empty.h\ntf2_msgs/TFMessage.h\n/opt/ros/kinetic/include/tf2_ros/tf2_msgs/TFMessage.h\nros/ros.h\n/opt/ros/kinetic/include/tf2_ros/ros/ros.h\nros/callback_queue.h\n/opt/ros/kinetic/include/tf2_ros/ros/callback_queue.h\ntf2_ros/buffer.h\n/opt/ros/kinetic/include/tf2_ros/tf2_ros/buffer.h\nboost/thread.hpp\n/opt/ros/kinetic/include/tf2_ros/boost/thread.hpp\n\n/opt/ros/kinetic/include/xmlrpcpp/XmlRpcDecl.h\nros/macros.h\n-\n\n/opt/ros/kinetic/include/xmlrpcpp/XmlRpcValue.h\nxmlrpcpp/XmlRpcDecl.h\n/opt/ros/kinetic/include/xmlrpcpp/xmlrpcpp/XmlRpcDecl.h\nmap\n-\nstring\n-\nvector\n-\ntime.h\n-\n\n/usr/include/eigen3/Eigen/Cholesky\nCore\n/usr/include/eigen3/Eigen/Core\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nsrc/Cholesky/LLT.h\n/usr/include/eigen3/Eigen/src/Cholesky/LLT.h\nsrc/Cholesky/LDLT.h\n/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h\nsrc/Cholesky/LLT_MKL.h\n/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/Core\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nnew\n-\nsrc/Core/util/Macros.h\n/usr/include/eigen3/Eigen/src/Core/util/Macros.h\ncomplex\n-\nsrc/Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h\nmalloc.h\n-\nimmintrin.h\n-\nemmintrin.h\n-\nxmmintrin.h\n-\npmmintrin.h\n-\ntmmintrin.h\n-\nsmmintrin.h\n-\nnmmintrin.h\n-\nimmintrin.h\n-\naltivec.h\n-\naltivec.h\n-\narm_neon.h\n-\nvector_types.h\n-\nomp.h\n-\ncerrno\n-\ncstddef\n-\ncstdlib\n-\ncmath\n-\ncassert\n-\nfunctional\n-\niosfwd\n-\ncstring\n-\nstring\n-\nlimits\n-\nclimits\n-\nalgorithm\n-\niostream\n-\nintrin.h\n-\nsrc/Core/util/Constants.h\n/usr/include/eigen3/Eigen/src/Core/util/Constants.h\nsrc/Core/util/Meta.h\n/usr/include/eigen3/Eigen/src/Core/util/Meta.h\nsrc/Core/util/ForwardDeclarations.h\n/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h\nsrc/Core/util/StaticAssert.h\n/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h\nsrc/Core/util/XprHelper.h\n/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h\nsrc/Core/util/Memory.h\n/usr/include/eigen3/Eigen/src/Core/util/Memory.h\nsrc/Core/NumTraits.h\n/usr/include/eigen3/Eigen/src/Core/NumTraits.h\nsrc/Core/MathFunctions.h\n/usr/include/eigen3/Eigen/src/Core/MathFunctions.h\nsrc/Core/SpecialFunctions.h\n/usr/include/eigen3/Eigen/src/Core/SpecialFunctions.h\nsrc/Core/GenericPacketMath.h\n/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h\nsrc/Core/arch/SSE/PacketMath.h\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h\nsrc/Core/arch/SSE/Complex.h\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h\nsrc/Core/arch/SSE/MathFunctions.h\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h\nsrc/Core/arch/AVX/PacketMath.h\n/usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h\nsrc/Core/arch/AVX/MathFunctions.h\n/usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h\nsrc/Core/arch/AVX/Complex.h\n/usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h\nsrc/Core/arch/AVX/TypeCasting.h\n/usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h\nsrc/Core/arch/SSE/PacketMath.h\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h\nsrc/Core/arch/SSE/MathFunctions.h\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h\nsrc/Core/arch/SSE/Complex.h\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h\nsrc/Core/arch/SSE/TypeCasting.h\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h\nsrc/Core/arch/AltiVec/PacketMath.h\n/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h\nsrc/Core/arch/AltiVec/MathFunctions.h\n/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h\nsrc/Core/arch/AltiVec/Complex.h\n/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h\nsrc/Core/arch/NEON/PacketMath.h\n/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h\nsrc/Core/arch/NEON/MathFunctions.h\n/usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h\nsrc/Core/arch/NEON/Complex.h\n/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h\nsrc/Core/arch/CUDA/PacketMath.h\n/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h\nsrc/Core/arch/CUDA/MathFunctions.h\n/usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h\nsrc/Core/arch/Default/Settings.h\n/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h\nsrc/Core/functors/BinaryFunctors.h\n/usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h\nsrc/Core/functors/UnaryFunctors.h\n/usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h\nsrc/Core/functors/NullaryFunctors.h\n/usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h\nsrc/Core/functors/StlFunctors.h\n/usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h\nsrc/Core/functors/AssignmentFunctors.h\n/usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h\nsrc/Core/DenseCoeffsBase.h\n/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h\nsrc/Core/DenseBase.h\n/usr/include/eigen3/Eigen/src/Core/DenseBase.h\nsrc/Core/MatrixBase.h\n/usr/include/eigen3/Eigen/src/Core/MatrixBase.h\nsrc/Core/EigenBase.h\n/usr/include/eigen3/Eigen/src/Core/EigenBase.h\nsrc/Core/Product.h\n/usr/include/eigen3/Eigen/src/Core/Product.h\nsrc/Core/CoreEvaluators.h\n/usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h\nsrc/Core/AssignEvaluator.h\n/usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h\nsrc/Core/Assign.h\n/usr/include/eigen3/Eigen/src/Core/Assign.h\nsrc/Core/ArrayBase.h\n/usr/include/eigen3/Eigen/src/Core/ArrayBase.h\nsrc/Core/util/BlasUtil.h\n/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h\nsrc/Core/DenseStorage.h\n/usr/include/eigen3/Eigen/src/Core/DenseStorage.h\nsrc/Core/NestByValue.h\n/usr/include/eigen3/Eigen/src/Core/NestByValue.h\nsrc/Core/ReturnByValue.h\n/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h\nsrc/Core/NoAlias.h\n/usr/include/eigen3/Eigen/src/Core/NoAlias.h\nsrc/Core/PlainObjectBase.h\n/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h\nsrc/Core/Matrix.h\n/usr/include/eigen3/Eigen/src/Core/Matrix.h\nsrc/Core/Array.h\n/usr/include/eigen3/Eigen/src/Core/Array.h\nsrc/Core/CwiseBinaryOp.h\n/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h\nsrc/Core/CwiseUnaryOp.h\n/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h\nsrc/Core/CwiseNullaryOp.h\n/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h\nsrc/Core/CwiseUnaryView.h\n/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h\nsrc/Core/SelfCwiseBinaryOp.h\n/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h\nsrc/Core/Dot.h\n/usr/include/eigen3/Eigen/src/Core/Dot.h\nsrc/Core/StableNorm.h\n/usr/include/eigen3/Eigen/src/Core/StableNorm.h\nsrc/Core/Stride.h\n/usr/include/eigen3/Eigen/src/Core/Stride.h\nsrc/Core/MapBase.h\n/usr/include/eigen3/Eigen/src/Core/MapBase.h\nsrc/Core/Map.h\n/usr/include/eigen3/Eigen/src/Core/Map.h\nsrc/Core/Ref.h\n/usr/include/eigen3/Eigen/src/Core/Ref.h\nsrc/Core/Block.h\n/usr/include/eigen3/Eigen/src/Core/Block.h\nsrc/Core/VectorBlock.h\n/usr/include/eigen3/Eigen/src/Core/VectorBlock.h\nsrc/Core/Transpose.h\n/usr/include/eigen3/Eigen/src/Core/Transpose.h\nsrc/Core/DiagonalMatrix.h\n/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h\nsrc/Core/Diagonal.h\n/usr/include/eigen3/Eigen/src/Core/Diagonal.h\nsrc/Core/DiagonalProduct.h\n/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h\nsrc/Core/Redux.h\n/usr/include/eigen3/Eigen/src/Core/Redux.h\nsrc/Core/Visitor.h\n/usr/include/eigen3/Eigen/src/Core/Visitor.h\nsrc/Core/Fuzzy.h\n/usr/include/eigen3/Eigen/src/Core/Fuzzy.h\nsrc/Core/IO.h\n/usr/include/eigen3/Eigen/src/Core/IO.h\nsrc/Core/Swap.h\n/usr/include/eigen3/Eigen/src/Core/Swap.h\nsrc/Core/CommaInitializer.h\n/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h\nsrc/Core/GeneralProduct.h\n/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h\nsrc/Core/Solve.h\n/usr/include/eigen3/Eigen/src/Core/Solve.h\nsrc/Core/Inverse.h\n/usr/include/eigen3/Eigen/src/Core/Inverse.h\nsrc/Core/SolverBase.h\n/usr/include/eigen3/Eigen/src/Core/SolverBase.h\nsrc/Core/PermutationMatrix.h\n/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h\nsrc/Core/Transpositions.h\n/usr/include/eigen3/Eigen/src/Core/Transpositions.h\nsrc/Core/TriangularMatrix.h\n/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h\nsrc/Core/SelfAdjointView.h\n/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h\nsrc/Core/products/GeneralBlockPanelKernel.h\n/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h\nsrc/Core/products/Parallelizer.h\n/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h\nsrc/Core/ProductEvaluators.h\n/usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h\nsrc/Core/products/GeneralMatrixVector.h\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h\nsrc/Core/products/GeneralMatrixMatrix.h\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h\nsrc/Core/SolveTriangular.h\n/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h\nsrc/Core/products/GeneralMatrixMatrixTriangular.h\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h\nsrc/Core/products/SelfadjointMatrixVector.h\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h\nsrc/Core/products/SelfadjointMatrixMatrix.h\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h\nsrc/Core/products/SelfadjointProduct.h\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h\nsrc/Core/products/SelfadjointRank2Update.h\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h\nsrc/Core/products/TriangularMatrixVector.h\n/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h\nsrc/Core/products/TriangularMatrixMatrix.h\n/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h\nsrc/Core/products/TriangularSolverMatrix.h\n/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h\nsrc/Core/products/TriangularSolverVector.h\n/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h\nsrc/Core/BandMatrix.h\n/usr/include/eigen3/Eigen/src/Core/BandMatrix.h\nsrc/Core/CoreIterators.h\n/usr/include/eigen3/Eigen/src/Core/CoreIterators.h\nsrc/Core/BooleanRedux.h\n/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h\nsrc/Core/Select.h\n/usr/include/eigen3/Eigen/src/Core/Select.h\nsrc/Core/VectorwiseOp.h\n/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h\nsrc/Core/Random.h\n/usr/include/eigen3/Eigen/src/Core/Random.h\nsrc/Core/Replicate.h\n/usr/include/eigen3/Eigen/src/Core/Replicate.h\nsrc/Core/Reverse.h\n/usr/include/eigen3/Eigen/src/Core/Reverse.h\nsrc/Core/ArrayWrapper.h\n/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h\nsrc/Core/products/GeneralMatrixMatrix_MKL.h\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h\nsrc/Core/products/GeneralMatrixVector_MKL.h\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h\nsrc/Core/products/GeneralMatrixMatrixTriangular_MKL.h\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h\nsrc/Core/products/SelfadjointMatrixMatrix_MKL.h\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h\nsrc/Core/products/SelfadjointMatrixVector_MKL.h\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h\nsrc/Core/products/TriangularMatrixMatrix_MKL.h\n/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h\nsrc/Core/products/TriangularMatrixVector_MKL.h\n/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h\nsrc/Core/products/TriangularSolverMatrix_MKL.h\n/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h\nsrc/Core/Assign_MKL.h\n/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h\nsrc/Core/GlobalFunctions.h\n/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/Dense\nCore\n/usr/include/eigen3/Eigen/Core\nLU\n/usr/include/eigen3/Eigen/LU\nCholesky\n/usr/include/eigen3/Eigen/Cholesky\nQR\n/usr/include/eigen3/Eigen/QR\nSVD\n/usr/include/eigen3/Eigen/SVD\nGeometry\n/usr/include/eigen3/Eigen/Geometry\nEigenvalues\n/usr/include/eigen3/Eigen/Eigenvalues\n\n/usr/include/eigen3/Eigen/Eigenvalues\nCore\n/usr/include/eigen3/Eigen/Core\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nCholesky\n/usr/include/eigen3/Eigen/Cholesky\nJacobi\n/usr/include/eigen3/Eigen/Jacobi\nHouseholder\n/usr/include/eigen3/Eigen/Householder\nLU\n/usr/include/eigen3/Eigen/LU\nGeometry\n/usr/include/eigen3/Eigen/Geometry\nsrc/Eigenvalues/Tridiagonalization.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h\nsrc/Eigenvalues/RealSchur.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h\nsrc/Eigenvalues/EigenSolver.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h\nsrc/Eigenvalues/SelfAdjointEigenSolver.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h\nsrc/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h\nsrc/Eigenvalues/HessenbergDecomposition.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h\nsrc/Eigenvalues/ComplexSchur.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h\nsrc/Eigenvalues/ComplexEigenSolver.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h\nsrc/Eigenvalues/RealQZ.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h\nsrc/Eigenvalues/GeneralizedEigenSolver.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h\nsrc/Eigenvalues/MatrixBaseEigenvalues.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h\nsrc/Eigenvalues/RealSchur_MKL.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h\nsrc/Eigenvalues/ComplexSchur_MKL.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h\nsrc/Eigenvalues/SelfAdjointEigenSolver_MKL.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/Geometry\nCore\n/usr/include/eigen3/Eigen/Core\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nSVD\n/usr/include/eigen3/Eigen/SVD\nLU\n/usr/include/eigen3/Eigen/LU\nlimits\n-\nsrc/Geometry/OrthoMethods.h\n/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h\nsrc/Geometry/EulerAngles.h\n/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h\nsrc/Geometry/Homogeneous.h\n/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h\nsrc/Geometry/RotationBase.h\n/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h\nsrc/Geometry/Rotation2D.h\n/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h\nsrc/Geometry/Quaternion.h\n/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h\nsrc/Geometry/AngleAxis.h\n/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h\nsrc/Geometry/Transform.h\n/usr/include/eigen3/Eigen/src/Geometry/Transform.h\nsrc/Geometry/Translation.h\n/usr/include/eigen3/Eigen/src/Geometry/Translation.h\nsrc/Geometry/Scaling.h\n/usr/include/eigen3/Eigen/src/Geometry/Scaling.h\nsrc/Geometry/Hyperplane.h\n/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h\nsrc/Geometry/ParametrizedLine.h\n/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h\nsrc/Geometry/AlignedBox.h\n/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h\nsrc/Geometry/Umeyama.h\n/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h\nsrc/Geometry/arch/Geometry_SSE.h\n/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/Householder\nCore\n/usr/include/eigen3/Eigen/Core\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nsrc/Householder/Householder.h\n/usr/include/eigen3/Eigen/src/Householder/Householder.h\nsrc/Householder/HouseholderSequence.h\n/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h\nsrc/Householder/BlockHouseholder.h\n/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/Jacobi\nCore\n/usr/include/eigen3/Eigen/Core\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nsrc/Jacobi/Jacobi.h\n/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/LU\nCore\n/usr/include/eigen3/Eigen/Core\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nsrc/misc/Kernel.h\n/usr/include/eigen3/Eigen/src/misc/Kernel.h\nsrc/misc/Image.h\n/usr/include/eigen3/Eigen/src/misc/Image.h\nsrc/LU/FullPivLU.h\n/usr/include/eigen3/Eigen/src/LU/FullPivLU.h\nsrc/LU/PartialPivLU.h\n/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h\nsrc/LU/PartialPivLU_MKL.h\n/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h\nsrc/LU/Determinant.h\n/usr/include/eigen3/Eigen/src/LU/Determinant.h\nsrc/LU/InverseImpl.h\n/usr/include/eigen3/Eigen/src/LU/InverseImpl.h\nsrc/LU/arch/Inverse_SSE.h\n/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/QR\nCore\n/usr/include/eigen3/Eigen/Core\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nCholesky\n/usr/include/eigen3/Eigen/Cholesky\nJacobi\n/usr/include/eigen3/Eigen/Jacobi\nHouseholder\n/usr/include/eigen3/Eigen/Householder\nsrc/QR/HouseholderQR.h\n/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h\nsrc/QR/FullPivHouseholderQR.h\n/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h\nsrc/QR/ColPivHouseholderQR.h\n/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h\nsrc/QR/HouseholderQR_MKL.h\n/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h\nsrc/QR/ColPivHouseholderQR_MKL.h\n/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/SVD\nQR\n/usr/include/eigen3/Eigen/QR\nHouseholder\n/usr/include/eigen3/Eigen/Householder\nJacobi\n/usr/include/eigen3/Eigen/Jacobi\nsrc/Core/util/DisableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nsrc/SVD/UpperBidiagonalization.h\n/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h\nsrc/SVD/SVDBase.h\n/usr/include/eigen3/Eigen/src/SVD/SVDBase.h\nsrc/SVD/JacobiSVD.h\n/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h\nsrc/SVD/BDCSVD.h\n/usr/include/eigen3/Eigen/src/SVD/BDCSVD.h\nsrc/SVD/JacobiSVD_MKL.h\n/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h\nsrc/Core/util/ReenableStupidWarnings.h\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/StdDeque\nCore\n/usr/include/eigen3/Eigen/Core\ndeque\n-\nsrc/StlSupport/StdDeque.h\n/usr/include/eigen3/Eigen/src/StlSupport/StdDeque.h\n\n/usr/include/eigen3/Eigen/StdVector\nCore\n/usr/include/eigen3/Eigen/Core\nvector\n-\nsrc/StlSupport/StdVector.h\n/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h\n\n/usr/include/eigen3/Eigen/src/Cholesky/LDLT.h\n\n/usr/include/eigen3/Eigen/src/Cholesky/LLT.h\n\n/usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h\nEigen/src/Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/Cholesky/Eigen/src/Core/util/MKL_support.h\niostream\n-\n\n/usr/include/eigen3/Eigen/src/Core/Array.h\n\n/usr/include/eigen3/Eigen/src/Core/ArrayBase.h\n../plugins/CommonCwiseUnaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h\n../plugins/MatrixCwiseUnaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h\n../plugins/ArrayCwiseUnaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h\n../plugins/CommonCwiseBinaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h\n../plugins/MatrixCwiseBinaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h\n../plugins/ArrayCwiseBinaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h\n\n/usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h\n\n/usr/include/eigen3/Eigen/src/Core/Assign.h\n\n/usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h\n\n/usr/include/eigen3/Eigen/src/Core/Assign_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/BandMatrix.h\n\n/usr/include/eigen3/Eigen/src/Core/Block.h\n\n/usr/include/eigen3/Eigen/src/Core/BooleanRedux.h\n\n/usr/include/eigen3/Eigen/src/Core/CommaInitializer.h\n\n/usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h\n\n/usr/include/eigen3/Eigen/src/Core/CoreIterators.h\n\n/usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h\n\n/usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h\n\n/usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h\n\n/usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h\n\n/usr/include/eigen3/Eigen/src/Core/DenseBase.h\n../plugins/BlockMethods.h\n/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h\n\n/usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h\n\n/usr/include/eigen3/Eigen/src/Core/DenseStorage.h\n\n/usr/include/eigen3/Eigen/src/Core/Diagonal.h\n\n/usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h\n\n/usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h\n\n/usr/include/eigen3/Eigen/src/Core/Dot.h\n\n/usr/include/eigen3/Eigen/src/Core/EigenBase.h\n\n/usr/include/eigen3/Eigen/src/Core/Fuzzy.h\n\n/usr/include/eigen3/Eigen/src/Core/GeneralProduct.h\n\n/usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h\n\n/usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h\n\n/usr/include/eigen3/Eigen/src/Core/IO.h\n\n/usr/include/eigen3/Eigen/src/Core/Inverse.h\n\n/usr/include/eigen3/Eigen/src/Core/Map.h\n\n/usr/include/eigen3/Eigen/src/Core/MapBase.h\n\n/usr/include/eigen3/Eigen/src/Core/MathFunctions.h\n\n/usr/include/eigen3/Eigen/src/Core/Matrix.h\n\n/usr/include/eigen3/Eigen/src/Core/MatrixBase.h\n../plugins/CommonCwiseUnaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h\n../plugins/CommonCwiseBinaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h\n../plugins/MatrixCwiseUnaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h\n../plugins/MatrixCwiseBinaryOps.h\n/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h\n\n/usr/include/eigen3/Eigen/src/Core/NestByValue.h\n\n/usr/include/eigen3/Eigen/src/Core/NoAlias.h\n\n/usr/include/eigen3/Eigen/src/Core/NumTraits.h\n\n/usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h\n\n/usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h\n\n/usr/include/eigen3/Eigen/src/Core/Product.h\n\n/usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h\n\n/usr/include/eigen3/Eigen/src/Core/Random.h\n\n/usr/include/eigen3/Eigen/src/Core/Redux.h\n\n/usr/include/eigen3/Eigen/src/Core/Ref.h\n\n/usr/include/eigen3/Eigen/src/Core/Replicate.h\n\n/usr/include/eigen3/Eigen/src/Core/ReturnByValue.h\n\n/usr/include/eigen3/Eigen/src/Core/Reverse.h\n\n/usr/include/eigen3/Eigen/src/Core/Select.h\n\n/usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h\n\n/usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h\n\n/usr/include/eigen3/Eigen/src/Core/Solve.h\n\n/usr/include/eigen3/Eigen/src/Core/SolveTriangular.h\n\n/usr/include/eigen3/Eigen/src/Core/SolverBase.h\n\n/usr/include/eigen3/Eigen/src/Core/SpecialFunctions.h\n\n/usr/include/eigen3/Eigen/src/Core/StableNorm.h\n\n/usr/include/eigen3/Eigen/src/Core/Stride.h\n\n/usr/include/eigen3/Eigen/src/Core/Swap.h\n\n/usr/include/eigen3/Eigen/src/Core/Transpose.h\n\n/usr/include/eigen3/Eigen/src/Core/Transpositions.h\n\n/usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h\n\n/usr/include/eigen3/Eigen/src/Core/VectorBlock.h\n\n/usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h\n\n/usr/include/eigen3/Eigen/src/Core/Visitor.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h\n\n/usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h\n\n/usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h\n\n/usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h\n\n/usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h\n\n/usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h\n\n/usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h\n\n/usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h\n\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h\n\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h\n\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h\n\n/usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h\n\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h\n\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h\n\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h\n\n/usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h\n\n/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h\n\n/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h\n\n/usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h\n\n/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h\n\n/usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h\n\n/usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h\n\n/usr/include/eigen3/Eigen/src/Core/util/Constants.h\n\n/usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h\n\n/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h\nmkl.h\n-\nmkl_lapacke.h\n-\n\n/usr/include/eigen3/Eigen/src/Core/util/Macros.h\ncstdlib\n-\niostream\n-\n\n/usr/include/eigen3/Eigen/src/Core/util/Memory.h\nunistd.h\n-\n\n/usr/include/eigen3/Eigen/src/Core/util/Meta.h\ncfloat\n-\nmath_constants.h\n-\n\n/usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n\n/usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h\n\n/usr/include/eigen3/Eigen/src/Core/util/XprHelper.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h\n./HessenbergDecomposition.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h\n./HessenbergDecomposition.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/././HessenbergDecomposition.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h\n./ComplexSchur.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h\n./HessenbergDecomposition.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h\nEigen/src/Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h\n./RealSchur.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h\n./RealQZ.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h\n./Tridiagonalization.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h\n./HessenbergDecomposition.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h\nEigen/src/Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h\n./Tridiagonalization.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h\nEigen/src/Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/Eigenvalues/Eigen/src/Core/util/MKL_support.h\n\n/usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h\n\n/usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h\n\n/usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h\n\n/usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h\n\n/usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h\n\n/usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h\n\n/usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h\n\n/usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h\n\n/usr/include/eigen3/Eigen/src/Geometry/Quaternion.h\n\n/usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h\n\n/usr/include/eigen3/Eigen/src/Geometry/RotationBase.h\n\n/usr/include/eigen3/Eigen/src/Geometry/Scaling.h\n\n/usr/include/eigen3/Eigen/src/Geometry/Transform.h\n\n/usr/include/eigen3/Eigen/src/Geometry/Translation.h\n\n/usr/include/eigen3/Eigen/src/Geometry/Umeyama.h\n\n/usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h\n\n/usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h\n\n/usr/include/eigen3/Eigen/src/Householder/Householder.h\n\n/usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h\n\n/usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h\n\n/usr/include/eigen3/Eigen/src/LU/Determinant.h\n\n/usr/include/eigen3/Eigen/src/LU/FullPivLU.h\n\n/usr/include/eigen3/Eigen/src/LU/InverseImpl.h\n\n/usr/include/eigen3/Eigen/src/LU/PartialPivLU.h\n\n/usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h\nEigen/src/Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/LU/Eigen/src/Core/util/MKL_support.h\n\n/usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h\n\n/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h\n\n/usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h\nEigen/src/Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/QR/Eigen/src/Core/util/MKL_support.h\n\n/usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h\n\n/usr/include/eigen3/Eigen/src/QR/HouseholderQR.h\n\n/usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h\n../Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/Core/util/MKL_support.h\n\n/usr/include/eigen3/Eigen/src/SVD/BDCSVD.h\n\n/usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h\n\n/usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h\nEigen/src/Core/util/MKL_support.h\n/usr/include/eigen3/Eigen/src/SVD/Eigen/src/Core/util/MKL_support.h\n\n/usr/include/eigen3/Eigen/src/SVD/SVDBase.h\n\n/usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h\n\n/usr/include/eigen3/Eigen/src/StlSupport/StdDeque.h\ndetails.h\n/usr/include/eigen3/Eigen/src/StlSupport/details.h\n\n/usr/include/eigen3/Eigen/src/StlSupport/StdVector.h\ndetails.h\n/usr/include/eigen3/Eigen/src/StlSupport/details.h\n\n/usr/include/eigen3/Eigen/src/StlSupport/details.h\n\n/usr/include/eigen3/Eigen/src/misc/Image.h\n\n/usr/include/eigen3/Eigen/src/misc/Kernel.h\n\n/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h\n\n/usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h\n\n/usr/include/eigen3/Eigen/src/plugins/BlockMethods.h\n\n/usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h\n\n/usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h\n\n/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h\n\n/usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h\n\n/usr/include/eigen3/unsupported/Eigen/MatrixFunctions\ncfloat\n-\nlist\n-\nEigen/Core\n-\nEigen/LU\n-\nEigen/Eigenvalues\n-\nsrc/MatrixFunctions/MatrixExponential.h\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h\nsrc/MatrixFunctions/MatrixFunction.h\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h\nsrc/MatrixFunctions/MatrixSquareRoot.h\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h\nsrc/MatrixFunctions/MatrixLogarithm.h\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h\nsrc/MatrixFunctions/MatrixPower.h\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h\nunsupported/Eigen/MatrixFunctions\n-\niostream\n-\n\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h\nStemFunction.h\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h\n\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h\nStemFunction.h\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h\n\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h\n\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h\n\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h\n\n/usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h\n\n/usr/include/mrpt/base/include/mrpt/base/link_pragmas.h\nmrpt/config.h\n-\nmrpt/utils/boost_join.h\n-\n\n/usr/include/mrpt/base/include/mrpt/bayes/CParticleFilter.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/CDebugOutputCapable.h\n-\nmrpt/utils/CLoadableOptions.h\n-\n\n/usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterCapable.h\nmrpt/utils/utils_defs.h\n-\nmrpt/bayes/CParticleFilter.h\n-\n\n/usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterData.h\nmrpt/utils/core_defs.h\n-\nmrpt/bayes/CProbabilityParticle.h\n-\nmrpt/bayes/CParticleFilterCapable.h\n-\ndeque\n-\nalgorithm\n-\n\n/usr/include/mrpt/base/include/mrpt/bayes/CProbabilityParticle.h\n\n/usr/include/mrpt/base/include/mrpt/math/CArray.h\nmrpt/utils/core_defs.h\n-\nstdexcept\n-\nmrpt/utils/TTypeName.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CArrayNumeric.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/types_math.h\n-\nmrpt/utils/TTypeName.h\n-\nmrpt/math/point_poses2vectors.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CHistogram.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/types_math.h\n-\nvector\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CMatrix.h\nmrpt/utils/CSerializable.h\n-\nmrpt/math/CMatrixTemplateNumeric.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CMatrixD.h\nmrpt/utils/CSerializable.h\n-\nmrpt/math/CMatrixTemplateNumeric.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CMatrixFixedNumeric.h\nmrpt/math/math_frwds.h\n-\nmrpt/math/eigen_frwds.h\n-\nmrpt/utils/types_math.h\n-\nmrpt/utils/CSerializable.h\n-\nmrpt/math/point_poses2vectors.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CMatrixTemplate.h\nmrpt/utils/utils_defs.h\n-\nmrpt/system/memory.h\n-\nmrpt/math/math_frwds.h\n-\nmrpt/math/CArray.h\n-\nalgorithm\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CMatrixTemplateNumeric.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/types_math.h\n-\nmrpt/utils/TTypeName.h\n-\nmrpt/math/point_poses2vectors.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CPolygon.h\nmrpt/utils/CSerializable.h\n-\nmrpt/math/lightweight_geom_data.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CQuaternion.h\nmrpt/math/CMatrixTemplateNumeric.h\n-\nmrpt/math/CArrayNumeric.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/CSparseMatrixTemplate.h\nmrpt/utils/utils_defs.h\n-\nmap\n-\n\n/usr/include/mrpt/base/include/mrpt/math/eigen_frwds.h\nmrpt/config.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/geometry.h\nmrpt/utils/utils_defs.h\n-\nmrpt/math/CMatrixTemplateNumeric.h\n-\nmrpt/poses/CPose3D.h\n-\nmrpt/math/CSparseMatrixTemplate.h\n-\nmrpt/math/math_frwds.h\n-\nmrpt/math/wrap2pi.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/homog_matrices.h\nmrpt/config.h\n-\nmrpt/utils/compiler_fixes.h\n-\nmrpt/utils/boost_join.h\n-\nmrpt/utils/mrpt_macros.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/lightweight_geom_data.h\nmrpt/utils/utils_defs.h\n-\nmrpt/config.h\n-\nmrpt/base/link_pragmas.h\n-\nmrpt/utils/TPixelCoord.h\n-\nmrpt/utils/TTypeName.h\n-\nmrpt/math/math_frwds.h\n-\nvector\n-\nstdexcept\n-\n\n/usr/include/mrpt/base/include/mrpt/math/math_frwds.h\nmrpt/config.h\n-\nmrpt/base/link_pragmas.h\n-\nmrpt/poses/poses_frwds.h\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/math/matrix_serialization.h\nmrpt/utils/CStream.h\n-\nmrpt/math/CMatrix.h\n-\nmrpt/math/CMatrixD.h\n-\nmrpt/math/CMatrixTemplateNumeric.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/point_poses2vectors.h\nmrpt/math/math_frwds.h\n-\n\n/usr/include/mrpt/base/include/mrpt/math/wrap2pi.h\ncmath\n-\ncstddef\n-\n\n/usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/containers_fixes.hpp\n\n/usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/exceptions.hpp\ncontainers_fixes.hpp\n/usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/containers_fixes.hpp\nstdexcept\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.hpp\nexceptions.hpp\n/usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/exceptions.hpp\nmrpt/synch/atomic_incr.h\n-\nsmart_ptr.tpp\n/usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.tpp\n\n/usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.tpp\n\n/usr/include/mrpt/base/include/mrpt/poses.h\nmrpt/poses/CPoseOrPoint.h\n-\nmrpt/poses/CPose.h\n-\nmrpt/poses/CPoint.h\n-\nmrpt/poses/CPoint2D.h\n-\nmrpt/poses/CPose2D.h\n-\nmrpt/poses/CPose3D.h\n-\nmrpt/poses/CPose3DRotVec.h\n-\nmrpt/poses/CPoint3D.h\n-\nmrpt/poses/CPosePDF.h\n-\nmrpt/poses/CPose2DGridTemplate.h\n-\nmrpt/poses/CPosePDFGaussian.h\n-\nmrpt/poses/CPointPDF.h\n-\nmrpt/poses/CPose3DQuat.h\n-\nmrpt/poses/CPosePDFGrid.h\n-\nmrpt/poses/CPointPDFGaussian.h\n-\nmrpt/poses/CPoint2DPDFGaussian.h\n-\nmrpt/poses/CPose3DPDF.h\n-\nmrpt/poses/CPosePDFParticles.h\n-\nmrpt/poses/CPointPDFParticles.h\n-\nmrpt/poses/CPose3DPDFGaussian.h\n-\nmrpt/poses/CPosePDFSOG.h\n-\nmrpt/poses/CPointPDFSOG.h\n-\nmrpt/poses/CPose3DPDFParticles.h\n-\nmrpt/poses/CPoses2DSequence.h\n-\nmrpt/poses/CPose3DPDFSOG.h\n-\nmrpt/poses/CPoses3DSequence.h\n-\nmrpt/poses/CPose3DInterpolator.h\n-\nmrpt/poses/CPoseRandomSampler.h\n-\nmrpt/poses/CRobot2DPoseEstimator.h\n-\nmrpt/poses/CPose3DQuatPDFGaussian.h\n-\nmrpt/poses/CPosePDFGaussianInf.h\n-\nmrpt/poses/CPose3DPDFGaussianInf.h\n-\nmrpt/poses/CPose3DQuatPDFGaussianInf.h\n-\nmrpt/poses/SE_traits.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoint.h\nmrpt/poses/CPoseOrPoint.h\n-\nmrpt/math/CMatrixTemplateNumeric.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoint2D.h\nmrpt/utils/CSerializable.h\n-\nmrpt/poses/CPoint.h\n-\nmrpt/math/CArray.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDF.h\nmrpt/utils/CSerializable.h\n-\nmrpt/utils/CProbabilityDensityFunction.h\n-\nmrpt/poses/CPoint2D.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDFGaussian.h\nmrpt/poses/CPoint2DPDF.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoint3D.h\nmrpt/poses/CPoint.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPointPDF.h\nmrpt/utils/CSerializable.h\n-\nmrpt/utils/CProbabilityDensityFunction.h\n-\nmrpt/poses/CPoint3D.h\n-\nmrpt/poses/CPosePDF.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPointPDFGaussian.h\nmrpt/poses/CPointPDF.h\n-\nmrpt/math/CMatrix.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPointPDFParticles.h\nmrpt/poses/CPointPDF.h\n-\nmrpt/math/CMatrix.h\n-\nmrpt/bayes/CParticleFilterCapable.h\n-\nmrpt/bayes/CProbabilityParticle.h\n-\nmrpt/bayes/CParticleFilterData.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPointPDFSOG.h\nmrpt/poses/CPointPDF.h\n-\nmrpt/poses/CPointPDFGaussian.h\n-\nmrpt/math/CMatrix.h\n-\nmrpt/math/CMatrixD.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose.h\nmrpt/poses/CPoseOrPoint.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose2D.h\nmrpt/poses/CPose.h\n-\nmrpt/utils/aligned_containers.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose2DGridTemplate.h\nmrpt/utils/CSerializable.h\n-\nmrpt/utils/round.h\n-\nmrpt/utils/bits.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3D.h\nmrpt/poses/CPose.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/math/CQuaternion.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DInterpolator.h\nmrpt/utils/CSerializable.h\n-\nmrpt/system/datetime.h\n-\nmrpt/utils/TEnumType.h\n-\nmrpt/utils/aligned_containers.h\n-\nmrpt/math/math_frwds.h\n-\nmrpt/poses/CPose3D.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DPDF.h\nmrpt/utils/CSerializable.h\n-\nmrpt/math/math_frwds.h\n-\nmrpt/poses/CPose3D.h\n-\nmrpt/utils/CProbabilityDensityFunction.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussian.h\nmrpt/poses/CPose3DPDF.h\n-\nmrpt/poses/CPose3D.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussianInf.h\nmrpt/poses/CPose3D.h\n-\nmrpt/poses/CPose3DPDF.h\n-\nmrpt/poses/CPosePDF.h\n-\nmrpt/math/CMatrixD.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFParticles.h\nmrpt/poses/CPose3DPDF.h\n-\nmrpt/bayes/CProbabilityParticle.h\n-\nmrpt/bayes/CParticleFilterCapable.h\n-\nmrpt/bayes/CParticleFilterData.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFSOG.h\nmrpt/poses/CPose3DPDF.h\n-\nmrpt/poses/CPose3DPDFGaussian.h\n-\nmrpt/utils/aligned_containers.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DQuat.h\nmrpt/poses/CPose.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/math/CQuaternion.h\n-\nmrpt/poses/CPoint3D.h\n-\nmrpt/poses/poses_frwds.h\n-\nmrpt/math/lightweight_geom_data.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDF.h\nmrpt/poses/CPose3D.h\n-\nmrpt/poses/CPose3DQuat.h\n-\nmrpt/math/CMatrixD.h\n-\nmrpt/utils/CProbabilityDensityFunction.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussian.h\nmrpt/poses/CPose3DQuatPDF.h\n-\nmrpt/poses/CPose3DPDF.h\n-\nmrpt/poses/CPosePDF.h\n-\nmrpt/math/CMatrixD.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h\nmrpt/poses/CPose3DQuatPDF.h\n-\nmrpt/poses/CPose3DPDF.h\n-\nmrpt/poses/CPosePDF.h\n-\nmrpt/math/CMatrixD.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPose3DRotVec.h\nmrpt/poses/CPose.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/math/CQuaternion.h\n-\nmrpt/poses/poses_frwds.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint.h\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/math/lightweight_geom_data.h\n-\nmrpt/math/homog_matrices.h\n-\nmrpt/math/CArrayNumeric.h\n-\nmrpt/poses/CPoseOrPoint_detail.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint_detail.h\nmrpt/poses/poses_frwds.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPosePDF.h\nmrpt/utils/CSerializable.h\n-\nmrpt/poses/CPose2D.h\n-\nmrpt/math/CMatrixTemplateNumeric.h\n-\nmrpt/utils/CProbabilityDensityFunction.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussian.h\nmrpt/poses/CPosePDF.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussianInf.h\nmrpt/poses/CPosePDF.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPosePDFGrid.h\nmrpt/poses/CPosePDF.h\n-\nmrpt/poses/CPose2DGridTemplate.h\n-\nmrpt/utils/bits.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPosePDFParticles.h\nmrpt/poses/CPosePDF.h\n-\nmrpt/poses/CPoseRandomSampler.h\n-\nmrpt/bayes/CParticleFilterCapable.h\n-\nmrpt/bayes/CParticleFilterData.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPosePDFSOG.h\nmrpt/poses/CPosePDF.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/math/math_frwds.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoseRandomSampler.h\nmrpt/poses/CPose3D.h\n-\nmrpt/poses/CPose2D.h\n-\nmrpt/math/CMatrixTemplateNumeric.h\n-\nmrpt/math/math_frwds.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoses2DSequence.h\nmrpt/poses/CPose2D.h\n-\nmrpt/utils/CSerializable.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CPoses3DSequence.h\nmrpt/poses/CPose3D.h\n-\nmrpt/utils/CSerializable.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/CRobot2DPoseEstimator.h\nmrpt/synch/CCriticalSection.h\n-\nmrpt/math/lightweight_geom_data.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/system/datetime.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/SE_traits.h\nmrpt/poses/CPose3D.h\n-\nmrpt/poses/CPose2D.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\n\n/usr/include/mrpt/base/include/mrpt/poses/poses_frwds.h\n\n/usr/include/mrpt/base/include/mrpt/synch/CCriticalSection.h\nmrpt/utils/CReferencedMemBlock.h\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/synch/atomic_incr.h\nmrpt/config.h\n-\nmrpt/utils/compiler_fixes.h\n-\nmrpt/base/link_pragmas.h\n-\n\n/usr/include/mrpt/base/include/mrpt/system/datetime.h\nmrpt/base/link_pragmas.h\n-\nmrpt/utils/mrpt_stdint.h\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/system/memory.h\nmrpt/utils/core_defs.h\n-\ncstring\n-\n\n/usr/include/mrpt/base/include/mrpt/system/os.h\nmrpt/config.h\n-\ncstdlib\n-\ncstdarg\n-\nmrpt/base/link_pragmas.h\n-\nmrpt/utils/mrpt_stdint.h\n-\nmrpt/utils/mrpt_macros.h\n-\n\n/usr/include/mrpt/base/include/mrpt/system/string_utils.h\nmrpt/utils/utils_defs.h\n-\ndeque\n-\n\n/usr/include/mrpt/base/include/mrpt/system/threads.h\nmrpt/utils/core_defs.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils.h\nmrpt/utils/utils_defs.h\n-\nmrpt/poses.h\n-\nmrpt/utils/CDebugOutputCapable.h\n-\nmrpt/utils/CStringList.h\n-\nmrpt/utils/TEnumType.h\n-\nmrpt/utils/CObject.h\n-\nmrpt/utils/CStartUpClassesRegister.h\n-\nmrpt/utils/CSerializable.h\n-\nmrpt/utils/CStream.h\n-\nmrpt/utils/CMemoryStream.h\n-\nmrpt/utils/CMemoryChunk.h\n-\nmrpt/utils/CStdOutStream.h\n-\nmrpt/utils/CFileStream.h\n-\nmrpt/utils/CFileInputStream.h\n-\nmrpt/utils/CFileOutputStream.h\n-\nmrpt/utils/CFileGZInputStream.h\n-\nmrpt/utils/CFileGZOutputStream.h\n-\nmrpt/utils/CServerTCPSocket.h\n-\nmrpt/utils/CClientTCPSocket.h\n-\nmrpt/utils/CEnhancedMetaFile.h\n-\nmrpt/utils/CCanvas.h\n-\nmrpt/utils/CImage.h\n-\nmrpt/utils/CMappedImage.h\n-\nmrpt/utils/CTicTac.h\n-\nmrpt/utils/CTimeLogger.h\n-\nmrpt/utils/CSimpleDatabase.h\n-\nmrpt/utils/CPropertiesValuesList.h\n-\nmrpt/utils/CMHPropertiesValuesList.h\n-\nmrpt/utils/CTypeSelector.h\n-\nmrpt/utils/CLoadableOptions.h\n-\nmrpt/utils/CMessage.h\n-\nmrpt/utils/CConfigFile.h\n-\nmrpt/utils/CConfigFileMemory.h\n-\nmrpt/utils/CThreadSafeQueue.h\n-\nmrpt/utils/CMessageQueue.h\n-\nmrpt/utils/CDynamicGrid.h\n-\nmrpt/utils/CProbabilityDensityFunction.h\n-\nmrpt/utils/CConsoleRedirector.h\n-\nmrpt/utils/exceptions.h\n-\nmrpt/utils/crc.h\n-\nmrpt/utils/md5.h\n-\nmrpt/utils/net_utils.h\n-\nmrpt/utils/CLog.h\n-\nmrpt/utils/CListOfClasses.h\n-\nmrpt/utils/CTextFileLinesParser.h\n-\nmrpt/utils/CRobotSimulator.h\n-\nmrpt/utils/TCamera.h\n-\nmrpt/utils/TStereoCamera.h\n-\nmrpt/utils/TMatchingPair.h\n-\nmrpt/utils/PLY_import_export.h\n-\nmrpt/utils/CObservable.h\n-\nmrpt/utils/CObserver.h\n-\nmrpt/utils/mrptEvent.h\n-\nmrpt/utils/adapters.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CCanvas.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/TColor.h\n-\nmrpt/math/eigen_frwds.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CClientTCPSocket.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/mrpt_stdint.h\n-\nmrpt/utils/CStream.h\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CConfigFile.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/CConfigFileBase.h\n-\nmrpt/utils/safe_pointers.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CConfigFileBase.h\nmrpt/utils/utils_defs.h\n-\nmrpt/system/string_utils.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CConfigFileMemory.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/CConfigFileBase.h\n-\nmrpt/utils/CStringList.h\n-\nmrpt/utils/safe_pointers.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CConsoleRedirector.h\nmrpt/synch/CCriticalSection.h\n-\nmrpt/utils/core_defs.h\n-\nstreambuf\n-\niostream\n-\nfstream\n-\ncstdio\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CDebugOutputCapable.h\nmrpt/base/link_pragmas.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CDynamicGrid.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/round.h\n-\nvector\n-\nstring\n-\ncmath\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CEnhancedMetaFile.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/CCanvas.h\n-\nmrpt/utils/safe_pointers.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CFileGZInputStream.h\nmrpt/utils/CStream.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CFileGZOutputStream.h\nmrpt/utils/CStream.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CFileInputStream.h\nmrpt/utils/CStream.h\n-\nfstream\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CFileOutputStream.h\nmrpt/utils/CStream.h\n-\nfstream\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CFileStream.h\nmrpt/utils/CStream.h\n-\nmrpt/utils/CUncopiable.h\n-\nfstream\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CImage.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/CSerializable.h\n-\nmrpt/math/eigen_frwds.h\n-\nmrpt/utils/CCanvas.h\n-\nmrpt/utils/TCamera.h\n-\nmrpt/utils/exceptions.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CListOfClasses.h\nmrpt/utils/CSerializable.h\n-\nmrpt/system/string_utils.h\n-\nset\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CLoadableOptions.h\nmrpt/utils/core_defs.h\n-\nstring\n-\nstdexcept\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CLog.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/CStringList.h\n-\nmrpt/synch/CCriticalSection.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CMHPropertiesValuesList.h\nmrpt/utils/CSerializable.h\n-\nmrpt/utils/CMemoryChunk.h\n-\nmrpt/system/string_utils.h\n-\ncstdio\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CMappedImage.h\nmrpt/utils/CImage.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CMemoryChunk.h\nmrpt/utils/CMemoryStream.h\n-\nmrpt/utils/CSerializable.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CMemoryStream.h\nmrpt/utils/CStream.h\n-\nmrpt/utils/safe_pointers.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CMessage.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/mrpt_stdint.h\n-\nvector\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CMessageQueue.h\nmrpt/utils/CThreadSafeQueue.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CObject.h\nmrpt/system/memory.h\n-\nmrpt/utils/safe_pointers.h\n-\nvector\n-\nmrpt/otherlibs/stlplus/smart_ptr.hpp\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CObservable.h\nmrpt/config.h\n-\nmrpt/base/link_pragmas.h\n-\nset\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CObserver.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/mrptEvent.h\n-\nset\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CProbabilityDensityFunction.h\nmrpt/math/CMatrixTemplateNumeric.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/math/math_frwds.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CPropertiesValuesList.h\nmrpt/utils/CSerializable.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CReferencedMemBlock.h\nmrpt/base/link_pragmas.h\n-\nvector\n-\nutility\n-\nmrpt/otherlibs/stlplus/smart_ptr.hpp\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CRobotSimulator.h\nmrpt/utils/CSerializable.h\n-\nmrpt/poses/CPose2D.h\n-\nmrpt/base/link_pragmas.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CSerializable.h\nmrpt/utils/CObject.h\n-\nmrpt/utils/TTypeName.h\n-\nmrpt/utils/types_simple.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CServerTCPSocket.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/CDebugOutputCapable.h\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CSimpleDatabase.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/CSerializable.h\n-\nmap\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CStartUpClassesRegister.h\nmrpt/base/link_pragmas.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CStdOutStream.h\nmrpt/utils/CStream.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CStream.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/types_simple.h\n-\nmrpt/utils/CUncopiable.h\n-\nmrpt/utils/exceptions.h\n-\nmrpt/utils/bits.h\n-\nvector\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CStringList.h\nmrpt/utils/CSerializable.h\n-\ndeque\n-\niterator\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CTextFileLinesParser.h\nmrpt/utils/utils_defs.h\n-\nmrpt/system/string_utils.h\n-\nfstream\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CThreadSafeQueue.h\nmrpt/utils/CMessage.h\n-\nmrpt/synch/CCriticalSection.h\n-\nqueue\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CTicTac.h\nmrpt/base/link_pragmas.h\n-\nmrpt/utils/CUncopiable.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CTimeLogger.h\nmrpt/utils/CTicTac.h\n-\nmrpt/utils/CDebugOutputCapable.h\n-\nmrpt/utils/compiler_fixes.h\n-\nmrpt/utils/mrpt_macros.h\n-\nvector\n-\nstack\n-\nmap\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CTypeSelector.h\nmrpt/utils/CSerializable.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/CUncopiable.h\nmrpt/base/link_pragmas.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/PLY_import_export.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/CStringList.h\n-\nmrpt/utils/TColor.h\n-\nmrpt/math/lightweight_geom_data.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/SSE_types.h\nmrpt/config.h\n-\nemmintrin.h\n-\nmmintrin.h\n-\npmmintrin.h\n-\nimmintrin.h\n-\nsmmintrin.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TCamera.h\nmrpt/math/CMatrixTemplateNumeric.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/utils/CLoadableOptions.h\n-\nmrpt/utils/CConfigFileBase.h\n-\nmrpt/utils/CSerializable.h\n-\nmrpt/poses/CPose3DQuat.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TColor.h\nmrpt/utils/mrpt_stdint.h\n-\nmrpt/base/link_pragmas.h\n-\niosfwd\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TEnumType.h\nmrpt/utils/core_defs.h\n-\nmrpt/utils/bimap.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TMatchingPair.h\nstring\n-\nvector\n-\nmrpt/base/link_pragmas.h\n-\nmrpt/poses/poses_frwds.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TParameters.h\ncstdarg\n-\ncstdio\n-\nmap\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TPixelCoord.h\niosfwd\n-\nmrpt/base/link_pragmas.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TStereoCamera.h\nmrpt/utils/TCamera.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TTypeName.h\nmrpt/utils/mrpt_stdint.h\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/TTypeName_impl.h\nmrpt/utils/TTypeName.h\n-\nlist\n-\nvector\n-\ndeque\n-\nset\n-\nmap\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/adapters.h\nmrpt/utils/utils_defs.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/aligned_containers.h\nvector\n-\nmap\n-\nlist\n-\ndeque\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/bimap.h\nmrpt/utils/utils_defs.h\n-\nmap\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/bits.h\ncmath\n-\nalgorithm\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/boost_join.h\n\n/usr/include/mrpt/base/include/mrpt/utils/ci_less.h\nfunctional\n-\ncctype\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/circular_buffer.h\nvector\n-\nstdexcept\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/color_maps.h\nmrpt/base/link_pragmas.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/compiler_fixes.h\n\n/usr/include/mrpt/base/include/mrpt/utils/core_defs.h\nmrpt/config.h\n-\nmrpt/utils/compiler_fixes.h\n-\nmrpt/utils/boost_join.h\n-\nmrpt/utils/mrpt_macros.h\n-\nmrpt/base/link_pragmas.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/crc.h\nmrpt/utils/utils_defs.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/exceptions.h\nstdexcept\n-\nstring\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/list_searchable.h\nlist\n-\nalgorithm\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/map_as_vector.h\nmrpt/utils/aligned_containers.h\n-\nmap\n-\nvector\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/md5.h\nmrpt/utils/utils_defs.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/metaprogramming_serialization.h\n\n/usr/include/mrpt/base/include/mrpt/utils/mrptEvent.h\nmrpt/system/datetime.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/mrpt_macros.h\nmrpt/base/link_pragmas.h\n-\nsstream\n-\nstdexcept\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/mrpt_stdint.h\nmrpt/config.h\n-\nstdint.h\n-\npstdint.h\n/usr/include/mrpt/base/include/mrpt/utils/pstdint.h\n\n/usr/include/mrpt/base/include/mrpt/utils/net_utils.h\nmrpt/utils/CClientTCPSocket.h\n-\nmrpt/utils/CServerTCPSocket.h\n-\nmrpt/utils/TParameters.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/printf_vector.h\nmrpt/math/eigen_frwds.h\n-\nstring\n-\nvector\n-\ncstdio\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/pstdint.h\nstddef.h\n-\nlimits.h\n-\nsignal.h\n-\nstdint.h\n-\nwchar.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/round.h\nmrpt/utils/SSE_types.h\n-\ncmath\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/safe_pointers.h\nmrpt/config.h\n-\nmrpt/utils/boost_join.h\n-\nmrpt/utils/mrpt_macros.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/stl_containers_utils.h\nlist\n-\nmap\n-\nset\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/stl_extensions.h\nmrpt/utils/circular_buffer.h\n-\nmrpt/utils/list_searchable.h\n-\nmrpt/utils/bimap.h\n-\nmrpt/utils/map_as_vector.h\n-\nmrpt/utils/traits_map.h\n-\nmrpt/utils/stl_serialization.h\n-\nmrpt/utils/printf_vector.h\n-\nmrpt/utils/stl_containers_utils.h\n-\nmrpt/utils/ci_less.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/stl_serialization.h\nmrpt/utils/TTypeName_impl.h\n-\nmrpt/utils/metaprogramming_serialization.h\n-\nmrpt/utils/CStream.h\n-\nvector\n-\ndeque\n-\nset\n-\nmap\n-\nlist\n-\nalgorithm\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/traits_map.h\nmrpt/utils/map_as_vector.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/types_math.h\nvector\n-\ndeque\n-\nmrpt/math/math_frwds.h\n-\nfstream\n-\nctime\n-\nstdexcept\n-\nEigen/Dense\n-\nEigen/StdVector\n-\nEigen/StdDeque\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/types_simple.h\nvector\n-\nstring\n-\nmrpt/utils/mrpt_stdint.h\n-\n\n/usr/include/mrpt/base/include/mrpt/utils/utils_defs.h\nmrpt/utils/core_defs.h\n-\ncstddef\n-\ncstdlib\n-\ncmath\n-\nvector\n-\nalgorithm\n-\niostream\n-\nexception\n-\nstdexcept\n-\nsstream\n-\nmrpt/utils/bits.h\n-\nmrpt/utils/types_simple.h\n-\n\n/usr/include/mrpt/mrpt-config/mrpt/config.h\n\n/usr/include/mrpt/mrpt-config/mrpt/version.h\n\n/usr/include/mrpt/obs/include/mrpt/maps/CMetricMap.h\nmrpt/utils/CSerializable.h\n-\nmrpt/utils/TMatchingPair.h\n-\nmrpt/utils/CObservable.h\n-\nmrpt/math/math_frwds.h\n-\nmrpt/math/lightweight_geom_data.h\n-\nmrpt/opengl/opengl_frwds.h\n-\nmrpt/maps/CMetricMapEvents.h\n-\nmrpt/maps/TMetricMapInitializer.h\n-\nmrpt/maps/metric_map_types.h\n-\nmrpt/obs/obs_frwds.h\n-\nmrpt/obs/link_pragmas.h\n-\ndeque\n-\n\n/usr/include/mrpt/obs/include/mrpt/maps/CMetricMapEvents.h\nmrpt/utils/mrptEvent.h\n-\nmrpt/poses/poses_frwds.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/maps/TMetricMapInitializer.h\nmrpt/utils/CLoadableOptions.h\n-\nmrpt/utils/CObject.h\n-\nmrpt/maps/TMetricMapTypesRegistry.h\n-\nmrpt/maps/metric_map_types.h\n-\ndeque\n-\nmrpt/obs/link_pragmas.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/maps/TMetricMapTypesRegistry.h\nmrpt/utils/core_defs.h\n-\nmrpt/obs/link_pragmas.h\n-\nmrpt/obs/obs_frwds.h\n-\nmap\n-\nstring\n-\n\n/usr/include/mrpt/obs/include/mrpt/maps/metric_map_types.h\nmrpt/utils/CLoadableOptions.h\n-\nmrpt/utils/CSerializable.h\n-\nmrpt/math/lightweight_geom_data.h\n-\nmrpt/obs/obs_frwds.h\n-\nmrpt/obs/link_pragmas.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/obs/CObservation.h\nmrpt/obs/link_pragmas.h\n-\nmrpt/utils/CSerializable.h\n-\nmrpt/system/datetime.h\n-\nmrpt/math/math_frwds.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/obs/CObservation2DRangeScan.h\nmrpt/utils/CSerializable.h\n-\nmrpt/obs/CObservation.h\n-\nmrpt/poses/CPose3D.h\n-\nmrpt/maps/CMetricMap.h\n-\nmrpt/math/CPolygon.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/obs/CObservationOdometry.h\nmrpt/utils/CSerializable.h\n-\nmrpt/obs/CObservation.h\n-\nmrpt/poses/CPose2D.h\n-\nmrpt/poses/CPose3D.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/obs/link_pragmas.h\nmrpt/config.h\n-\nmrpt/utils/boost_join.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/obs/obs_frwds.h\nmrpt/poses/poses_frwds.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/slam/CObservation2DRangeScan.h\nmrpt/obs/CObservation2DRangeScan.h\n-\n\n/usr/include/mrpt/obs/include/mrpt/slam/CObservationOdometry.h\nmrpt/obs/CObservationOdometry.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl.h\nmrpt/config.h\n-\nmrpt/opengl/CRenderizable.h\n-\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/opengl/COpenGLScene.h\n-\nmrpt/opengl/COpenGLViewport.h\n-\nmrpt/opengl/CArrow.h\n-\nmrpt/opengl/CAxis.h\n-\nmrpt/opengl/CBox.h\n-\nmrpt/opengl/CFrustum.h\n-\nmrpt/opengl/CCamera.h\n-\nmrpt/opengl/CDisk.h\n-\nmrpt/opengl/CEllipsoid.h\n-\nmrpt/opengl/CGridPlaneXY.h\n-\nmrpt/opengl/CGridPlaneXZ.h\n-\nmrpt/opengl/CMesh.h\n-\nmrpt/opengl/CMeshFast.h\n-\nmrpt/opengl/CPointCloud.h\n-\nmrpt/opengl/CPointCloudColoured.h\n-\nmrpt/opengl/CSetOfLines.h\n-\nmrpt/opengl/CSetOfObjects.h\n-\nmrpt/opengl/CSetOfTriangles.h\n-\nmrpt/opengl/CSetOfTexturedTriangles.h\n-\nmrpt/opengl/CSimpleLine.h\n-\nmrpt/opengl/CSphere.h\n-\nmrpt/opengl/CText.h\n-\nmrpt/opengl/CText3D.h\n-\nmrpt/opengl/CTexturedPlane.h\n-\nmrpt/opengl/C3DSScene.h\n-\nmrpt/opengl/CAssimpModel.h\n-\nmrpt/opengl/CCylinder.h\n-\nmrpt/opengl/CPolyhedron.h\n-\nmrpt/opengl/CGeneralizedCylinder.h\n-\nmrpt/opengl/COpenGLStandardObject.h\n-\nmrpt/opengl/CFBORender.h\n-\nmrpt/opengl/CEllipsoidInverseDepth2D.h\n-\nmrpt/opengl/CEllipsoidInverseDepth3D.h\n-\nmrpt/opengl/CEllipsoidRangeBearing2D.h\n-\nmrpt/opengl/COctoMapVoxels.h\n-\nmrpt/opengl/CVectorField2D.h\n-\nmrpt/opengl/CVectorField3D.h\n-\nmrpt/opengl/stock_objects.h\n-\nmrpt/opengl/pose_pdfs.h\n-\nmrpt/opengl/graph_tools.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/C3DSScene.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/opengl/COpenGLScene.h\n-\nmrpt/utils/CMemoryChunk.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CArrow.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CAssimpModel.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/opengl/COpenGLScene.h\n-\nmrpt/utils/CMemoryChunk.h\n-\nmap\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CAxis.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CBox.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/lightweight_geom_data.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CCamera.h\nmrpt/opengl/CRenderizable.h\n-\nmrpt/poses/CPoseOrPoint.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CCylinder.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CDisk.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/poses/CPose3D.h\n-\nmrpt/math/geometry.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoid.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/CMatrixD.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth2D.h\nmrpt/opengl/CGeneralizedEllipsoidTemplate.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth3D.h\nmrpt/opengl/CGeneralizedEllipsoidTemplate.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidRangeBearing2D.h\nmrpt/opengl/CGeneralizedEllipsoidTemplate.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CFBORender.h\nmrpt/utils/CImage.h\n-\nmrpt/opengl/COpenGLScene.h\n-\nmrpt/opengl/CTextMessageCapable.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CFrustum.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/lightweight_geom_data.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedCylinder.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/opengl/CPolyhedron.h\n-\nmrpt/opengl/CSetOfTriangles.h\n-\nmrpt/math/geometry.h\n-\nmrpt/math/CMatrixTemplate.h\n-\nmrpt/utils/aligned_containers.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedEllipsoidTemplate.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/CMatrixFixedNumeric.h\n-\nmrpt/utils/types_math.h\n-\nmrpt/utils/CStream.h\n-\nmrpt/math/matrix_serialization.h\n-\nmrpt/opengl/link_pragmas.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXY.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXZ.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CLight.h\nmrpt/utils/utils_defs.h\n-\nmrpt/utils/TTypeName.h\n-\nmrpt/opengl/link_pragmas.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CMesh.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/CMatrix.h\n-\nmrpt/utils/CImage.h\n-\nmrpt/utils/color_maps.h\n-\nmrpt/opengl/CSetOfTriangles.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CMeshFast.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/CMatrix.h\n-\nmrpt/utils/CImage.h\n-\nmrpt/utils/color_maps.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/COctoMapVoxels.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/lightweight_geom_data.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/COctreePointRenderer.h\nmrpt/opengl/CRenderizable.h\n-\nmrpt/opengl/CSetOfObjects.h\n-\nmrpt/opengl/CBox.h\n-\nmrpt/opengl/gl_utils.h\n-\nmrpt/utils/aligned_containers.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLScene.h\nmrpt/opengl/CRenderizable.h\n-\nmrpt/opengl/COpenGLViewport.h\n-\nmrpt/utils/CStringList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLStandardObject.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/geometry.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLViewport.h\nmrpt/utils/CSerializable.h\n-\nmrpt/utils/safe_pointers.h\n-\nmrpt/utils/CImage.h\n-\nmrpt/opengl/CCamera.h\n-\nmrpt/opengl/CSetOfObjects.h\n-\nmrpt/opengl/CLight.h\n-\nmrpt/math/lightweight_geom_data.h\n-\nmrpt/utils/CObservable.h\n-\nmrpt/utils/CStringList.h\n-\nmrpt/utils/mrptEvent.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloud.h\nmrpt/opengl/CRenderizable.h\n-\nmrpt/opengl/COctreePointRenderer.h\n-\nmrpt/utils/PLY_import_export.h\n-\nmrpt/utils/adapters.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloudColoured.h\nmrpt/opengl/CRenderizable.h\n-\nmrpt/opengl/COctreePointRenderer.h\n-\nmrpt/utils/PLY_import_export.h\n-\nmrpt/utils/adapters.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CPolyhedron.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/geometry.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizable.h\nmrpt/utils/CSerializable.h\n-\nmrpt/utils/TColor.h\n-\nmrpt/math/math_frwds.h\n-\nmrpt/poses/CPose3D.h\n-\nmrpt/opengl/opengl_fonts.h\n-\nmrpt/opengl/link_pragmas.h\n-\nmrpt/math/lightweight_geom_data.h\n-\ndeque\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizableDisplayList.h\nmrpt/opengl/CRenderizable.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfLines.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/lightweight_geom_data.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfObjects.h\nmrpt/opengl/CRenderizable.h\n-\nmrpt/poses/poses_frwds.h\n-\nmrpt/utils/CStringList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTexturedTriangles.h\nmrpt/opengl/CTexturedObject.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTriangles.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/geometry.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CSimpleLine.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CSphere.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CText.h\nmrpt/opengl/CRenderizable.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CText3D.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CTextMessageCapable.h\nmrpt/opengl/CRenderizable.h\n-\nmrpt/opengl/opengl_fonts.h\n-\nmap\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedObject.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/utils/CImage.h\n-\nmrpt/math/geometry.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedPlane.h\nmrpt/opengl/CTexturedObject.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField2D.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/lightweight_geom_data.h\n-\nmrpt/math/CMatrix.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField3D.h\nmrpt/opengl/CRenderizableDisplayList.h\n-\nmrpt/math/lightweight_geom_data.h\n-\nmrpt/math/CMatrix.h\n-\nmrpt/utils/stl_extensions.h\n-\nEigen/Dense\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/gl_utils.h\nmrpt/utils/utils_defs.h\n-\nmrpt/opengl/opengl_fonts.h\n-\nmrpt/opengl/CRenderizable.h\n-\nmrpt/opengl/link_pragmas.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools.h\nmrpt/opengl/CSetOfObjects.h\n-\nmrpt/utils/TParameters.h\n-\ngraph_tools_impl.h\n/usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h\nmrpt/opengl/CGridPlaneXY.h\n-\nmrpt/opengl/CPointCloud.h\n-\nmrpt/opengl/CSetOfObjects.h\n-\nmrpt/opengl/CSimpleLine.h\n-\nmrpt/opengl/CSetOfLines.h\n-\nmrpt/opengl/stock_objects.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/link_pragmas.h\nmrpt/config.h\n-\nmrpt/utils/boost_join.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/opengl_fonts.h\nmrpt/utils/TColor.h\n-\nmrpt/utils/compiler_fixes.h\n-\nmrpt/opengl/link_pragmas.h\n-\nstring\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/opengl_frwds.h\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/pose_pdfs.h\nmrpt/opengl/CSetOfObjects.h\n-\n\n/usr/include/mrpt/opengl/include/mrpt/opengl/stock_objects.h\nmrpt/opengl/CSetOfObjects.h\n-\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  \"CXX\"\n  )\n# The set of files for implicit dependencies of each language:\nset(CMAKE_DEPENDS_CHECK_CXX\n  \"/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\"\n  )\nset(CMAKE_CXX_COMPILER_ID \"GNU\")\n\n# Preprocessor definitions for this target.\nset(CMAKE_TARGET_DEFINITIONS_CXX\n  \"ROSCONSOLE_BACKEND_LOG4CXX\"\n  \"ROS_PACKAGE_NAME=\\\"rf2o_laser_odometry\\\"\"\n  )\n\n# The include file search paths:\nset(CMAKE_CXX_TARGET_INCLUDE_PATH\n  \"/usr/include/eigen3\"\n  \"/usr/include/mrpt/mrpt-config\"\n  \"/usr/include/mrpt/bayes/include\"\n  \"/usr/include/mrpt/graphs/include\"\n  \"/usr/include/mrpt/vision/include\"\n  \"/usr/include/mrpt/tfest/include\"\n  \"/usr/include/mrpt/maps/include\"\n  \"/usr/include/mrpt/obs/include\"\n  \"/usr/include/mrpt/opengl/include\"\n  \"/usr/include/mrpt/base/include\"\n  \"/usr/include/mrpt/slam/include\"\n  \"/usr/include/mrpt/topography/include\"\n  \"../include\"\n  \"/opt/ros/kinetic/include\"\n  \"/opt/ros/kinetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp\"\n  )\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Include any dependencies generated for this target.\ninclude CMakeFiles/rf2o_laser_odometry_node.dir/depend.make\n\n# Include the progress variables for this target.\ninclude CMakeFiles/rf2o_laser_odometry_node.dir/progress.make\n\n# Include the compile flags for this target's objects.\ninclude CMakeFiles/rf2o_laser_odometry_node.dir/flags.make\n\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: CMakeFiles/rf2o_laser_odometry_node.dir/flags.make\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: ../src/CLaserOdometry2D.cpp\n\t@$(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\"\n\t/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\n\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.i: cmake_force\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green \"Preprocessing CXX source to CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.i\"\n\t/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\n\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.s: cmake_force\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --green \"Compiling CXX source to assembly CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.s\"\n\t/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\n\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.requires:\n\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.requires\n\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.provides: CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.requires\n\t$(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.provides.build\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.provides\n\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.provides.build: CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o\n\n\n# Object files for target rf2o_laser_odometry_node\nrf2o_laser_odometry_node_OBJECTS = \\\n\"CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o\"\n\n# External object files for target rf2o_laser_odometry_node\nrf2o_laser_odometry_node_EXTERNAL_OBJECTS =\n\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: CMakeFiles/rf2o_laser_odometry_node.dir/build.make\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libtf.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libtf2_ros.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libactionlib.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libmessage_filters.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libroscpp.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_filesystem.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_signals.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libxmlrpcpp.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libtf2.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libroscpp_serialization.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/librosconsole.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/librosconsole_log4cxx.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/librosconsole_backend_interface.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/liblog4cxx.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_regex.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/librostime.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /opt/ros/kinetic/lib/libcpp_common.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_system.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_thread.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_chrono.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_date_time.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_atomic.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libpthread.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libconsole_bridge.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_system.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_thread.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_chrono.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_date_time.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libboost_atomic.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libpthread.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: /usr/lib/x86_64-linux-gnu/libconsole_bridge.so\ndevel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node: CMakeFiles/rf2o_laser_odometry_node.dir/link.txt\n\t@$(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\"\n\t$(CMAKE_COMMAND) -E cmake_link_script CMakeFiles/rf2o_laser_odometry_node.dir/link.txt --verbose=$(VERBOSE)\n\n# Rule to build all files generated by this target.\nCMakeFiles/rf2o_laser_odometry_node.dir/build: devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node\n\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/build\n\nCMakeFiles/rf2o_laser_odometry_node.dir/requires: CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o.requires\n\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/requires\n\nCMakeFiles/rf2o_laser_odometry_node.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/rf2o_laser_odometry_node.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/clean\n\nCMakeFiles/rf2o_laser_odometry_node.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/rf2o_laser_odometry_node.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/cmake_clean.cmake",
    "content": "file(REMOVE_RECURSE\n  \"CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o\"\n  \"devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node.pdb\"\n  \"devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node\"\n)\n\n# Per-language clean rules from dependency scanning.\nforeach(lang CXX)\n  include(CMakeFiles/rf2o_laser_odometry_node.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/depend.internal",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o\n ../include/rf2o_laser_odometry/CLaserOdometry2D.h\n /home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp\n /opt/ros/kinetic/include/boost_161_condition_variable.h\n /opt/ros/kinetic/include/boost_161_pthread_condition_variable.h\n /opt/ros/kinetic/include/boost_161_pthread_condition_variable_fwd.h\n /opt/ros/kinetic/include/geometry_msgs/Point.h\n /opt/ros/kinetic/include/geometry_msgs/Point32.h\n /opt/ros/kinetic/include/geometry_msgs/PointStamped.h\n /opt/ros/kinetic/include/geometry_msgs/Pose.h\n /opt/ros/kinetic/include/geometry_msgs/PoseStamped.h\n /opt/ros/kinetic/include/geometry_msgs/PoseWithCovariance.h\n /opt/ros/kinetic/include/geometry_msgs/Quaternion.h\n /opt/ros/kinetic/include/geometry_msgs/QuaternionStamped.h\n /opt/ros/kinetic/include/geometry_msgs/Transform.h\n /opt/ros/kinetic/include/geometry_msgs/TransformStamped.h\n /opt/ros/kinetic/include/geometry_msgs/Twist.h\n /opt/ros/kinetic/include/geometry_msgs/TwistStamped.h\n /opt/ros/kinetic/include/geometry_msgs/TwistWithCovariance.h\n /opt/ros/kinetic/include/geometry_msgs/Vector3.h\n /opt/ros/kinetic/include/geometry_msgs/Vector3Stamped.h\n /opt/ros/kinetic/include/nav_msgs/Odometry.h\n /opt/ros/kinetic/include/ros/advertise_options.h\n /opt/ros/kinetic/include/ros/advertise_service_options.h\n /opt/ros/kinetic/include/ros/assert.h\n /opt/ros/kinetic/include/ros/builtin_message_traits.h\n /opt/ros/kinetic/include/ros/callback_queue.h\n /opt/ros/kinetic/include/ros/callback_queue_interface.h\n /opt/ros/kinetic/include/ros/common.h\n /opt/ros/kinetic/include/ros/console.h\n /opt/ros/kinetic/include/ros/console_backend.h\n /opt/ros/kinetic/include/ros/datatypes.h\n /opt/ros/kinetic/include/ros/duration.h\n /opt/ros/kinetic/include/ros/exception.h\n /opt/ros/kinetic/include/ros/exceptions.h\n /opt/ros/kinetic/include/ros/forwards.h\n /opt/ros/kinetic/include/ros/init.h\n /opt/ros/kinetic/include/ros/macros.h\n /opt/ros/kinetic/include/ros/master.h\n /opt/ros/kinetic/include/ros/message.h\n /opt/ros/kinetic/include/ros/message_event.h\n /opt/ros/kinetic/include/ros/message_forward.h\n /opt/ros/kinetic/include/ros/message_operations.h\n /opt/ros/kinetic/include/ros/message_traits.h\n /opt/ros/kinetic/include/ros/names.h\n /opt/ros/kinetic/include/ros/node_handle.h\n /opt/ros/kinetic/include/ros/param.h\n /opt/ros/kinetic/include/ros/parameter_adapter.h\n /opt/ros/kinetic/include/ros/platform.h\n /opt/ros/kinetic/include/ros/publisher.h\n /opt/ros/kinetic/include/ros/rate.h\n /opt/ros/kinetic/include/ros/ros.h\n /opt/ros/kinetic/include/ros/roscpp_serialization_macros.h\n /opt/ros/kinetic/include/ros/rostime_decl.h\n /opt/ros/kinetic/include/ros/serialization.h\n /opt/ros/kinetic/include/ros/serialized_message.h\n /opt/ros/kinetic/include/ros/service.h\n /opt/ros/kinetic/include/ros/service_callback_helper.h\n /opt/ros/kinetic/include/ros/service_client.h\n /opt/ros/kinetic/include/ros/service_client_options.h\n /opt/ros/kinetic/include/ros/service_server.h\n /opt/ros/kinetic/include/ros/service_traits.h\n /opt/ros/kinetic/include/ros/single_subscriber_publisher.h\n /opt/ros/kinetic/include/ros/spinner.h\n /opt/ros/kinetic/include/ros/static_assert.h\n /opt/ros/kinetic/include/ros/steady_timer.h\n /opt/ros/kinetic/include/ros/steady_timer_options.h\n /opt/ros/kinetic/include/ros/subscribe_options.h\n /opt/ros/kinetic/include/ros/subscriber.h\n /opt/ros/kinetic/include/ros/subscription_callback_helper.h\n /opt/ros/kinetic/include/ros/this_node.h\n /opt/ros/kinetic/include/ros/time.h\n /opt/ros/kinetic/include/ros/timer.h\n /opt/ros/kinetic/include/ros/timer_options.h\n /opt/ros/kinetic/include/ros/topic.h\n /opt/ros/kinetic/include/ros/transport_hints.h\n /opt/ros/kinetic/include/ros/types.h\n /opt/ros/kinetic/include/ros/wall_timer.h\n /opt/ros/kinetic/include/ros/wall_timer_options.h\n /opt/ros/kinetic/include/rosconsole/macros_generated.h\n /opt/ros/kinetic/include/sensor_msgs/ChannelFloat32.h\n /opt/ros/kinetic/include/sensor_msgs/LaserScan.h\n /opt/ros/kinetic/include/sensor_msgs/PointCloud.h\n /opt/ros/kinetic/include/std_msgs/Empty.h\n /opt/ros/kinetic/include/std_msgs/Header.h\n /opt/ros/kinetic/include/tf/FrameGraph.h\n /opt/ros/kinetic/include/tf/FrameGraphRequest.h\n /opt/ros/kinetic/include/tf/FrameGraphResponse.h\n /opt/ros/kinetic/include/tf/LinearMath/Matrix3x3.h\n /opt/ros/kinetic/include/tf/LinearMath/MinMax.h\n /opt/ros/kinetic/include/tf/LinearMath/QuadWord.h\n /opt/ros/kinetic/include/tf/LinearMath/Quaternion.h\n /opt/ros/kinetic/include/tf/LinearMath/Scalar.h\n /opt/ros/kinetic/include/tf/LinearMath/Transform.h\n /opt/ros/kinetic/include/tf/LinearMath/Vector3.h\n /opt/ros/kinetic/include/tf/exceptions.h\n /opt/ros/kinetic/include/tf/tf.h\n /opt/ros/kinetic/include/tf/tfMessage.h\n /opt/ros/kinetic/include/tf/time_cache.h\n /opt/ros/kinetic/include/tf/transform_broadcaster.h\n /opt/ros/kinetic/include/tf/transform_datatypes.h\n /opt/ros/kinetic/include/tf/transform_listener.h\n /opt/ros/kinetic/include/tf2/LinearMath/Quaternion.h\n /opt/ros/kinetic/include/tf2/LinearMath/Vector3.h\n /opt/ros/kinetic/include/tf2/buffer_core.h\n /opt/ros/kinetic/include/tf2/convert.h\n /opt/ros/kinetic/include/tf2/exceptions.h\n /opt/ros/kinetic/include/tf2/impl/convert.h\n /opt/ros/kinetic/include/tf2/transform_datatypes.h\n /opt/ros/kinetic/include/tf2/transform_storage.h\n /opt/ros/kinetic/include/tf2_msgs/FrameGraph.h\n /opt/ros/kinetic/include/tf2_msgs/FrameGraphRequest.h\n /opt/ros/kinetic/include/tf2_msgs/FrameGraphResponse.h\n /opt/ros/kinetic/include/tf2_msgs/TFMessage.h\n /opt/ros/kinetic/include/tf2_ros/buffer.h\n /opt/ros/kinetic/include/tf2_ros/buffer_interface.h\n /opt/ros/kinetic/include/tf2_ros/transform_broadcaster.h\n /opt/ros/kinetic/include/tf2_ros/transform_listener.h\n /opt/ros/kinetic/include/xmlrpcpp/XmlRpcDecl.h\n /opt/ros/kinetic/include/xmlrpcpp/XmlRpcValue.h\n /usr/include/eigen3/Eigen/Cholesky\n /usr/include/eigen3/Eigen/Core\n /usr/include/eigen3/Eigen/Dense\n /usr/include/eigen3/Eigen/Eigenvalues\n /usr/include/eigen3/Eigen/Geometry\n /usr/include/eigen3/Eigen/Householder\n /usr/include/eigen3/Eigen/Jacobi\n /usr/include/eigen3/Eigen/LU\n /usr/include/eigen3/Eigen/QR\n /usr/include/eigen3/Eigen/SVD\n /usr/include/eigen3/Eigen/StdDeque\n /usr/include/eigen3/Eigen/StdVector\n /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h\n /usr/include/eigen3/Eigen/src/Cholesky/LLT.h\n /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h\n /usr/include/eigen3/Eigen/src/Core/Array.h\n /usr/include/eigen3/Eigen/src/Core/ArrayBase.h\n /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h\n /usr/include/eigen3/Eigen/src/Core/Assign.h\n /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h\n /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h\n /usr/include/eigen3/Eigen/src/Core/BandMatrix.h\n /usr/include/eigen3/Eigen/src/Core/Block.h\n /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h\n /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h\n /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h\n /usr/include/eigen3/Eigen/src/Core/CoreIterators.h\n /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h\n /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h\n /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h\n /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h\n /usr/include/eigen3/Eigen/src/Core/DenseBase.h\n /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h\n /usr/include/eigen3/Eigen/src/Core/DenseStorage.h\n /usr/include/eigen3/Eigen/src/Core/Diagonal.h\n /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h\n /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h\n /usr/include/eigen3/Eigen/src/Core/Dot.h\n /usr/include/eigen3/Eigen/src/Core/EigenBase.h\n /usr/include/eigen3/Eigen/src/Core/Fuzzy.h\n /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h\n /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h\n /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h\n /usr/include/eigen3/Eigen/src/Core/IO.h\n /usr/include/eigen3/Eigen/src/Core/Inverse.h\n /usr/include/eigen3/Eigen/src/Core/Map.h\n /usr/include/eigen3/Eigen/src/Core/MapBase.h\n /usr/include/eigen3/Eigen/src/Core/MathFunctions.h\n /usr/include/eigen3/Eigen/src/Core/Matrix.h\n /usr/include/eigen3/Eigen/src/Core/MatrixBase.h\n /usr/include/eigen3/Eigen/src/Core/NestByValue.h\n /usr/include/eigen3/Eigen/src/Core/NoAlias.h\n /usr/include/eigen3/Eigen/src/Core/NumTraits.h\n /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h\n /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h\n /usr/include/eigen3/Eigen/src/Core/Product.h\n /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h\n /usr/include/eigen3/Eigen/src/Core/Random.h\n /usr/include/eigen3/Eigen/src/Core/Redux.h\n /usr/include/eigen3/Eigen/src/Core/Ref.h\n /usr/include/eigen3/Eigen/src/Core/Replicate.h\n /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h\n /usr/include/eigen3/Eigen/src/Core/Reverse.h\n /usr/include/eigen3/Eigen/src/Core/Select.h\n /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h\n /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h\n /usr/include/eigen3/Eigen/src/Core/Solve.h\n /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h\n /usr/include/eigen3/Eigen/src/Core/SolverBase.h\n /usr/include/eigen3/Eigen/src/Core/SpecialFunctions.h\n /usr/include/eigen3/Eigen/src/Core/StableNorm.h\n /usr/include/eigen3/Eigen/src/Core/Stride.h\n /usr/include/eigen3/Eigen/src/Core/Swap.h\n /usr/include/eigen3/Eigen/src/Core/Transpose.h\n /usr/include/eigen3/Eigen/src/Core/Transpositions.h\n /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h\n /usr/include/eigen3/Eigen/src/Core/VectorBlock.h\n /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h\n /usr/include/eigen3/Eigen/src/Core/Visitor.h\n /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h\n /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h\n /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h\n /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h\n /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h\n /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h\n /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h\n /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h\n /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h\n /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h\n /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h\n /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h\n /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h\n /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h\n /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h\n /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h\n /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h\n /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h\n /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h\n /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h\n /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h\n /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h\n /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h\n /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h\n /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h\n /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h\n /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h\n /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h\n /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h\n /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h\n /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h\n /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h\n /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h\n /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h\n /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h\n /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h\n /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h\n /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h\n /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h\n /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h\n /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h\n /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h\n /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h\n /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h\n /usr/include/eigen3/Eigen/src/Core/util/Constants.h\n /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\n /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h\n /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h\n /usr/include/eigen3/Eigen/src/Core/util/Macros.h\n /usr/include/eigen3/Eigen/src/Core/util/Memory.h\n /usr/include/eigen3/Eigen/src/Core/util/Meta.h\n /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\n /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h\n /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h\n /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h\n /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h\n /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h\n /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h\n /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h\n /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h\n /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h\n /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h\n /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h\n /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h\n /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h\n /usr/include/eigen3/Eigen/src/Geometry/Scaling.h\n /usr/include/eigen3/Eigen/src/Geometry/Transform.h\n /usr/include/eigen3/Eigen/src/Geometry/Translation.h\n /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h\n /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h\n /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h\n /usr/include/eigen3/Eigen/src/Householder/Householder.h\n /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h\n /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h\n /usr/include/eigen3/Eigen/src/LU/Determinant.h\n /usr/include/eigen3/Eigen/src/LU/FullPivLU.h\n /usr/include/eigen3/Eigen/src/LU/InverseImpl.h\n /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h\n /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h\n /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h\n /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h\n /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h\n /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h\n /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h\n /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h\n /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h\n /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h\n /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h\n /usr/include/eigen3/Eigen/src/SVD/SVDBase.h\n /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h\n /usr/include/eigen3/Eigen/src/StlSupport/StdDeque.h\n /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h\n /usr/include/eigen3/Eigen/src/StlSupport/details.h\n /usr/include/eigen3/Eigen/src/misc/Image.h\n /usr/include/eigen3/Eigen/src/misc/Kernel.h\n /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h\n /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h\n /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h\n /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h\n /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h\n /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h\n /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h\n /usr/include/eigen3/unsupported/Eigen/MatrixFunctions\n /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h\n /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h\n /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h\n /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h\n /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h\n /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h\n /usr/include/mrpt/base/include/mrpt/base/link_pragmas.h\n /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilter.h\n /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterCapable.h\n /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterData.h\n /usr/include/mrpt/base/include/mrpt/bayes/CProbabilityParticle.h\n /usr/include/mrpt/base/include/mrpt/math/CArray.h\n /usr/include/mrpt/base/include/mrpt/math/CArrayNumeric.h\n /usr/include/mrpt/base/include/mrpt/math/CHistogram.h\n /usr/include/mrpt/base/include/mrpt/math/CMatrix.h\n /usr/include/mrpt/base/include/mrpt/math/CMatrixD.h\n /usr/include/mrpt/base/include/mrpt/math/CMatrixFixedNumeric.h\n /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplate.h\n /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplateNumeric.h\n /usr/include/mrpt/base/include/mrpt/math/CPolygon.h\n /usr/include/mrpt/base/include/mrpt/math/CQuaternion.h\n /usr/include/mrpt/base/include/mrpt/math/CSparseMatrixTemplate.h\n /usr/include/mrpt/base/include/mrpt/math/eigen_frwds.h\n /usr/include/mrpt/base/include/mrpt/math/geometry.h\n /usr/include/mrpt/base/include/mrpt/math/homog_matrices.h\n /usr/include/mrpt/base/include/mrpt/math/lightweight_geom_data.h\n /usr/include/mrpt/base/include/mrpt/math/math_frwds.h\n /usr/include/mrpt/base/include/mrpt/math/matrix_serialization.h\n /usr/include/mrpt/base/include/mrpt/math/point_poses2vectors.h\n /usr/include/mrpt/base/include/mrpt/math/wrap2pi.h\n /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/containers_fixes.hpp\n /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/exceptions.hpp\n /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.hpp\n /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.tpp\n /usr/include/mrpt/base/include/mrpt/poses.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoint.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoint2D.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDF.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDFGaussian.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoint3D.h\n /usr/include/mrpt/base/include/mrpt/poses/CPointPDF.h\n /usr/include/mrpt/base/include/mrpt/poses/CPointPDFGaussian.h\n /usr/include/mrpt/base/include/mrpt/poses/CPointPDFParticles.h\n /usr/include/mrpt/base/include/mrpt/poses/CPointPDFSOG.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose2D.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose2DGridTemplate.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3D.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DInterpolator.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDF.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussian.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussianInf.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFParticles.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFSOG.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuat.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDF.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussian.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h\n /usr/include/mrpt/base/include/mrpt/poses/CPose3DRotVec.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint_detail.h\n /usr/include/mrpt/base/include/mrpt/poses/CPosePDF.h\n /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussian.h\n /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussianInf.h\n /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGrid.h\n /usr/include/mrpt/base/include/mrpt/poses/CPosePDFParticles.h\n /usr/include/mrpt/base/include/mrpt/poses/CPosePDFSOG.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoseRandomSampler.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoses2DSequence.h\n /usr/include/mrpt/base/include/mrpt/poses/CPoses3DSequence.h\n /usr/include/mrpt/base/include/mrpt/poses/CRobot2DPoseEstimator.h\n /usr/include/mrpt/base/include/mrpt/poses/SE_traits.h\n /usr/include/mrpt/base/include/mrpt/poses/poses_frwds.h\n /usr/include/mrpt/base/include/mrpt/synch/CCriticalSection.h\n /usr/include/mrpt/base/include/mrpt/synch/atomic_incr.h\n /usr/include/mrpt/base/include/mrpt/system/datetime.h\n /usr/include/mrpt/base/include/mrpt/system/memory.h\n /usr/include/mrpt/base/include/mrpt/system/os.h\n /usr/include/mrpt/base/include/mrpt/system/string_utils.h\n /usr/include/mrpt/base/include/mrpt/system/threads.h\n /usr/include/mrpt/base/include/mrpt/utils.h\n /usr/include/mrpt/base/include/mrpt/utils/CCanvas.h\n /usr/include/mrpt/base/include/mrpt/utils/CClientTCPSocket.h\n /usr/include/mrpt/base/include/mrpt/utils/CConfigFile.h\n /usr/include/mrpt/base/include/mrpt/utils/CConfigFileBase.h\n /usr/include/mrpt/base/include/mrpt/utils/CConfigFileMemory.h\n /usr/include/mrpt/base/include/mrpt/utils/CConsoleRedirector.h\n /usr/include/mrpt/base/include/mrpt/utils/CDebugOutputCapable.h\n /usr/include/mrpt/base/include/mrpt/utils/CDynamicGrid.h\n /usr/include/mrpt/base/include/mrpt/utils/CEnhancedMetaFile.h\n /usr/include/mrpt/base/include/mrpt/utils/CFileGZInputStream.h\n /usr/include/mrpt/base/include/mrpt/utils/CFileGZOutputStream.h\n /usr/include/mrpt/base/include/mrpt/utils/CFileInputStream.h\n /usr/include/mrpt/base/include/mrpt/utils/CFileOutputStream.h\n /usr/include/mrpt/base/include/mrpt/utils/CFileStream.h\n /usr/include/mrpt/base/include/mrpt/utils/CImage.h\n /usr/include/mrpt/base/include/mrpt/utils/CListOfClasses.h\n /usr/include/mrpt/base/include/mrpt/utils/CLoadableOptions.h\n /usr/include/mrpt/base/include/mrpt/utils/CLog.h\n /usr/include/mrpt/base/include/mrpt/utils/CMHPropertiesValuesList.h\n /usr/include/mrpt/base/include/mrpt/utils/CMappedImage.h\n /usr/include/mrpt/base/include/mrpt/utils/CMemoryChunk.h\n /usr/include/mrpt/base/include/mrpt/utils/CMemoryStream.h\n /usr/include/mrpt/base/include/mrpt/utils/CMessage.h\n /usr/include/mrpt/base/include/mrpt/utils/CMessageQueue.h\n /usr/include/mrpt/base/include/mrpt/utils/CObject.h\n /usr/include/mrpt/base/include/mrpt/utils/CObservable.h\n /usr/include/mrpt/base/include/mrpt/utils/CObserver.h\n /usr/include/mrpt/base/include/mrpt/utils/CProbabilityDensityFunction.h\n /usr/include/mrpt/base/include/mrpt/utils/CPropertiesValuesList.h\n /usr/include/mrpt/base/include/mrpt/utils/CReferencedMemBlock.h\n /usr/include/mrpt/base/include/mrpt/utils/CRobotSimulator.h\n /usr/include/mrpt/base/include/mrpt/utils/CSerializable.h\n /usr/include/mrpt/base/include/mrpt/utils/CServerTCPSocket.h\n /usr/include/mrpt/base/include/mrpt/utils/CSimpleDatabase.h\n /usr/include/mrpt/base/include/mrpt/utils/CStartUpClassesRegister.h\n /usr/include/mrpt/base/include/mrpt/utils/CStdOutStream.h\n /usr/include/mrpt/base/include/mrpt/utils/CStream.h\n /usr/include/mrpt/base/include/mrpt/utils/CStringList.h\n /usr/include/mrpt/base/include/mrpt/utils/CTextFileLinesParser.h\n /usr/include/mrpt/base/include/mrpt/utils/CThreadSafeQueue.h\n /usr/include/mrpt/base/include/mrpt/utils/CTicTac.h\n /usr/include/mrpt/base/include/mrpt/utils/CTimeLogger.h\n /usr/include/mrpt/base/include/mrpt/utils/CTypeSelector.h\n /usr/include/mrpt/base/include/mrpt/utils/CUncopiable.h\n /usr/include/mrpt/base/include/mrpt/utils/PLY_import_export.h\n /usr/include/mrpt/base/include/mrpt/utils/SSE_types.h\n /usr/include/mrpt/base/include/mrpt/utils/TCamera.h\n /usr/include/mrpt/base/include/mrpt/utils/TColor.h\n /usr/include/mrpt/base/include/mrpt/utils/TEnumType.h\n /usr/include/mrpt/base/include/mrpt/utils/TMatchingPair.h\n /usr/include/mrpt/base/include/mrpt/utils/TParameters.h\n /usr/include/mrpt/base/include/mrpt/utils/TPixelCoord.h\n /usr/include/mrpt/base/include/mrpt/utils/TStereoCamera.h\n /usr/include/mrpt/base/include/mrpt/utils/TTypeName.h\n /usr/include/mrpt/base/include/mrpt/utils/TTypeName_impl.h\n /usr/include/mrpt/base/include/mrpt/utils/adapters.h\n /usr/include/mrpt/base/include/mrpt/utils/aligned_containers.h\n /usr/include/mrpt/base/include/mrpt/utils/bimap.h\n /usr/include/mrpt/base/include/mrpt/utils/bits.h\n /usr/include/mrpt/base/include/mrpt/utils/boost_join.h\n /usr/include/mrpt/base/include/mrpt/utils/ci_less.h\n /usr/include/mrpt/base/include/mrpt/utils/circular_buffer.h\n /usr/include/mrpt/base/include/mrpt/utils/color_maps.h\n /usr/include/mrpt/base/include/mrpt/utils/compiler_fixes.h\n /usr/include/mrpt/base/include/mrpt/utils/core_defs.h\n /usr/include/mrpt/base/include/mrpt/utils/crc.h\n /usr/include/mrpt/base/include/mrpt/utils/exceptions.h\n /usr/include/mrpt/base/include/mrpt/utils/list_searchable.h\n /usr/include/mrpt/base/include/mrpt/utils/map_as_vector.h\n /usr/include/mrpt/base/include/mrpt/utils/md5.h\n /usr/include/mrpt/base/include/mrpt/utils/metaprogramming_serialization.h\n /usr/include/mrpt/base/include/mrpt/utils/mrptEvent.h\n /usr/include/mrpt/base/include/mrpt/utils/mrpt_macros.h\n /usr/include/mrpt/base/include/mrpt/utils/mrpt_stdint.h\n /usr/include/mrpt/base/include/mrpt/utils/net_utils.h\n /usr/include/mrpt/base/include/mrpt/utils/printf_vector.h\n /usr/include/mrpt/base/include/mrpt/utils/pstdint.h\n /usr/include/mrpt/base/include/mrpt/utils/round.h\n /usr/include/mrpt/base/include/mrpt/utils/safe_pointers.h\n /usr/include/mrpt/base/include/mrpt/utils/stl_containers_utils.h\n /usr/include/mrpt/base/include/mrpt/utils/stl_extensions.h\n /usr/include/mrpt/base/include/mrpt/utils/stl_serialization.h\n /usr/include/mrpt/base/include/mrpt/utils/traits_map.h\n /usr/include/mrpt/base/include/mrpt/utils/types_math.h\n /usr/include/mrpt/base/include/mrpt/utils/types_simple.h\n /usr/include/mrpt/base/include/mrpt/utils/utils_defs.h\n /usr/include/mrpt/mrpt-config/mrpt/config.h\n /usr/include/mrpt/mrpt-config/mrpt/version.h\n /usr/include/mrpt/obs/include/mrpt/maps/CMetricMap.h\n /usr/include/mrpt/obs/include/mrpt/maps/CMetricMapEvents.h\n /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapInitializer.h\n /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapTypesRegistry.h\n /usr/include/mrpt/obs/include/mrpt/maps/metric_map_types.h\n /usr/include/mrpt/obs/include/mrpt/obs/CObservation.h\n /usr/include/mrpt/obs/include/mrpt/obs/CObservation2DRangeScan.h\n /usr/include/mrpt/obs/include/mrpt/obs/CObservationOdometry.h\n /usr/include/mrpt/obs/include/mrpt/obs/link_pragmas.h\n /usr/include/mrpt/obs/include/mrpt/obs/obs_frwds.h\n /usr/include/mrpt/obs/include/mrpt/slam/CObservation2DRangeScan.h\n /usr/include/mrpt/obs/include/mrpt/slam/CObservationOdometry.h\n /usr/include/mrpt/opengl/include/mrpt/opengl.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/C3DSScene.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CArrow.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CAssimpModel.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CAxis.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CBox.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CCamera.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CCylinder.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CDisk.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoid.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth2D.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth3D.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidRangeBearing2D.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CFBORender.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CFrustum.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedCylinder.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedEllipsoidTemplate.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXY.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXZ.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CLight.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CMesh.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CMeshFast.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/COctoMapVoxels.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/COctreePointRenderer.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLScene.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLStandardObject.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLViewport.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloud.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloudColoured.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CPolyhedron.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizable.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizableDisplayList.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfLines.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfObjects.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTexturedTriangles.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTriangles.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CSimpleLine.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CSphere.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CText.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CText3D.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CTextMessageCapable.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedObject.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedPlane.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField2D.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField3D.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/gl_utils.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/link_pragmas.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_fonts.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_frwds.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/pose_pdfs.h\n /usr/include/mrpt/opengl/include/mrpt/opengl/stock_objects.h\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/depend.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: ../include/rf2o_laser_odometry/CLaserOdometry2D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: ../src/CLaserOdometry2D.cpp\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/boost_161_condition_variable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/boost_161_pthread_condition_variable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/boost_161_pthread_condition_variable_fwd.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Point.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Point32.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/PointStamped.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Pose.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/PoseStamped.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/PoseWithCovariance.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Quaternion.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/QuaternionStamped.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Transform.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/TransformStamped.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Twist.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/TwistStamped.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/TwistWithCovariance.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Vector3.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/geometry_msgs/Vector3Stamped.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/nav_msgs/Odometry.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/advertise_options.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/advertise_service_options.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/assert.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/builtin_message_traits.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/callback_queue.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/callback_queue_interface.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/common.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/console.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/console_backend.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/datatypes.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/duration.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/exception.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/exceptions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/forwards.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/init.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/macros.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/master.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message_event.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message_forward.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message_operations.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/message_traits.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/names.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/node_handle.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/param.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/parameter_adapter.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/platform.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/publisher.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/rate.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/ros.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/roscpp_serialization_macros.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/rostime_decl.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/serialization.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/serialized_message.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_callback_helper.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_client.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_client_options.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_server.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/service_traits.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/single_subscriber_publisher.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/spinner.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/static_assert.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/steady_timer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/steady_timer_options.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/subscribe_options.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/subscriber.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/subscription_callback_helper.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/this_node.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/time.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/timer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/timer_options.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/topic.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/transport_hints.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/types.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/wall_timer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/ros/wall_timer_options.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/rosconsole/macros_generated.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/sensor_msgs/ChannelFloat32.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/sensor_msgs/LaserScan.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/sensor_msgs/PointCloud.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/std_msgs/Empty.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/std_msgs/Header.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/FrameGraph.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/FrameGraphRequest.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/FrameGraphResponse.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Matrix3x3.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/MinMax.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/QuadWord.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Quaternion.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Scalar.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Transform.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/LinearMath/Vector3.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/exceptions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/tf.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/tfMessage.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/time_cache.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/transform_broadcaster.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/transform_datatypes.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf/transform_listener.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/LinearMath/Quaternion.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/LinearMath/Vector3.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/buffer_core.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/convert.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/exceptions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/impl/convert.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/transform_datatypes.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2/transform_storage.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_msgs/FrameGraph.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_msgs/FrameGraphRequest.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_msgs/FrameGraphResponse.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_msgs/TFMessage.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_ros/buffer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_ros/buffer_interface.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_ros/transform_broadcaster.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/tf2_ros/transform_listener.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/xmlrpcpp/XmlRpcDecl.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /opt/ros/kinetic/include/xmlrpcpp/XmlRpcValue.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Cholesky\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Core\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Dense\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Eigenvalues\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Geometry\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Householder\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/Jacobi\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/LU\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/QR\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/SVD\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/StdDeque\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/StdVector\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LDLT.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Cholesky/LLT_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Array.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/ArrayWrapper.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/AssignEvaluator.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Assign_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/BandMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Block.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/BooleanRedux.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CommaInitializer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreEvaluators.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CoreIterators.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseBinaryOp.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseNullaryOp.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryOp.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/CwiseUnaryView.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseCoeffsBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Diagonal.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/DiagonalProduct.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Dot.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/EigenBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Fuzzy.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/GeneralProduct.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/GenericPacketMath.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/GlobalFunctions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/IO.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Inverse.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Map.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/MapBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/MathFunctions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Matrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/MatrixBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/NestByValue.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/NoAlias.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/NumTraits.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/PermutationMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/PlainObjectBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Product.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/ProductEvaluators.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Random.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Redux.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Ref.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Replicate.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/ReturnByValue.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Reverse.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Select.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfAdjointView.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SelfCwiseBinaryOp.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Solve.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolveTriangular.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SolverBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/SpecialFunctions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/StableNorm.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Stride.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Swap.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpose.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Transpositions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/TriangularMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorBlock.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/VectorwiseOp.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/Visitor.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/Complex.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/MathFunctions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/PacketMath.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AVX/TypeCasting.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/Complex.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/MathFunctions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/AltiVec/PacketMath.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/MathFunctions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/CUDA/PacketMath.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/Default/Settings.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/Complex.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/MathFunctions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/NEON/PacketMath.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/Complex.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/MathFunctions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/PacketMath.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/arch/SSE/TypeCasting.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/AssignmentFunctors.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/BinaryFunctors.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/NullaryFunctors.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/StlFunctors.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/functors/UnaryFunctors.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralBlockPanelKernel.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrixTriangular_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixMatrix_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/GeneralMatrixVector_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/Parallelizer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixMatrix_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointMatrixVector_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointProduct.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/SelfadjointRank2Update.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixMatrix_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularMatrixVector_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverMatrix_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/products/TriangularSolverVector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/BlasUtil.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Constants.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/DisableStupidWarnings.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/MKL_support.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Macros.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Memory.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/Meta.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/ReenableStupidWarnings.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/StaticAssert.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Core/util/XprHelper.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./ComplexSchur.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./HessenbergDecomposition.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealQZ.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./RealSchur.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/./Tridiagonalization.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexEigenSolver.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/ComplexSchur_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/EigenSolver.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/HessenbergDecomposition.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealQZ.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/RealSchur_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Eigenvalues/Tridiagonalization.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AlignedBox.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/AngleAxis.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/EulerAngles.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Homogeneous.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Hyperplane.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/OrthoMethods.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/ParametrizedLine.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Quaternion.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Rotation2D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/RotationBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Scaling.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Transform.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Translation.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/Umeyama.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Geometry/arch/Geometry_SSE.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Householder/BlockHouseholder.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Householder/Householder.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Householder/HouseholderSequence.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/Jacobi/Jacobi.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/Determinant.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/FullPivLU.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/InverseImpl.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/PartialPivLU_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/LU/arch/Inverse_SSE.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/ColPivHouseholderQR_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/FullPivHouseholderQR.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/QR/HouseholderQR_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/BDCSVD.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/JacobiSVD_MKL.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/SVDBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/SVD/UpperBidiagonalization.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdDeque.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/StdVector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/StlSupport/details.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/misc/Image.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/misc/Kernel.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseBinaryOps.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/ArrayCwiseUnaryOps.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/BlockMethods.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseBinaryOps.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/CommonCwiseUnaryOps.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseBinaryOps.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/Eigen/src/plugins/MatrixCwiseUnaryOps.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/MatrixFunctions\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/eigen3/unsupported/Eigen/src/MatrixFunctions/StemFunction.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/base/link_pragmas.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilter.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterCapable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/bayes/CParticleFilterData.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/bayes/CProbabilityParticle.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CArray.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CArrayNumeric.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CHistogram.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrix.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrixD.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrixFixedNumeric.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplate.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CMatrixTemplateNumeric.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CPolygon.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CQuaternion.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/CSparseMatrixTemplate.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/eigen_frwds.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/geometry.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/homog_matrices.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/lightweight_geom_data.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/math_frwds.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/matrix_serialization.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/point_poses2vectors.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/math/wrap2pi.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/containers_fixes.hpp\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/exceptions.hpp\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.hpp\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/otherlibs/stlplus/smart_ptr.tpp\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint2D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDF.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint2DPDFGaussian.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoint3D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPointPDF.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPointPDFGaussian.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPointPDFParticles.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPointPDFSOG.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose2D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose2DGridTemplate.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DInterpolator.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDF.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussian.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFGaussianInf.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFParticles.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DPDFSOG.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuat.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDF.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussian.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DQuatPDFGaussianInf.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPose3DRotVec.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoseOrPoint_detail.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDF.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussian.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGaussianInf.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFGrid.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFParticles.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPosePDFSOG.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoseRandomSampler.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoses2DSequence.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CPoses3DSequence.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/CRobot2DPoseEstimator.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/SE_traits.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/poses/poses_frwds.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/synch/CCriticalSection.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/synch/atomic_incr.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/datetime.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/memory.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/os.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/string_utils.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/system/threads.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CCanvas.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CClientTCPSocket.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CConfigFile.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CConfigFileBase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CConfigFileMemory.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CConsoleRedirector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CDebugOutputCapable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CDynamicGrid.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CEnhancedMetaFile.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileGZInputStream.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileGZOutputStream.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileInputStream.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileOutputStream.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CFileStream.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CImage.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CListOfClasses.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CLoadableOptions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CLog.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMHPropertiesValuesList.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMappedImage.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMemoryChunk.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMemoryStream.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMessage.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CMessageQueue.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CObject.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CObservable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CObserver.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CProbabilityDensityFunction.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CPropertiesValuesList.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CReferencedMemBlock.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CRobotSimulator.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CSerializable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CServerTCPSocket.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CSimpleDatabase.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CStartUpClassesRegister.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CStdOutStream.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CStream.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CStringList.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CTextFileLinesParser.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CThreadSafeQueue.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CTicTac.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CTimeLogger.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CTypeSelector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/CUncopiable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/PLY_import_export.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/SSE_types.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TCamera.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TColor.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TEnumType.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TMatchingPair.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TParameters.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TPixelCoord.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TStereoCamera.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TTypeName.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/TTypeName_impl.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/adapters.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/aligned_containers.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/bimap.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/bits.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/boost_join.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/ci_less.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/circular_buffer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/color_maps.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/compiler_fixes.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/core_defs.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/crc.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/exceptions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/list_searchable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/map_as_vector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/md5.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/metaprogramming_serialization.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/mrptEvent.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/mrpt_macros.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/mrpt_stdint.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/net_utils.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/printf_vector.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/pstdint.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/round.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/safe_pointers.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/stl_containers_utils.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/stl_extensions.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/stl_serialization.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/traits_map.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/types_math.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/types_simple.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/base/include/mrpt/utils/utils_defs.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/mrpt-config/mrpt/config.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/mrpt-config/mrpt/version.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/CMetricMap.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/CMetricMapEvents.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapInitializer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/TMetricMapTypesRegistry.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/maps/metric_map_types.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/CObservation.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/CObservation2DRangeScan.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/CObservationOdometry.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/link_pragmas.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/obs/obs_frwds.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/slam/CObservation2DRangeScan.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/obs/include/mrpt/slam/CObservationOdometry.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/C3DSScene.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CArrow.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CAssimpModel.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CAxis.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CBox.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CCamera.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CCylinder.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CDisk.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoid.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth2D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidInverseDepth3D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CEllipsoidRangeBearing2D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CFBORender.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CFrustum.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedCylinder.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CGeneralizedEllipsoidTemplate.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXY.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CGridPlaneXZ.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CLight.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CMesh.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CMeshFast.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COctoMapVoxels.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COctreePointRenderer.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLScene.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLStandardObject.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/COpenGLViewport.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloud.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CPointCloudColoured.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CPolyhedron.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CRenderizableDisplayList.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfLines.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfObjects.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTexturedTriangles.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSetOfTriangles.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSimpleLine.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CSphere.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CText.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CText3D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CTextMessageCapable.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedObject.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CTexturedPlane.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField2D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/CVectorField3D.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/gl_utils.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/graph_tools_impl.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/link_pragmas.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_fonts.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/opengl_frwds.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/pose_pdfs.h\nCMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o: /usr/include/mrpt/opengl/include/mrpt/opengl/stock_objects.h\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/flags.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# compile CXX with /usr/bin/c++\nCXX_FLAGS =  -Wno-long-long -Wno-variadic-macros -Wno-long-long -Wno-variadic-macros -g   -std=gnu++1z\n\nCXX_DEFINES = -DROSCONSOLE_BACKEND_LOG4CXX -DROS_PACKAGE_NAME=\\\"rf2o_laser_odometry\\\"\n\nCXX_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 \n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/link.txt",
    "content": "/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 \n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rf2o_laser_odometry_node.dir/progress.make",
    "content": "CMAKE_PROGRESS_1 = 1\nCMAKE_PROGRESS_2 = 2\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for roscpp_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/roscpp_generate_messages_cpp.dir/progress.make\n\nroscpp_generate_messages_cpp: CMakeFiles/roscpp_generate_messages_cpp.dir/build.make\n\n.PHONY : roscpp_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/roscpp_generate_messages_cpp.dir/build: roscpp_generate_messages_cpp\n\n.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/build\n\nCMakeFiles/roscpp_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/clean\n\nCMakeFiles/roscpp_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/roscpp_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/roscpp_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for roscpp_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/roscpp_generate_messages_eus.dir/progress.make\n\nroscpp_generate_messages_eus: CMakeFiles/roscpp_generate_messages_eus.dir/build.make\n\n.PHONY : roscpp_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/roscpp_generate_messages_eus.dir/build: roscpp_generate_messages_eus\n\n.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/build\n\nCMakeFiles/roscpp_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/clean\n\nCMakeFiles/roscpp_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/roscpp_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/roscpp_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for roscpp_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/roscpp_generate_messages_lisp.dir/progress.make\n\nroscpp_generate_messages_lisp: CMakeFiles/roscpp_generate_messages_lisp.dir/build.make\n\n.PHONY : roscpp_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/roscpp_generate_messages_lisp.dir/build: roscpp_generate_messages_lisp\n\n.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/build\n\nCMakeFiles/roscpp_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/clean\n\nCMakeFiles/roscpp_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/roscpp_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/roscpp_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for roscpp_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/roscpp_generate_messages_nodejs.dir/progress.make\n\nroscpp_generate_messages_nodejs: CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make\n\n.PHONY : roscpp_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/roscpp_generate_messages_nodejs.dir/build: roscpp_generate_messages_nodejs\n\n.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/build\n\nCMakeFiles/roscpp_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/clean\n\nCMakeFiles/roscpp_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/roscpp_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/roscpp_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for roscpp_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/roscpp_generate_messages_py.dir/progress.make\n\nroscpp_generate_messages_py: CMakeFiles/roscpp_generate_messages_py.dir/build.make\n\n.PHONY : roscpp_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/roscpp_generate_messages_py.dir/build: roscpp_generate_messages_py\n\n.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/build\n\nCMakeFiles/roscpp_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/clean\n\nCMakeFiles/roscpp_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/roscpp_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/roscpp_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/roscpp_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for rosgraph_msgs_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/progress.make\n\nrosgraph_msgs_generate_messages_cpp: CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make\n\n.PHONY : rosgraph_msgs_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build: rosgraph_msgs_generate_messages_cpp\n\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build\n\nCMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/clean\n\nCMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for rosgraph_msgs_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/progress.make\n\nrosgraph_msgs_generate_messages_eus: CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make\n\n.PHONY : rosgraph_msgs_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build: rosgraph_msgs_generate_messages_eus\n\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build\n\nCMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/clean\n\nCMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for rosgraph_msgs_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/progress.make\n\nrosgraph_msgs_generate_messages_lisp: CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make\n\n.PHONY : rosgraph_msgs_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build: rosgraph_msgs_generate_messages_lisp\n\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build\n\nCMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/clean\n\nCMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for rosgraph_msgs_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/progress.make\n\nrosgraph_msgs_generate_messages_nodejs: CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make\n\n.PHONY : rosgraph_msgs_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build: rosgraph_msgs_generate_messages_nodejs\n\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build\n\nCMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/clean\n\nCMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for rosgraph_msgs_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/rosgraph_msgs_generate_messages_py.dir/progress.make\n\nrosgraph_msgs_generate_messages_py: CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make\n\n.PHONY : rosgraph_msgs_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/rosgraph_msgs_generate_messages_py.dir/build: rosgraph_msgs_generate_messages_py\n\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build\n\nCMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/clean\n\nCMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/rosgraph_msgs_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/rosgraph_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/rosgraph_msgs_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for run_tests.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/run_tests.dir/progress.make\n\nrun_tests: CMakeFiles/run_tests.dir/build.make\n\n.PHONY : run_tests\n\n# Rule to build all files generated by this target.\nCMakeFiles/run_tests.dir/build: run_tests\n\n.PHONY : CMakeFiles/run_tests.dir/build\n\nCMakeFiles/run_tests.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/run_tests.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/run_tests.dir/clean\n\nCMakeFiles/run_tests.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/run_tests.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/run_tests.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/run_tests.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for sensor_msgs_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/sensor_msgs_generate_messages_cpp.dir/progress.make\n\nsensor_msgs_generate_messages_cpp: CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make\n\n.PHONY : sensor_msgs_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/sensor_msgs_generate_messages_cpp.dir/build: sensor_msgs_generate_messages_cpp\n\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build\n\nCMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/clean\n\nCMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/sensor_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for sensor_msgs_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/sensor_msgs_generate_messages_eus.dir/progress.make\n\nsensor_msgs_generate_messages_eus: CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make\n\n.PHONY : sensor_msgs_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/sensor_msgs_generate_messages_eus.dir/build: sensor_msgs_generate_messages_eus\n\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/build\n\nCMakeFiles/sensor_msgs_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/clean\n\nCMakeFiles/sensor_msgs_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/sensor_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for sensor_msgs_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/sensor_msgs_generate_messages_lisp.dir/progress.make\n\nsensor_msgs_generate_messages_lisp: CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make\n\n.PHONY : sensor_msgs_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/sensor_msgs_generate_messages_lisp.dir/build: sensor_msgs_generate_messages_lisp\n\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build\n\nCMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/clean\n\nCMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/sensor_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for sensor_msgs_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/progress.make\n\nsensor_msgs_generate_messages_nodejs: CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make\n\n.PHONY : sensor_msgs_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build: sensor_msgs_generate_messages_nodejs\n\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build\n\nCMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/clean\n\nCMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for sensor_msgs_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/sensor_msgs_generate_messages_py.dir/progress.make\n\nsensor_msgs_generate_messages_py: CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make\n\n.PHONY : sensor_msgs_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/sensor_msgs_generate_messages_py.dir/build: sensor_msgs_generate_messages_py\n\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/build\n\nCMakeFiles/sensor_msgs_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/clean\n\nCMakeFiles/sensor_msgs_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/sensor_msgs_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/sensor_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/sensor_msgs_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for std_msgs_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/std_msgs_generate_messages_cpp.dir/progress.make\n\nstd_msgs_generate_messages_cpp: CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make\n\n.PHONY : std_msgs_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/std_msgs_generate_messages_cpp.dir/build: std_msgs_generate_messages_cpp\n\n.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/build\n\nCMakeFiles/std_msgs_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/clean\n\nCMakeFiles/std_msgs_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/std_msgs_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/std_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for std_msgs_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/std_msgs_generate_messages_eus.dir/progress.make\n\nstd_msgs_generate_messages_eus: CMakeFiles/std_msgs_generate_messages_eus.dir/build.make\n\n.PHONY : std_msgs_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/std_msgs_generate_messages_eus.dir/build: std_msgs_generate_messages_eus\n\n.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/build\n\nCMakeFiles/std_msgs_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/clean\n\nCMakeFiles/std_msgs_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/std_msgs_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/std_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for std_msgs_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/std_msgs_generate_messages_lisp.dir/progress.make\n\nstd_msgs_generate_messages_lisp: CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make\n\n.PHONY : std_msgs_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/std_msgs_generate_messages_lisp.dir/build: std_msgs_generate_messages_lisp\n\n.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/build\n\nCMakeFiles/std_msgs_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/clean\n\nCMakeFiles/std_msgs_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/std_msgs_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/std_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for std_msgs_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/std_msgs_generate_messages_nodejs.dir/progress.make\n\nstd_msgs_generate_messages_nodejs: CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make\n\n.PHONY : std_msgs_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/std_msgs_generate_messages_nodejs.dir/build: std_msgs_generate_messages_nodejs\n\n.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/build\n\nCMakeFiles/std_msgs_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/clean\n\nCMakeFiles/std_msgs_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/std_msgs_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/std_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for std_msgs_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/std_msgs_generate_messages_py.dir/progress.make\n\nstd_msgs_generate_messages_py: CMakeFiles/std_msgs_generate_messages_py.dir/build.make\n\n.PHONY : std_msgs_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/std_msgs_generate_messages_py.dir/build: std_msgs_generate_messages_py\n\n.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/build\n\nCMakeFiles/std_msgs_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/clean\n\nCMakeFiles/std_msgs_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/std_msgs_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/std_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/std_msgs_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tests.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tests.dir/progress.make\n\ntests: CMakeFiles/tests.dir/build.make\n\n.PHONY : tests\n\n# Rule to build all files generated by this target.\nCMakeFiles/tests.dir/build: tests\n\n.PHONY : CMakeFiles/tests.dir/build\n\nCMakeFiles/tests.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tests.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tests.dir/clean\n\nCMakeFiles/tests.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tests.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tests.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tests.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf2_msgs_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf2_msgs_generate_messages_cpp.dir/progress.make\n\ntf2_msgs_generate_messages_cpp: CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make\n\n.PHONY : tf2_msgs_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf2_msgs_generate_messages_cpp.dir/build: tf2_msgs_generate_messages_cpp\n\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build\n\nCMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/clean\n\nCMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf2_msgs_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf2_msgs_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf2_msgs_generate_messages_eus.dir/progress.make\n\ntf2_msgs_generate_messages_eus: CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make\n\n.PHONY : tf2_msgs_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf2_msgs_generate_messages_eus.dir/build: tf2_msgs_generate_messages_eus\n\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/build\n\nCMakeFiles/tf2_msgs_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/clean\n\nCMakeFiles/tf2_msgs_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf2_msgs_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf2_msgs_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf2_msgs_generate_messages_lisp.dir/progress.make\n\ntf2_msgs_generate_messages_lisp: CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make\n\n.PHONY : tf2_msgs_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf2_msgs_generate_messages_lisp.dir/build: tf2_msgs_generate_messages_lisp\n\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build\n\nCMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/clean\n\nCMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf2_msgs_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf2_msgs_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/progress.make\n\ntf2_msgs_generate_messages_nodejs: CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make\n\n.PHONY : tf2_msgs_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build: tf2_msgs_generate_messages_nodejs\n\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build\n\nCMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/clean\n\nCMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf2_msgs_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf2_msgs_generate_messages_py.dir/progress.make\n\ntf2_msgs_generate_messages_py: CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make\n\n.PHONY : tf2_msgs_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf2_msgs_generate_messages_py.dir/build: tf2_msgs_generate_messages_py\n\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/build\n\nCMakeFiles/tf2_msgs_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/clean\n\nCMakeFiles/tf2_msgs_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf2_msgs_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf2_msgs_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf2_msgs_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf_generate_messages_cpp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf_generate_messages_cpp.dir/progress.make\n\ntf_generate_messages_cpp: CMakeFiles/tf_generate_messages_cpp.dir/build.make\n\n.PHONY : tf_generate_messages_cpp\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf_generate_messages_cpp.dir/build: tf_generate_messages_cpp\n\n.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/build\n\nCMakeFiles/tf_generate_messages_cpp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/clean\n\nCMakeFiles/tf_generate_messages_cpp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf_generate_messages_cpp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf_generate_messages_cpp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_cpp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf_generate_messages_eus.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf_generate_messages_eus.dir/progress.make\n\ntf_generate_messages_eus: CMakeFiles/tf_generate_messages_eus.dir/build.make\n\n.PHONY : tf_generate_messages_eus\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf_generate_messages_eus.dir/build: tf_generate_messages_eus\n\n.PHONY : CMakeFiles/tf_generate_messages_eus.dir/build\n\nCMakeFiles/tf_generate_messages_eus.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_eus.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf_generate_messages_eus.dir/clean\n\nCMakeFiles/tf_generate_messages_eus.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf_generate_messages_eus.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf_generate_messages_eus.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_eus.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf_generate_messages_lisp.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf_generate_messages_lisp.dir/progress.make\n\ntf_generate_messages_lisp: CMakeFiles/tf_generate_messages_lisp.dir/build.make\n\n.PHONY : tf_generate_messages_lisp\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf_generate_messages_lisp.dir/build: tf_generate_messages_lisp\n\n.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/build\n\nCMakeFiles/tf_generate_messages_lisp.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/clean\n\nCMakeFiles/tf_generate_messages_lisp.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf_generate_messages_lisp.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf_generate_messages_lisp.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_lisp.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf_generate_messages_nodejs.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf_generate_messages_nodejs.dir/progress.make\n\ntf_generate_messages_nodejs: CMakeFiles/tf_generate_messages_nodejs.dir/build.make\n\n.PHONY : tf_generate_messages_nodejs\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf_generate_messages_nodejs.dir/build: tf_generate_messages_nodejs\n\n.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/build\n\nCMakeFiles/tf_generate_messages_nodejs.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/clean\n\nCMakeFiles/tf_generate_messages_nodejs.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf_generate_messages_nodejs.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf_generate_messages_nodejs.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_nodejs.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/DependInfo.cmake",
    "content": "# The set of languages for which implicit dependencies are needed:\nset(CMAKE_DEPENDS_LANGUAGES\n  )\n# The set of files for implicit dependencies of each language:\n\n# Targets to which this target links.\nset(CMAKE_TARGET_LINKED_INFO_FILES\n  )\n\n# Fortran module output directory.\nset(CMAKE_Fortran_TARGET_MODULE_DIR \"\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/build.make",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Delete rule output on recipe failure.\n.DELETE_ON_ERROR:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n# Utility rule file for tf_generate_messages_py.\n\n# Include the progress variables for this target.\ninclude CMakeFiles/tf_generate_messages_py.dir/progress.make\n\ntf_generate_messages_py: CMakeFiles/tf_generate_messages_py.dir/build.make\n\n.PHONY : tf_generate_messages_py\n\n# Rule to build all files generated by this target.\nCMakeFiles/tf_generate_messages_py.dir/build: tf_generate_messages_py\n\n.PHONY : CMakeFiles/tf_generate_messages_py.dir/build\n\nCMakeFiles/tf_generate_messages_py.dir/clean:\n\t$(CMAKE_COMMAND) -P CMakeFiles/tf_generate_messages_py.dir/cmake_clean.cmake\n.PHONY : CMakeFiles/tf_generate_messages_py.dir/clean\n\nCMakeFiles/tf_generate_messages_py.dir/depend:\n\tcd /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)\n.PHONY : CMakeFiles/tf_generate_messages_py.dir/depend\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/cmake_clean.cmake",
    "content": "\n# Per-language clean rules from dependency scanning.\nforeach(lang )\n  include(CMakeFiles/tf_generate_messages_py.dir/cmake_clean_${lang}.cmake OPTIONAL)\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles/tf_generate_messages_py.dir/progress.make",
    "content": "\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/CTestTestfile.cmake",
    "content": "# CMake generated Testfile for \n# Source directory: /home/zn/racecar/src/rf2o_laser_odometry\n# Build directory: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n# \n# This file includes the relevant testing commands required for \n# testing this directory and lists subdirectories to be tested as well.\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/Makefile",
    "content": "# CMAKE generated file: DO NOT EDIT!\n# Generated by \"Unix Makefiles\" Generator, CMake Version 3.9\n\n# Default target executed when no arguments are given to make.\ndefault_target: all\n\n.PHONY : default_target\n\n# Allow only one \"make -f Makefile2\" at a time, but pass parallelism.\n.NOTPARALLEL:\n\n\n#=============================================================================\n# Special targets provided by cmake.\n\n# Disable implicit rules so canonical targets will work.\n.SUFFIXES:\n\n\n# Remove some rules from gmake that .SUFFIXES does not remove.\nSUFFIXES =\n\n.SUFFIXES: .hpux_make_needs_suffix_list\n\n\n# Suppress display of executed commands.\n$(VERBOSE).SILENT:\n\n\n# A target that is always out of date.\ncmake_force:\n\n.PHONY : cmake_force\n\n#=============================================================================\n# Set environment variables for the build.\n\n# The shell in which to execute make rules.\nSHELL = /bin/sh\n\n# The CMake executable.\nCMAKE_COMMAND = /home/zn/.ide/clion/bin/cmake/bin/cmake\n\n# The command to remove a file.\nRM = /home/zn/.ide/clion/bin/cmake/bin/cmake -E remove -f\n\n# Escaping for special characters.\nEQUALS = =\n\n# The top-level source directory on which CMake was run.\nCMAKE_SOURCE_DIR = /home/zn/racecar/src/rf2o_laser_odometry\n\n# The top-level build directory on which CMake was run.\nCMAKE_BINARY_DIR = /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\n\n#=============================================================================\n# Targets provided globally by CMake.\n\n# Special rule for the target install/local\ninstall/local: preinstall\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Installing only the local directory...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake\n.PHONY : install/local\n\n# Special rule for the target install/local\ninstall/local/fast: preinstall/fast\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Installing only the local directory...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_INSTALL_LOCAL_ONLY=1 -P cmake_install.cmake\n.PHONY : install/local/fast\n\n# Special rule for the target edit_cache\nedit_cache:\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"No interactive CMake dialog available...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/cmake -E echo No\\ interactive\\ CMake\\ dialog\\ available.\n.PHONY : edit_cache\n\n# Special rule for the target edit_cache\nedit_cache/fast: edit_cache\n\n.PHONY : edit_cache/fast\n\n# Special rule for the target install/strip\ninstall/strip: preinstall\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Installing the project stripped...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake\n.PHONY : install/strip\n\n# Special rule for the target install/strip\ninstall/strip/fast: preinstall/fast\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Installing the project stripped...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/cmake -DCMAKE_INSTALL_DO_STRIP=1 -P cmake_install.cmake\n.PHONY : install/strip/fast\n\n# Special rule for the target rebuild_cache\nrebuild_cache:\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Running CMake to regenerate build system...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/cmake -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR)\n.PHONY : rebuild_cache\n\n# Special rule for the target rebuild_cache\nrebuild_cache/fast: rebuild_cache\n\n.PHONY : rebuild_cache/fast\n\n# Special rule for the target install\ninstall: preinstall\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Install the project...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/cmake -P cmake_install.cmake\n.PHONY : install\n\n# Special rule for the target install\ninstall/fast: preinstall/fast\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Install the project...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/cmake -P cmake_install.cmake\n.PHONY : install/fast\n\n# Special rule for the target list_install_components\nlist_install_components:\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Available install components are: \\\"Unspecified\\\"\"\n.PHONY : list_install_components\n\n# Special rule for the target list_install_components\nlist_install_components/fast: list_install_components\n\n.PHONY : list_install_components/fast\n\n# Special rule for the target test\ntest:\n\t@$(CMAKE_COMMAND) -E cmake_echo_color --switch=$(COLOR) --cyan \"Running tests...\"\n\t/home/zn/.ide/clion/bin/cmake/bin/ctest --force-new-ctest-process $(ARGS)\n.PHONY : test\n\n# Special rule for the target test\ntest/fast: test\n\n.PHONY : test/fast\n\n# The main all target\nall: cmake_check_build_system\n\t$(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\n\t$(MAKE) -f CMakeFiles/Makefile2 all\n\t$(CMAKE_COMMAND) -E cmake_progress_start /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/CMakeFiles 0\n.PHONY : all\n\n# The main clean target\nclean:\n\t$(MAKE) -f CMakeFiles/Makefile2 clean\n.PHONY : clean\n\n# The main clean target\nclean/fast: clean\n\n.PHONY : clean/fast\n\n# Prepare targets for installation.\npreinstall: all\n\t$(MAKE) -f CMakeFiles/Makefile2 preinstall\n.PHONY : preinstall\n\n# Prepare targets for installation.\npreinstall/fast:\n\t$(MAKE) -f CMakeFiles/Makefile2 preinstall\n.PHONY : preinstall/fast\n\n# clear depends\ndepend:\n\t$(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 1\n.PHONY : depend\n\n#=============================================================================\n# Target rules for targets named tf2_msgs_generate_messages_nodejs\n\n# Build rule for target.\ntf2_msgs_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_nodejs\n.PHONY : tf2_msgs_generate_messages_nodejs\n\n# fast build rule for target.\ntf2_msgs_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/tf2_msgs_generate_messages_nodejs.dir/build\n.PHONY : tf2_msgs_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named tf2_msgs_generate_messages_lisp\n\n# Build rule for target.\ntf2_msgs_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_lisp\n.PHONY : tf2_msgs_generate_messages_lisp\n\n# fast build rule for target.\ntf2_msgs_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_lisp.dir/build\n.PHONY : tf2_msgs_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named tf2_msgs_generate_messages_eus\n\n# Build rule for target.\ntf2_msgs_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_eus\n.PHONY : tf2_msgs_generate_messages_eus\n\n# fast build rule for target.\ntf2_msgs_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_eus.dir/build.make CMakeFiles/tf2_msgs_generate_messages_eus.dir/build\n.PHONY : tf2_msgs_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named tf2_msgs_generate_messages_cpp\n\n# Build rule for target.\ntf2_msgs_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_cpp\n.PHONY : tf2_msgs_generate_messages_cpp\n\n# fast build rule for target.\ntf2_msgs_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build.make CMakeFiles/tf2_msgs_generate_messages_cpp.dir/build\n.PHONY : tf2_msgs_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_generate_messages_py\n\n# Build rule for target.\nactionlib_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_py\n.PHONY : actionlib_generate_messages_py\n\n# fast build rule for target.\nactionlib_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_py.dir/build.make CMakeFiles/actionlib_generate_messages_py.dir/build\n.PHONY : actionlib_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_generate_messages_eus\n\n# Build rule for target.\nactionlib_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_eus\n.PHONY : actionlib_generate_messages_eus\n\n# fast build rule for target.\nactionlib_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_eus.dir/build.make CMakeFiles/actionlib_generate_messages_eus.dir/build\n.PHONY : actionlib_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named nav_msgs_generate_messages_eus\n\n# Build rule for target.\nnav_msgs_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_eus\n.PHONY : nav_msgs_generate_messages_eus\n\n# fast build rule for target.\nnav_msgs_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_eus.dir/build.make CMakeFiles/nav_msgs_generate_messages_eus.dir/build\n.PHONY : nav_msgs_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named std_msgs_generate_messages_eus\n\n# Build rule for target.\nstd_msgs_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_eus\n.PHONY : std_msgs_generate_messages_eus\n\n# fast build rule for target.\nstd_msgs_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_eus.dir/build.make CMakeFiles/std_msgs_generate_messages_eus.dir/build\n.PHONY : std_msgs_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named roscpp_generate_messages_lisp\n\n# Build rule for target.\nroscpp_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_lisp\n.PHONY : roscpp_generate_messages_lisp\n\n# fast build rule for target.\nroscpp_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_lisp.dir/build.make CMakeFiles/roscpp_generate_messages_lisp.dir/build\n.PHONY : roscpp_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named rosgraph_msgs_generate_messages_lisp\n\n# Build rule for target.\nrosgraph_msgs_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_lisp\n.PHONY : rosgraph_msgs_generate_messages_lisp\n\n# fast build rule for target.\nrosgraph_msgs_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_lisp.dir/build\n.PHONY : rosgraph_msgs_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named tests\n\n# Build rule for target.\ntests: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tests\n.PHONY : tests\n\n# fast build rule for target.\ntests/fast:\n\t$(MAKE) -f CMakeFiles/tests.dir/build.make CMakeFiles/tests.dir/build\n.PHONY : tests/fast\n\n#=============================================================================\n# Target rules for targets named rf2o_laser_odometry_node\n\n# Build rule for target.\nrf2o_laser_odometry_node: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 rf2o_laser_odometry_node\n.PHONY : rf2o_laser_odometry_node\n\n# fast build rule for target.\nrf2o_laser_odometry_node/fast:\n\t$(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/build\n.PHONY : rf2o_laser_odometry_node/fast\n\n#=============================================================================\n# Target rules for targets named roscpp_generate_messages_nodejs\n\n# Build rule for target.\nroscpp_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_nodejs\n.PHONY : roscpp_generate_messages_nodejs\n\n# fast build rule for target.\nroscpp_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_nodejs.dir/build.make CMakeFiles/roscpp_generate_messages_nodejs.dir/build\n.PHONY : roscpp_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named tf_generate_messages_eus\n\n# Build rule for target.\ntf_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_eus\n.PHONY : tf_generate_messages_eus\n\n# fast build rule for target.\ntf_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_eus.dir/build.make CMakeFiles/tf_generate_messages_eus.dir/build\n.PHONY : tf_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named rosgraph_msgs_generate_messages_nodejs\n\n# Build rule for target.\nrosgraph_msgs_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_nodejs\n.PHONY : rosgraph_msgs_generate_messages_nodejs\n\n# fast build rule for target.\nrosgraph_msgs_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_nodejs.dir/build\n.PHONY : rosgraph_msgs_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named nav_msgs_generate_messages_cpp\n\n# Build rule for target.\nnav_msgs_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_cpp\n.PHONY : nav_msgs_generate_messages_cpp\n\n# fast build rule for target.\nnav_msgs_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_cpp.dir/build.make CMakeFiles/nav_msgs_generate_messages_cpp.dir/build\n.PHONY : nav_msgs_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named std_msgs_generate_messages_lisp\n\n# Build rule for target.\nstd_msgs_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_lisp\n.PHONY : std_msgs_generate_messages_lisp\n\n# fast build rule for target.\nstd_msgs_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_lisp.dir/build.make CMakeFiles/std_msgs_generate_messages_lisp.dir/build\n.PHONY : std_msgs_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named geometry_msgs_generate_messages_lisp\n\n# Build rule for target.\ngeometry_msgs_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_lisp\n.PHONY : geometry_msgs_generate_messages_lisp\n\n# fast build rule for target.\ngeometry_msgs_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_lisp.dir/build\n.PHONY : geometry_msgs_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named rosgraph_msgs_generate_messages_cpp\n\n# Build rule for target.\nrosgraph_msgs_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_cpp\n.PHONY : rosgraph_msgs_generate_messages_cpp\n\n# fast build rule for target.\nrosgraph_msgs_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_cpp.dir/build\n.PHONY : rosgraph_msgs_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named run_tests\n\n# Build rule for target.\nrun_tests: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 run_tests\n.PHONY : run_tests\n\n# fast build rule for target.\nrun_tests/fast:\n\t$(MAKE) -f CMakeFiles/run_tests.dir/build.make CMakeFiles/run_tests.dir/build\n.PHONY : run_tests/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_generate_messages_lisp\n\n# Build rule for target.\nactionlib_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_lisp\n.PHONY : actionlib_generate_messages_lisp\n\n# fast build rule for target.\nactionlib_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_generate_messages_lisp.dir/build\n.PHONY : actionlib_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_msgs_generate_messages_eus\n\n# Build rule for target.\nactionlib_msgs_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_eus\n.PHONY : actionlib_msgs_generate_messages_eus\n\n# fast build rule for target.\nactionlib_msgs_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_eus.dir/build\n.PHONY : actionlib_msgs_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named roscpp_generate_messages_eus\n\n# Build rule for target.\nroscpp_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_eus\n.PHONY : roscpp_generate_messages_eus\n\n# fast build rule for target.\nroscpp_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_eus.dir/build.make CMakeFiles/roscpp_generate_messages_eus.dir/build\n.PHONY : roscpp_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named roscpp_generate_messages_cpp\n\n# Build rule for target.\nroscpp_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_cpp\n.PHONY : roscpp_generate_messages_cpp\n\n# fast build rule for target.\nroscpp_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_cpp.dir/build.make CMakeFiles/roscpp_generate_messages_cpp.dir/build\n.PHONY : roscpp_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named geometry_msgs_generate_messages_eus\n\n# Build rule for target.\ngeometry_msgs_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_eus\n.PHONY : geometry_msgs_generate_messages_eus\n\n# fast build rule for target.\ngeometry_msgs_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_eus.dir/build.make CMakeFiles/geometry_msgs_generate_messages_eus.dir/build\n.PHONY : geometry_msgs_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_msgs_generate_messages_py\n\n# Build rule for target.\nactionlib_msgs_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_py\n.PHONY : actionlib_msgs_generate_messages_py\n\n# fast build rule for target.\nactionlib_msgs_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_py.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_py.dir/build\n.PHONY : actionlib_msgs_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named clean_test_results\n\n# Build rule for target.\nclean_test_results: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 clean_test_results\n.PHONY : clean_test_results\n\n# fast build rule for target.\nclean_test_results/fast:\n\t$(MAKE) -f CMakeFiles/clean_test_results.dir/build.make CMakeFiles/clean_test_results.dir/build\n.PHONY : clean_test_results/fast\n\n#=============================================================================\n# Target rules for targets named geometry_msgs_generate_messages_nodejs\n\n# Build rule for target.\ngeometry_msgs_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_nodejs\n.PHONY : geometry_msgs_generate_messages_nodejs\n\n# fast build rule for target.\ngeometry_msgs_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/geometry_msgs_generate_messages_nodejs.dir/build\n.PHONY : geometry_msgs_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named rosgraph_msgs_generate_messages_eus\n\n# Build rule for target.\nrosgraph_msgs_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_eus\n.PHONY : rosgraph_msgs_generate_messages_eus\n\n# fast build rule for target.\nrosgraph_msgs_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_eus.dir/build\n.PHONY : rosgraph_msgs_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named doxygen\n\n# Build rule for target.\ndoxygen: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 doxygen\n.PHONY : doxygen\n\n# fast build rule for target.\ndoxygen/fast:\n\t$(MAKE) -f CMakeFiles/doxygen.dir/build.make CMakeFiles/doxygen.dir/build\n.PHONY : doxygen/fast\n\n#=============================================================================\n# Target rules for targets named tf_generate_messages_cpp\n\n# Build rule for target.\ntf_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_cpp\n.PHONY : tf_generate_messages_cpp\n\n# fast build rule for target.\ntf_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_cpp.dir/build.make CMakeFiles/tf_generate_messages_cpp.dir/build\n.PHONY : tf_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named nav_msgs_generate_messages_lisp\n\n# Build rule for target.\nnav_msgs_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_lisp\n.PHONY : nav_msgs_generate_messages_lisp\n\n# fast build rule for target.\nnav_msgs_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_lisp.dir/build.make CMakeFiles/nav_msgs_generate_messages_lisp.dir/build\n.PHONY : nav_msgs_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named nav_msgs_generate_messages_nodejs\n\n# Build rule for target.\nnav_msgs_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_nodejs\n.PHONY : nav_msgs_generate_messages_nodejs\n\n# fast build rule for target.\nnav_msgs_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/nav_msgs_generate_messages_nodejs.dir/build\n.PHONY : nav_msgs_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named std_msgs_generate_messages_py\n\n# Build rule for target.\nstd_msgs_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_py\n.PHONY : std_msgs_generate_messages_py\n\n# fast build rule for target.\nstd_msgs_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_py.dir/build.make CMakeFiles/std_msgs_generate_messages_py.dir/build\n.PHONY : std_msgs_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named nav_msgs_generate_messages_py\n\n# Build rule for target.\nnav_msgs_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 nav_msgs_generate_messages_py\n.PHONY : nav_msgs_generate_messages_py\n\n# fast build rule for target.\nnav_msgs_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/nav_msgs_generate_messages_py.dir/build.make CMakeFiles/nav_msgs_generate_messages_py.dir/build\n.PHONY : nav_msgs_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named geometry_msgs_generate_messages_cpp\n\n# Build rule for target.\ngeometry_msgs_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_cpp\n.PHONY : geometry_msgs_generate_messages_cpp\n\n# fast build rule for target.\ngeometry_msgs_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build.make CMakeFiles/geometry_msgs_generate_messages_cpp.dir/build\n.PHONY : geometry_msgs_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named sensor_msgs_generate_messages_nodejs\n\n# Build rule for target.\nsensor_msgs_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_nodejs\n.PHONY : sensor_msgs_generate_messages_nodejs\n\n# fast build rule for target.\nsensor_msgs_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/sensor_msgs_generate_messages_nodejs.dir/build\n.PHONY : sensor_msgs_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named std_msgs_generate_messages_nodejs\n\n# Build rule for target.\nstd_msgs_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_nodejs\n.PHONY : std_msgs_generate_messages_nodejs\n\n# fast build rule for target.\nstd_msgs_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/std_msgs_generate_messages_nodejs.dir/build\n.PHONY : std_msgs_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named geometry_msgs_generate_messages_py\n\n# Build rule for target.\ngeometry_msgs_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 geometry_msgs_generate_messages_py\n.PHONY : geometry_msgs_generate_messages_py\n\n# fast build rule for target.\ngeometry_msgs_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/geometry_msgs_generate_messages_py.dir/build.make CMakeFiles/geometry_msgs_generate_messages_py.dir/build\n.PHONY : geometry_msgs_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_msgs_generate_messages_lisp\n\n# Build rule for target.\nactionlib_msgs_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_lisp\n.PHONY : actionlib_msgs_generate_messages_lisp\n\n# fast build rule for target.\nactionlib_msgs_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_lisp.dir/build\n.PHONY : actionlib_msgs_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named tf2_msgs_generate_messages_py\n\n# Build rule for target.\ntf2_msgs_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf2_msgs_generate_messages_py\n.PHONY : tf2_msgs_generate_messages_py\n\n# fast build rule for target.\ntf2_msgs_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/tf2_msgs_generate_messages_py.dir/build.make CMakeFiles/tf2_msgs_generate_messages_py.dir/build\n.PHONY : tf2_msgs_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_msgs_generate_messages_nodejs\n\n# Build rule for target.\nactionlib_msgs_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_nodejs\n.PHONY : actionlib_msgs_generate_messages_nodejs\n\n# fast build rule for target.\nactionlib_msgs_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_nodejs.dir/build\n.PHONY : actionlib_msgs_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named sensor_msgs_generate_messages_cpp\n\n# Build rule for target.\nsensor_msgs_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_cpp\n.PHONY : sensor_msgs_generate_messages_cpp\n\n# fast build rule for target.\nsensor_msgs_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_cpp.dir/build\n.PHONY : sensor_msgs_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_generate_messages_nodejs\n\n# Build rule for target.\nactionlib_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_nodejs\n.PHONY : actionlib_generate_messages_nodejs\n\n# fast build rule for target.\nactionlib_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_nodejs.dir/build.make CMakeFiles/actionlib_generate_messages_nodejs.dir/build\n.PHONY : actionlib_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_msgs_generate_messages_cpp\n\n# Build rule for target.\nactionlib_msgs_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_msgs_generate_messages_cpp\n.PHONY : actionlib_msgs_generate_messages_cpp\n\n# fast build rule for target.\nactionlib_msgs_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_msgs_generate_messages_cpp.dir/build\n.PHONY : actionlib_msgs_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named std_msgs_generate_messages_cpp\n\n# Build rule for target.\nstd_msgs_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 std_msgs_generate_messages_cpp\n.PHONY : std_msgs_generate_messages_cpp\n\n# fast build rule for target.\nstd_msgs_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/std_msgs_generate_messages_cpp.dir/build.make CMakeFiles/std_msgs_generate_messages_cpp.dir/build\n.PHONY : std_msgs_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named sensor_msgs_generate_messages_eus\n\n# Build rule for target.\nsensor_msgs_generate_messages_eus: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_eus\n.PHONY : sensor_msgs_generate_messages_eus\n\n# fast build rule for target.\nsensor_msgs_generate_messages_eus/fast:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_eus.dir/build.make CMakeFiles/sensor_msgs_generate_messages_eus.dir/build\n.PHONY : sensor_msgs_generate_messages_eus/fast\n\n#=============================================================================\n# Target rules for targets named download_extra_data\n\n# Build rule for target.\ndownload_extra_data: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 download_extra_data\n.PHONY : download_extra_data\n\n# fast build rule for target.\ndownload_extra_data/fast:\n\t$(MAKE) -f CMakeFiles/download_extra_data.dir/build.make CMakeFiles/download_extra_data.dir/build\n.PHONY : download_extra_data/fast\n\n#=============================================================================\n# Target rules for targets named sensor_msgs_generate_messages_lisp\n\n# Build rule for target.\nsensor_msgs_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_lisp\n.PHONY : sensor_msgs_generate_messages_lisp\n\n# fast build rule for target.\nsensor_msgs_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build.make CMakeFiles/sensor_msgs_generate_messages_lisp.dir/build\n.PHONY : sensor_msgs_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named actionlib_generate_messages_cpp\n\n# Build rule for target.\nactionlib_generate_messages_cpp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 actionlib_generate_messages_cpp\n.PHONY : actionlib_generate_messages_cpp\n\n# fast build rule for target.\nactionlib_generate_messages_cpp/fast:\n\t$(MAKE) -f CMakeFiles/actionlib_generate_messages_cpp.dir/build.make CMakeFiles/actionlib_generate_messages_cpp.dir/build\n.PHONY : actionlib_generate_messages_cpp/fast\n\n#=============================================================================\n# Target rules for targets named sensor_msgs_generate_messages_py\n\n# Build rule for target.\nsensor_msgs_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 sensor_msgs_generate_messages_py\n.PHONY : sensor_msgs_generate_messages_py\n\n# fast build rule for target.\nsensor_msgs_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/sensor_msgs_generate_messages_py.dir/build.make CMakeFiles/sensor_msgs_generate_messages_py.dir/build\n.PHONY : sensor_msgs_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named rosgraph_msgs_generate_messages_py\n\n# Build rule for target.\nrosgraph_msgs_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 rosgraph_msgs_generate_messages_py\n.PHONY : rosgraph_msgs_generate_messages_py\n\n# fast build rule for target.\nrosgraph_msgs_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build.make CMakeFiles/rosgraph_msgs_generate_messages_py.dir/build\n.PHONY : rosgraph_msgs_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named tf_generate_messages_lisp\n\n# Build rule for target.\ntf_generate_messages_lisp: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_lisp\n.PHONY : tf_generate_messages_lisp\n\n# fast build rule for target.\ntf_generate_messages_lisp/fast:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_lisp.dir/build.make CMakeFiles/tf_generate_messages_lisp.dir/build\n.PHONY : tf_generate_messages_lisp/fast\n\n#=============================================================================\n# Target rules for targets named roscpp_generate_messages_py\n\n# Build rule for target.\nroscpp_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 roscpp_generate_messages_py\n.PHONY : roscpp_generate_messages_py\n\n# fast build rule for target.\nroscpp_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/roscpp_generate_messages_py.dir/build.make CMakeFiles/roscpp_generate_messages_py.dir/build\n.PHONY : roscpp_generate_messages_py/fast\n\n#=============================================================================\n# Target rules for targets named tf_generate_messages_nodejs\n\n# Build rule for target.\ntf_generate_messages_nodejs: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_nodejs\n.PHONY : tf_generate_messages_nodejs\n\n# fast build rule for target.\ntf_generate_messages_nodejs/fast:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_nodejs.dir/build.make CMakeFiles/tf_generate_messages_nodejs.dir/build\n.PHONY : tf_generate_messages_nodejs/fast\n\n#=============================================================================\n# Target rules for targets named tf_generate_messages_py\n\n# Build rule for target.\ntf_generate_messages_py: cmake_check_build_system\n\t$(MAKE) -f CMakeFiles/Makefile2 tf_generate_messages_py\n.PHONY : tf_generate_messages_py\n\n# fast build rule for target.\ntf_generate_messages_py/fast:\n\t$(MAKE) -f CMakeFiles/tf_generate_messages_py.dir/build.make CMakeFiles/tf_generate_messages_py.dir/build\n.PHONY : tf_generate_messages_py/fast\n\nsrc/CLaserOdometry2D.o: src/CLaserOdometry2D.cpp.o\n\n.PHONY : src/CLaserOdometry2D.o\n\n# target to build an object file\nsrc/CLaserOdometry2D.cpp.o:\n\t$(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.o\n.PHONY : src/CLaserOdometry2D.cpp.o\n\nsrc/CLaserOdometry2D.i: src/CLaserOdometry2D.cpp.i\n\n.PHONY : src/CLaserOdometry2D.i\n\n# target to preprocess a source file\nsrc/CLaserOdometry2D.cpp.i:\n\t$(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.i\n.PHONY : src/CLaserOdometry2D.cpp.i\n\nsrc/CLaserOdometry2D.s: src/CLaserOdometry2D.cpp.s\n\n.PHONY : src/CLaserOdometry2D.s\n\n# target to generate assembly for a file\nsrc/CLaserOdometry2D.cpp.s:\n\t$(MAKE) -f CMakeFiles/rf2o_laser_odometry_node.dir/build.make CMakeFiles/rf2o_laser_odometry_node.dir/src/CLaserOdometry2D.cpp.s\n.PHONY : src/CLaserOdometry2D.cpp.s\n\n# Help Target\nhelp:\n\t@echo \"The following are some of the valid targets for this Makefile:\"\n\t@echo \"... all (the default if no target is provided)\"\n\t@echo \"... clean\"\n\t@echo \"... depend\"\n\t@echo \"... install/local\"\n\t@echo \"... edit_cache\"\n\t@echo \"... tf2_msgs_generate_messages_nodejs\"\n\t@echo \"... tf2_msgs_generate_messages_lisp\"\n\t@echo \"... tf2_msgs_generate_messages_eus\"\n\t@echo \"... tf2_msgs_generate_messages_cpp\"\n\t@echo \"... actionlib_generate_messages_py\"\n\t@echo \"... actionlib_generate_messages_eus\"\n\t@echo \"... install/strip\"\n\t@echo \"... nav_msgs_generate_messages_eus\"\n\t@echo \"... std_msgs_generate_messages_eus\"\n\t@echo \"... roscpp_generate_messages_lisp\"\n\t@echo \"... rosgraph_msgs_generate_messages_lisp\"\n\t@echo \"... tests\"\n\t@echo \"... rf2o_laser_odometry_node\"\n\t@echo \"... roscpp_generate_messages_nodejs\"\n\t@echo \"... rebuild_cache\"\n\t@echo \"... tf_generate_messages_eus\"\n\t@echo \"... rosgraph_msgs_generate_messages_nodejs\"\n\t@echo \"... nav_msgs_generate_messages_cpp\"\n\t@echo \"... install\"\n\t@echo \"... std_msgs_generate_messages_lisp\"\n\t@echo \"... geometry_msgs_generate_messages_lisp\"\n\t@echo \"... rosgraph_msgs_generate_messages_cpp\"\n\t@echo \"... run_tests\"\n\t@echo \"... actionlib_generate_messages_lisp\"\n\t@echo \"... actionlib_msgs_generate_messages_eus\"\n\t@echo \"... list_install_components\"\n\t@echo \"... roscpp_generate_messages_eus\"\n\t@echo \"... roscpp_generate_messages_cpp\"\n\t@echo \"... geometry_msgs_generate_messages_eus\"\n\t@echo \"... actionlib_msgs_generate_messages_py\"\n\t@echo \"... clean_test_results\"\n\t@echo \"... geometry_msgs_generate_messages_nodejs\"\n\t@echo \"... rosgraph_msgs_generate_messages_eus\"\n\t@echo \"... doxygen\"\n\t@echo \"... tf_generate_messages_cpp\"\n\t@echo \"... nav_msgs_generate_messages_lisp\"\n\t@echo \"... nav_msgs_generate_messages_nodejs\"\n\t@echo \"... std_msgs_generate_messages_py\"\n\t@echo \"... nav_msgs_generate_messages_py\"\n\t@echo \"... test\"\n\t@echo \"... geometry_msgs_generate_messages_cpp\"\n\t@echo \"... sensor_msgs_generate_messages_nodejs\"\n\t@echo \"... std_msgs_generate_messages_nodejs\"\n\t@echo \"... geometry_msgs_generate_messages_py\"\n\t@echo \"... actionlib_msgs_generate_messages_lisp\"\n\t@echo \"... tf2_msgs_generate_messages_py\"\n\t@echo \"... actionlib_msgs_generate_messages_nodejs\"\n\t@echo \"... sensor_msgs_generate_messages_cpp\"\n\t@echo \"... actionlib_generate_messages_nodejs\"\n\t@echo \"... actionlib_msgs_generate_messages_cpp\"\n\t@echo \"... std_msgs_generate_messages_cpp\"\n\t@echo \"... sensor_msgs_generate_messages_eus\"\n\t@echo \"... download_extra_data\"\n\t@echo \"... sensor_msgs_generate_messages_lisp\"\n\t@echo \"... actionlib_generate_messages_cpp\"\n\t@echo \"... sensor_msgs_generate_messages_py\"\n\t@echo \"... rosgraph_msgs_generate_messages_py\"\n\t@echo \"... tf_generate_messages_lisp\"\n\t@echo \"... roscpp_generate_messages_py\"\n\t@echo \"... tf_generate_messages_nodejs\"\n\t@echo \"... tf_generate_messages_py\"\n\t@echo \"... src/CLaserOdometry2D.o\"\n\t@echo \"... src/CLaserOdometry2D.i\"\n\t@echo \"... src/CLaserOdometry2D.s\"\n.PHONY : help\n\n\n\n#=============================================================================\n# Special targets to cleanup operation of make.\n\n# Special rule to run CMake to check the build system integrity.\n# No rule that depends on this can have commands that come from listfiles\n# because they might be regenerated.\ncmake_check_build_system:\n\t$(CMAKE_COMMAND) -H$(CMAKE_SOURCE_DIR) -B$(CMAKE_BINARY_DIR) --check-build-system CMakeFiles/Makefile.cmake 0\n.PHONY : cmake_check_build_system\n\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin/catkin_generated/version/package.cmake",
    "content": "set(_CATKIN_CURRENT_PACKAGE \"catkin\")\nset(catkin_VERSION \"0.7.11\")\nset(catkin_MAINTAINER \"Dirk Thomas <dthomas@osrfoundation.org>\")\nset(catkin_PACKAGE_FORMAT \"2\")\nset(catkin_BUILD_DEPENDS \"python-empy\" \"python-argparse\" \"python-catkin-pkg\")\nset(catkin_BUILD_DEPENDS_python-catkin-pkg_VERSION_GT \"0.2.9\")\nset(catkin_BUILD_EXPORT_DEPENDS \"google-mock\" \"gtest\" \"python-empy\" \"python-nose\" \"python-argparse\" \"python-catkin-pkg\")\nset(catkin_BUILD_EXPORT_DEPENDS_python-catkin-pkg_VERSION_GT \"0.2.9\")\nset(catkin_BUILDTOOL_DEPENDS \"cmake\")\nset(catkin_BUILDTOOL_EXPORT_DEPENDS \"cmake\")\nset(catkin_EXEC_DEPENDS \"python-argparse\" \"python-catkin-pkg\")\nset(catkin_EXEC_DEPENDS_python-catkin-pkg_VERSION_GT \"0.2.9\")\nset(catkin_RUN_DEPENDS \"python-argparse\" \"python-catkin-pkg\" \"google-mock\" \"gtest\" \"python-empy\" \"python-nose\")\nset(catkin_RUN_DEPENDS_python-catkin-pkg_VERSION_GT \"0.2.9\")\nset(catkin_TEST_DEPENDS \"python-mock\" \"python-nose\")\nset(catkin_DOC_DEPENDS )\nset(catkin_URL_WEBSITE \"http://www.ros.org/wiki/catkin\")\nset(catkin_URL_BUGTRACKER \"https://github.com/ros/catkin/issues\")\nset(catkin_URL_REPOSITORY \"https://github.com/ros/catkin\")\nset(catkin_DEPRECATED \"\")"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/env_cached.sh",
    "content": "#!/usr/bin/env sh\n# generated from catkin/cmake/templates/env.sh.in\n\nif [ $# -eq 0 ] ; then\n  /bin/echo \"Usage: env.sh COMMANDS\"\n  /bin/echo \"Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually.\"\n  exit 1\nfi\n\n# ensure to not use different shell type which was set before\nCATKIN_SHELL=sh\n\n# source setup_cached.sh from same directory as this file\n_CATKIN_SETUP_DIR=$(cd \"`dirname \"$0\"`\" > /dev/null && pwd)\n. \"$_CATKIN_SETUP_DIR/setup_cached.sh\"\nexec \"$@\"\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/generate_cached_setup.py",
    "content": "# -*- coding: utf-8 -*-\nfrom __future__ import print_function\nimport argparse\nimport os\nimport stat\nimport sys\n\n# find the import for catkin's python package - either from source space or from an installed underlay\nif os.path.exists(os.path.join('/opt/ros/kinetic/share/catkin/cmake', 'catkinConfig.cmake.in')):\n    sys.path.insert(0, os.path.join('/opt/ros/kinetic/share/catkin/cmake', '..', 'python'))\ntry:\n    from catkin.environment_cache import generate_environment_script\nexcept ImportError:\n    # search for catkin package in all workspaces and prepend to path\n    for workspace in \"/home/zn/artrobot/devel;/opt/ros/kinetic\".split(';'):\n        python_path = os.path.join(workspace, 'lib/python2.7/dist-packages')\n        if os.path.isdir(os.path.join(python_path, 'catkin')):\n            sys.path.insert(0, python_path)\n            break\n    from catkin.environment_cache import generate_environment_script\n\ncode = generate_environment_script('/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/env.sh')\n\noutput_filename = '/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/setup_cached.sh'\nwith open(output_filename, 'w') as f:\n    #print('Generate script for cached setup \"%s\"' % output_filename)\n    f.write('\\n'.join(code))\n\nmode = os.stat(output_filename).st_mode\nos.chmod(output_filename, mode | stat.S_IXUSR)\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/.rosinstall",
    "content": "- setup-file:\n    local-name: /usr/local/setup.sh\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/_setup_util.py",
    "content": "#!/usr/bin/python\n# -*- coding: utf-8 -*-\n\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2012, Willow Garage, Inc.\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of Willow Garage, Inc. nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\n'''This file generates shell code for the setup.SHELL scripts to set environment variables'''\n\nfrom __future__ import print_function\nimport argparse\nimport copy\nimport errno\nimport os\nimport platform\nimport sys\n\nCATKIN_MARKER_FILE = '.catkin'\n\nsystem = platform.system()\nIS_DARWIN = (system == 'Darwin')\nIS_WINDOWS = (system == 'Windows')\n\n# subfolder of workspace prepended to CMAKE_PREFIX_PATH\nENV_VAR_SUBFOLDERS = {\n    'CMAKE_PREFIX_PATH': '',\n    'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')],\n    'PATH': 'bin',\n    'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')],\n    'PYTHONPATH': 'lib/python2.7/dist-packages',\n}\n\n\ndef rollback_env_variables(environ, env_var_subfolders):\n    '''\n    Generate shell code to reset environment variables\n    by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH.\n    This does not cover modifications performed by environment hooks.\n    '''\n    lines = []\n    unmodified_environ = copy.copy(environ)\n    for key in sorted(env_var_subfolders.keys()):\n        subfolders = env_var_subfolders[key]\n        if not isinstance(subfolders, list):\n            subfolders = [subfolders]\n        value = _rollback_env_variable(unmodified_environ, key, subfolders)\n        if value is not None:\n            environ[key] = value\n            lines.append(assignment(key, value))\n    if lines:\n        lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH'))\n    return lines\n\n\ndef _rollback_env_variable(environ, name, subfolders):\n    '''\n    For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder.\n\n    :param subfolders: list of str '' or subfoldername that may start with '/'\n    :returns: the updated value of the environment variable.\n    '''\n    value = environ[name] if name in environ else ''\n    env_paths = [path for path in value.split(os.pathsep) if path]\n    value_modified = False\n    for subfolder in subfolders:\n        if subfolder:\n            if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)):\n                subfolder = subfolder[1:]\n            if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)):\n                subfolder = subfolder[:-1]\n        for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True):\n            path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path\n            path_to_remove = None\n            for env_path in env_paths:\n                env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path\n                if env_path_clean == path_to_find:\n                    path_to_remove = env_path\n                    break\n            if path_to_remove:\n                env_paths.remove(path_to_remove)\n                value_modified = True\n    new_value = os.pathsep.join(env_paths)\n    return new_value if value_modified else None\n\n\ndef _get_workspaces(environ, include_fuerte=False, include_non_existing=False):\n    '''\n    Based on CMAKE_PREFIX_PATH return all catkin workspaces.\n\n    :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool``\n    '''\n    # get all cmake prefix paths\n    env_name = 'CMAKE_PREFIX_PATH'\n    value = environ[env_name] if env_name in environ else ''\n    paths = [path for path in value.split(os.pathsep) if path]\n    # remove non-workspace paths\n    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))]\n    return workspaces\n\n\ndef prepend_env_variables(environ, env_var_subfolders, workspaces):\n    '''\n    Generate shell code to prepend environment variables\n    for the all workspaces.\n    '''\n    lines = []\n    lines.append(comment('prepend folders of workspaces to environment variables'))\n\n    paths = [path for path in workspaces.split(os.pathsep) if path]\n\n    prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '')\n    lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix))\n\n    for key in sorted([key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH']):\n        subfolder = env_var_subfolders[key]\n        prefix = _prefix_env_variable(environ, key, paths, subfolder)\n        lines.append(prepend(environ, key, prefix))\n    return lines\n\n\ndef _prefix_env_variable(environ, name, paths, subfolders):\n    '''\n    Return the prefix to prepend to the environment variable NAME, adding any path in NEW_PATHS_STR without creating duplicate or empty items.\n    '''\n    value = environ[name] if name in environ else ''\n    environ_paths = [path for path in value.split(os.pathsep) if path]\n    checked_paths = []\n    for path in paths:\n        if not isinstance(subfolders, list):\n            subfolders = [subfolders]\n        for subfolder in subfolders:\n            path_tmp = path\n            if subfolder:\n                path_tmp = os.path.join(path_tmp, subfolder)\n            # skip nonexistent paths\n            if not os.path.exists(path_tmp):\n                continue\n            # exclude any path already in env and any path we already added\n            if path_tmp not in environ_paths and path_tmp not in checked_paths:\n                checked_paths.append(path_tmp)\n    prefix_str = os.pathsep.join(checked_paths)\n    if prefix_str != '' and environ_paths:\n        prefix_str += os.pathsep\n    return prefix_str\n\n\ndef assignment(key, value):\n    if not IS_WINDOWS:\n        return 'export %s=\"%s\"' % (key, value)\n    else:\n        return 'set %s=%s' % (key, value)\n\n\ndef comment(msg):\n    if not IS_WINDOWS:\n        return '# %s' % msg\n    else:\n        return 'REM %s' % msg\n\n\ndef prepend(environ, key, prefix):\n    if key not in environ or not environ[key]:\n        return assignment(key, prefix)\n    if not IS_WINDOWS:\n        return 'export %s=\"%s$%s\"' % (key, prefix, key)\n    else:\n        return 'set %s=%s%%%s%%' % (key, prefix, key)\n\n\ndef find_env_hooks(environ, cmake_prefix_path):\n    '''\n    Generate shell code with found environment hooks\n    for the all workspaces.\n    '''\n    lines = []\n    lines.append(comment('found environment hooks in workspaces'))\n\n    generic_env_hooks = []\n    generic_env_hooks_workspace = []\n    specific_env_hooks = []\n    specific_env_hooks_workspace = []\n    generic_env_hooks_by_filename = {}\n    specific_env_hooks_by_filename = {}\n    generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh'\n    specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None\n    # remove non-workspace paths\n    workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))]\n    for workspace in reversed(workspaces):\n        env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d')\n        if os.path.isdir(env_hook_dir):\n            for filename in sorted(os.listdir(env_hook_dir)):\n                if filename.endswith('.%s' % generic_env_hook_ext):\n                    # remove previous env hook with same name if present\n                    if filename in generic_env_hooks_by_filename:\n                        i = generic_env_hooks.index(generic_env_hooks_by_filename[filename])\n                        generic_env_hooks.pop(i)\n                        generic_env_hooks_workspace.pop(i)\n                    # append env hook\n                    generic_env_hooks.append(os.path.join(env_hook_dir, filename))\n                    generic_env_hooks_workspace.append(workspace)\n                    generic_env_hooks_by_filename[filename] = generic_env_hooks[-1]\n                elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext):\n                    # remove previous env hook with same name if present\n                    if filename in specific_env_hooks_by_filename:\n                        i = specific_env_hooks.index(specific_env_hooks_by_filename[filename])\n                        specific_env_hooks.pop(i)\n                        specific_env_hooks_workspace.pop(i)\n                    # append env hook\n                    specific_env_hooks.append(os.path.join(env_hook_dir, filename))\n                    specific_env_hooks_workspace.append(workspace)\n                    specific_env_hooks_by_filename[filename] = specific_env_hooks[-1]\n    env_hooks = generic_env_hooks + specific_env_hooks\n    env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace\n    count = len(env_hooks)\n    lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count))\n    for i in range(count):\n        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i]))\n        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i]))\n    return lines\n\n\ndef _parse_arguments(args=None):\n    parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.')\n    parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context')\n    return parser.parse_known_args(args=args)[0]\n\n\nif __name__ == '__main__':\n    try:\n        try:\n            args = _parse_arguments()\n        except Exception as e:\n            print(e, file=sys.stderr)\n            sys.exit(1)\n\n        # environment at generation time\n        CMAKE_PREFIX_PATH = '/home/zn/artrobot/devel;/opt/ros/kinetic'.split(';')\n        # prepend current workspace if not already part of CPP\n        base_path = os.path.dirname(__file__)\n        if base_path not in CMAKE_PREFIX_PATH:\n            CMAKE_PREFIX_PATH.insert(0, base_path)\n        CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH)\n\n        environ = dict(os.environ)\n        lines = []\n        if not args.extend:\n            lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS)\n        lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH)\n        lines += find_env_hooks(environ, CMAKE_PREFIX_PATH)\n        print('\\n'.join(lines))\n\n        # need to explicitly flush the output\n        sys.stdout.flush()\n    except IOError as e:\n        # and catch potential \"broken pipe\" if stdout is not writable\n        # which can happen when piping the output to a file but the disk is full\n        if e.errno == errno.EPIPE:\n            print(e, file=sys.stderr)\n            sys.exit(2)\n        raise\n\n    sys.exit(0)\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/env.sh",
    "content": "#!/usr/bin/env sh\n# generated from catkin/cmake/templates/env.sh.in\n\nif [ $# -eq 0 ] ; then\n  /bin/echo \"Usage: env.sh COMMANDS\"\n  /bin/echo \"Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually.\"\n  exit 1\nfi\n\n# ensure to not use different shell type which was set before\nCATKIN_SHELL=sh\n\n# source setup.sh from same directory as this file\n_CATKIN_SETUP_DIR=$(cd \"`dirname \"$0\"`\" > /dev/null && pwd)\n. \"$_CATKIN_SETUP_DIR/setup.sh\"\nexec \"$@\"\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometry.pc",
    "content": "prefix=/usr/local\n\nName: rf2o_laser_odometry\nDescription: Description of rf2o_laser_odometry\nVersion: 1.0.0\nCflags: -I/usr/local/include\nLibs: -L/usr/local/lib -llaser_odometry\nRequires: nav_msgs roscpp sensor_msgs std_msgs tf\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometryConfig-version.cmake",
    "content": "# generated from catkin/cmake/template/pkgConfig-version.cmake.in\nset(PACKAGE_VERSION \"1.0.0\")\n\nset(PACKAGE_VERSION_EXACT False)\nset(PACKAGE_VERSION_COMPATIBLE False)\n\nif(\"${PACKAGE_FIND_VERSION}\" VERSION_EQUAL \"${PACKAGE_VERSION}\")\n  set(PACKAGE_VERSION_EXACT True)\n  set(PACKAGE_VERSION_COMPATIBLE True)\nendif()\n\nif(\"${PACKAGE_FIND_VERSION}\" VERSION_LESS \"${PACKAGE_VERSION}\")\n  set(PACKAGE_VERSION_COMPATIBLE True)\nendif()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometryConfig.cmake",
    "content": "# generated from catkin/cmake/template/pkgConfig.cmake.in\n\n# append elements to a list and remove existing duplicates from the list\n# copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig\n# self contained\nmacro(_list_append_deduplicate listname)\n  if(NOT \"${ARGN}\" STREQUAL \"\")\n    if(${listname})\n      list(REMOVE_ITEM ${listname} ${ARGN})\n    endif()\n    list(APPEND ${listname} ${ARGN})\n  endif()\nendmacro()\n\n# append elements to a list if they are not already in the list\n# copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig\n# self contained\nmacro(_list_append_unique listname)\n  foreach(_item ${ARGN})\n    list(FIND ${listname} ${_item} _index)\n    if(_index EQUAL -1)\n      list(APPEND ${listname} ${_item})\n    endif()\n  endforeach()\nendmacro()\n\n# pack a list of libraries with optional build configuration keywords\n# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig\n# self contained\nmacro(_pack_libraries_with_build_configuration VAR)\n  set(${VAR} \"\")\n  set(_argn ${ARGN})\n  list(LENGTH _argn _count)\n  set(_index 0)\n  while(${_index} LESS ${_count})\n    list(GET _argn ${_index} lib)\n    if(\"${lib}\" MATCHES \"^(debug|optimized|general)$\")\n      math(EXPR _index \"${_index} + 1\")\n      if(${_index} EQUAL ${_count})\n        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\")\n      endif()\n      list(GET _argn ${_index} library)\n      list(APPEND ${VAR} \"${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}\")\n    else()\n      list(APPEND ${VAR} \"${lib}\")\n    endif()\n    math(EXPR _index \"${_index} + 1\")\n  endwhile()\nendmacro()\n\n# unpack a list of libraries with optional build configuration keyword prefixes\n# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig\n# self contained\nmacro(_unpack_libraries_with_build_configuration VAR)\n  set(${VAR} \"\")\n  foreach(lib ${ARGN})\n    string(REGEX REPLACE \"^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$\" \"\\\\1;\\\\2\" lib \"${lib}\")\n    list(APPEND ${VAR} \"${lib}\")\n  endforeach()\nendmacro()\n\n\nif(rf2o_laser_odometry_CONFIG_INCLUDED)\n  return()\nendif()\nset(rf2o_laser_odometry_CONFIG_INCLUDED TRUE)\n\n# set variables for source/devel/install prefixes\nif(\"FALSE\" STREQUAL \"TRUE\")\n  set(rf2o_laser_odometry_SOURCE_PREFIX /home/zn/racecar/src/rf2o_laser_odometry)\n  set(rf2o_laser_odometry_DEVEL_PREFIX /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel)\n  set(rf2o_laser_odometry_INSTALL_PREFIX \"\")\n  set(rf2o_laser_odometry_PREFIX ${rf2o_laser_odometry_DEVEL_PREFIX})\nelse()\n  set(rf2o_laser_odometry_SOURCE_PREFIX \"\")\n  set(rf2o_laser_odometry_DEVEL_PREFIX \"\")\n  set(rf2o_laser_odometry_INSTALL_PREFIX /usr/local)\n  set(rf2o_laser_odometry_PREFIX ${rf2o_laser_odometry_INSTALL_PREFIX})\nendif()\n\n# warn when using a deprecated package\nif(NOT \"\" STREQUAL \"\")\n  set(_msg \"WARNING: package 'rf2o_laser_odometry' is deprecated\")\n  # append custom deprecation text if available\n  if(NOT \"\" STREQUAL \"TRUE\")\n    set(_msg \"${_msg} ()\")\n  endif()\n  message(\"${_msg}\")\nendif()\n\n# flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project\nset(rf2o_laser_odometry_FOUND_CATKIN_PROJECT TRUE)\n\nif(NOT \"include \" STREQUAL \" \")\n  set(rf2o_laser_odometry_INCLUDE_DIRS \"\")\n  set(_include_dirs \"include\")\n  if(NOT \" \" STREQUAL \" \")\n    set(_report \"Check the issue tracker '' and consider creating a ticket if the problem has not been reported yet.\")\n  elseif(NOT \" \" STREQUAL \" \")\n    set(_report \"Check the website '' for information and consider reporting the problem.\")\n  else()\n    set(_report \"Report the problem to the maintainer 'Javier G. Monroy <jgmonroy@uma.es>' and request to fix the problem.\")\n  endif()\n  foreach(idir ${_include_dirs})\n    if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir})\n      set(include ${idir})\n    elseif(\"${idir} \" STREQUAL \"include \")\n      get_filename_component(include \"${rf2o_laser_odometry_DIR}/../../../include\" ABSOLUTE)\n      if(NOT IS_DIRECTORY ${include})\n        message(FATAL_ERROR \"Project 'rf2o_laser_odometry' specifies '${idir}' as an include dir, which is not found.  It does not exist in '${include}'.  ${_report}\")\n      endif()\n    else()\n      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}\")\n    endif()\n    _list_append_unique(rf2o_laser_odometry_INCLUDE_DIRS ${include})\n  endforeach()\nendif()\n\nset(libraries \"laser_odometry\")\nforeach(library ${libraries})\n  # keep build configuration keywords, target names and absolute libraries as-is\n  if(\"${library}\" MATCHES \"^(debug|optimized|general)$\")\n    list(APPEND rf2o_laser_odometry_LIBRARIES ${library})\n  elseif(TARGET ${library})\n    list(APPEND rf2o_laser_odometry_LIBRARIES ${library})\n  elseif(IS_ABSOLUTE ${library})\n    list(APPEND rf2o_laser_odometry_LIBRARIES ${library})\n  else()\n    set(lib_path \"\")\n    set(lib \"${library}-NOTFOUND\")\n    # since the path where the library is found is returned we have to iterate over the paths manually\n    foreach(path /usr/local/lib;/home/zn/artrobot/devel/lib;/opt/ros/kinetic/lib)\n      find_library(lib ${library}\n        PATHS ${path}\n        NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH)\n      if(lib)\n        set(lib_path ${path})\n        break()\n      endif()\n    endforeach()\n    if(lib)\n      _list_append_unique(rf2o_laser_odometry_LIBRARY_DIRS ${lib_path})\n      list(APPEND rf2o_laser_odometry_LIBRARIES ${lib})\n    else()\n      # as a fall back for non-catkin libraries try to search globally\n      find_library(lib ${library})\n      if(NOT lib)\n        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?\")\n      endif()\n      list(APPEND rf2o_laser_odometry_LIBRARIES ${lib})\n    endif()\n  endif()\nendforeach()\n\nset(rf2o_laser_odometry_EXPORTED_TARGETS \"\")\n# create dummy targets for exported code generation targets to make life of users easier\nforeach(t ${rf2o_laser_odometry_EXPORTED_TARGETS})\n  if(NOT TARGET ${t})\n    add_custom_target(${t})\n  endif()\nendforeach()\n\nset(depends \"nav_msgs;roscpp;sensor_msgs;std_msgs;tf\")\nforeach(depend ${depends})\n  string(REPLACE \" \" \";\" depend_list ${depend})\n  # the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls\n  list(GET depend_list 0 rf2o_laser_odometry_dep)\n  list(LENGTH depend_list count)\n  if(${count} EQUAL 1)\n    # simple dependencies must only be find_package()-ed once\n    if(NOT ${rf2o_laser_odometry_dep}_FOUND)\n      find_package(${rf2o_laser_odometry_dep} REQUIRED NO_MODULE)\n    endif()\n  else()\n    # dependencies with components must be find_package()-ed again\n    list(REMOVE_AT depend_list 0)\n    find_package(${rf2o_laser_odometry_dep} REQUIRED NO_MODULE ${depend_list})\n  endif()\n  _list_append_unique(rf2o_laser_odometry_INCLUDE_DIRS ${${rf2o_laser_odometry_dep}_INCLUDE_DIRS})\n\n  # merge build configuration keywords with library names to correctly deduplicate\n  _pack_libraries_with_build_configuration(rf2o_laser_odometry_LIBRARIES ${rf2o_laser_odometry_LIBRARIES})\n  _pack_libraries_with_build_configuration(_libraries ${${rf2o_laser_odometry_dep}_LIBRARIES})\n  _list_append_deduplicate(rf2o_laser_odometry_LIBRARIES ${_libraries})\n  # undo build configuration keyword merging after deduplication\n  _unpack_libraries_with_build_configuration(rf2o_laser_odometry_LIBRARIES ${rf2o_laser_odometry_LIBRARIES})\n\n  _list_append_unique(rf2o_laser_odometry_LIBRARY_DIRS ${${rf2o_laser_odometry_dep}_LIBRARY_DIRS})\n  list(APPEND rf2o_laser_odometry_EXPORTED_TARGETS ${${rf2o_laser_odometry_dep}_EXPORTED_TARGETS})\nendforeach()\n\nset(pkg_cfg_extras \"\")\nforeach(extra ${pkg_cfg_extras})\n  if(NOT IS_ABSOLUTE ${extra})\n    set(extra ${rf2o_laser_odometry_DIR}/${extra})\n  endif()\n  include(${extra})\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.bash",
    "content": "#!/usr/bin/env bash\n# generated from catkin/cmake/templates/setup.bash.in\n\nCATKIN_SHELL=bash\n\n# source setup.sh from same directory as this file\n_CATKIN_SETUP_DIR=$(builtin cd \"`dirname \"${BASH_SOURCE[0]}\"`\" > /dev/null && pwd)\n. \"$_CATKIN_SETUP_DIR/setup.sh\"\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.sh",
    "content": "#!/usr/bin/env sh\n# generated from catkin/cmake/template/setup.sh.in\n\n# Sets various environment variables and sources additional environment hooks.\n# It tries it's best to undo changes from a previously sourced setup file before.\n# Supported command line options:\n# --extend: skips the undoing of changes from a previously sourced setup file\n#   (in plain sh shell which does't support arguments for sourced scripts you\n#   can set the environment variable `CATKIN_SETUP_UTIL_ARGS=--extend` instead)\n\n# since this file is sourced either use the provided _CATKIN_SETUP_DIR\n# or fall back to the destination set at configure time\n: ${_CATKIN_SETUP_DIR:=/usr/local}\n_SETUP_UTIL=\"$_CATKIN_SETUP_DIR/_setup_util.py\"\nunset _CATKIN_SETUP_DIR\n\nif [ ! -f \"$_SETUP_UTIL\" ]; then\n  echo \"Missing Python script: $_SETUP_UTIL\"\n  return 22\nfi\n\n# detect if running on Darwin platform\n_UNAME=`uname -s`\n_IS_DARWIN=0\nif [ \"$_UNAME\" = \"Darwin\" ]; then\n  _IS_DARWIN=1\nfi\nunset _UNAME\n\n# make sure to export all environment variables\nexport CMAKE_PREFIX_PATH\nif [ $_IS_DARWIN -eq 0 ]; then\n  export LD_LIBRARY_PATH\nelse\n  export DYLD_LIBRARY_PATH\nfi\nunset _IS_DARWIN\nexport PATH\nexport PKG_CONFIG_PATH\nexport PYTHONPATH\n\n# remember type of shell if not already set\nif [ -z \"$CATKIN_SHELL\" ]; then\n  CATKIN_SHELL=sh\nfi\n\n# invoke Python script to generate necessary exports of environment variables\n# use TMPDIR if it exists, otherwise fall back to /tmp\nif [ -d \"${TMPDIR:-}\" ]; then\n  _TMPDIR=\"${TMPDIR}\"\nelse\n  _TMPDIR=/tmp\nfi\n_SETUP_TMP=`mktemp \"${_TMPDIR}/setup.sh.XXXXXXXXXX\"`\nunset _TMPDIR\nif [ $? -ne 0 -o ! -f \"$_SETUP_TMP\" ]; then\n  echo \"Could not create temporary file: $_SETUP_TMP\"\n  return 1\nfi\nCATKIN_SHELL=$CATKIN_SHELL \"$_SETUP_UTIL\" $@ ${CATKIN_SETUP_UTIL_ARGS:-} >> \"$_SETUP_TMP\"\n_RC=$?\nif [ $_RC -ne 0 ]; then\n  if [ $_RC -eq 2 ]; then\n    echo \"Could not write the output of '$_SETUP_UTIL' to temporary file '$_SETUP_TMP': may be the disk if full?\"\n  else\n    echo \"Failed to run '\\\"$_SETUP_UTIL\\\" $@': return code $_RC\"\n  fi\n  unset _RC\n  unset _SETUP_UTIL\n  rm -f \"$_SETUP_TMP\"\n  unset _SETUP_TMP\n  return 1\nfi\nunset _RC\nunset _SETUP_UTIL\n. \"$_SETUP_TMP\"\nrm -f \"$_SETUP_TMP\"\nunset _SETUP_TMP\n\n# source all environment hooks\n_i=0\nwhile [ $_i -lt $_CATKIN_ENVIRONMENT_HOOKS_COUNT ]; do\n  eval _envfile=\\$_CATKIN_ENVIRONMENT_HOOKS_$_i\n  unset _CATKIN_ENVIRONMENT_HOOKS_$_i\n  eval _envfile_workspace=\\$_CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE\n  unset _CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE\n  # set workspace for environment hook\n  CATKIN_ENV_HOOK_WORKSPACE=$_envfile_workspace\n  . \"$_envfile\"\n  unset CATKIN_ENV_HOOK_WORKSPACE\n  _i=$((_i + 1))\ndone\nunset _i\n\nunset _CATKIN_ENVIRONMENT_HOOKS_COUNT\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.zsh",
    "content": "#!/usr/bin/env zsh\n# generated from catkin/cmake/templates/setup.zsh.in\n\nCATKIN_SHELL=zsh\n\n# source setup.sh from same directory as this file\n_CATKIN_SETUP_DIR=$(builtin cd -q \"`dirname \"$0\"`\" > /dev/null && pwd)\nemulate -R zsh -c 'source \"$_CATKIN_SETUP_DIR/setup.sh\"'\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/ordered_paths.cmake",
    "content": "set(ORDERED_PATHS \"/opt/ros/kinetic/lib\")"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/package.cmake",
    "content": "set(_CATKIN_CURRENT_PACKAGE \"rf2o_laser_odometry\")\nset(rf2o_laser_odometry_VERSION \"1.0.0\")\nset(rf2o_laser_odometry_MAINTAINER \"Javier G. Monroy <jgmonroy@uma.es>\")\nset(rf2o_laser_odometry_PACKAGE_FORMAT \"1\")\nset(rf2o_laser_odometry_BUILD_DEPENDS \"nav_msgs\" \"roscpp\" \"sensor_msgs\" \"std_msgs\" \"tf\" \"cmake_modules\" \"mrpt\")\nset(rf2o_laser_odometry_BUILD_EXPORT_DEPENDS \"nav_msgs\" \"roscpp\" \"sensor_msgs\" \"std_msgs\" \"tf\" \"cmake_modules\" \"mrpt\")\nset(rf2o_laser_odometry_BUILDTOOL_DEPENDS \"catkin\")\nset(rf2o_laser_odometry_BUILDTOOL_EXPORT_DEPENDS )\nset(rf2o_laser_odometry_EXEC_DEPENDS \"nav_msgs\" \"roscpp\" \"sensor_msgs\" \"std_msgs\" \"tf\" \"cmake_modules\" \"mrpt\")\nset(rf2o_laser_odometry_RUN_DEPENDS \"nav_msgs\" \"roscpp\" \"sensor_msgs\" \"std_msgs\" \"tf\" \"cmake_modules\" \"mrpt\")\nset(rf2o_laser_odometry_TEST_DEPENDS )\nset(rf2o_laser_odometry_DOC_DEPENDS )\nset(rf2o_laser_odometry_URL_WEBSITE \"\")\nset(rf2o_laser_odometry_URL_BUGTRACKER \"\")\nset(rf2o_laser_odometry_URL_REPOSITORY \"\")\nset(rf2o_laser_odometry_DEPRECATED \"\")"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/pkg.develspace.context.pc.py",
    "content": "# generated from catkin/cmake/template/pkg.context.pc.in\nCATKIN_PACKAGE_PREFIX = \"\"\nPROJECT_PKG_CONFIG_INCLUDE_DIRS = \"/home/zn/racecar/src/rf2o_laser_odometry/include\".split(';') if \"/home/zn/racecar/src/rf2o_laser_odometry/include\" != \"\" else []\nPROJECT_CATKIN_DEPENDS = \"nav_msgs;roscpp;sensor_msgs;std_msgs;tf\".replace(';', ' ')\nPKG_CONFIG_LIBRARIES_WITH_PREFIX = \"-llaser_odometry\".split(';') if \"-llaser_odometry\" != \"\" else []\nPROJECT_NAME = \"rf2o_laser_odometry\"\nPROJECT_SPACE_DIR = \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel\"\nPROJECT_VERSION = \"1.0.0\"\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/pkg.installspace.context.pc.py",
    "content": "# generated from catkin/cmake/template/pkg.context.pc.in\nCATKIN_PACKAGE_PREFIX = \"\"\nPROJECT_PKG_CONFIG_INCLUDE_DIRS = \"/usr/local/include\".split(';') if \"/usr/local/include\" != \"\" else []\nPROJECT_CATKIN_DEPENDS = \"nav_msgs;roscpp;sensor_msgs;std_msgs;tf\".replace(';', ' ')\nPKG_CONFIG_LIBRARIES_WITH_PREFIX = \"-llaser_odometry\".split(';') if \"-llaser_odometry\" != \"\" else []\nPROJECT_NAME = \"rf2o_laser_odometry\"\nPROJECT_SPACE_DIR = \"/usr/local\"\nPROJECT_VERSION = \"1.0.0\"\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/setup_cached.sh",
    "content": "#!/usr/bin/env sh\n# generated from catkin/python/catkin/environment_cache.py\n\n# based on a snapshot of the environment before and after calling the setup script\n# it emulates the modifications of the setup script without recurring computations\n\n# new environment variables\n\n# modified environment variables\nexport CMAKE_PREFIX_PATH=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel:$CMAKE_PREFIX_PATH\"\nexport ROSLISP_PACKAGE_DIRECTORIES=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/share/common-lisp:$ROSLISP_PACKAGE_DIRECTORIES\"\nexport ROS_PACKAGE_PATH=\"/home/zn/racecar/src/rf2o_laser_odometry:$ROS_PACKAGE_PATH\""
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/stamps/rf2o_laser_odometry/_setup_util.py.stamp",
    "content": "#!/usr/bin/python\n# -*- coding: utf-8 -*-\n\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2012, Willow Garage, Inc.\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of Willow Garage, Inc. nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\n'''This file generates shell code for the setup.SHELL scripts to set environment variables'''\n\nfrom __future__ import print_function\nimport argparse\nimport copy\nimport errno\nimport os\nimport platform\nimport sys\n\nCATKIN_MARKER_FILE = '.catkin'\n\nsystem = platform.system()\nIS_DARWIN = (system == 'Darwin')\nIS_WINDOWS = (system == 'Windows')\n\n# subfolder of workspace prepended to CMAKE_PREFIX_PATH\nENV_VAR_SUBFOLDERS = {\n    'CMAKE_PREFIX_PATH': '',\n    'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')],\n    'PATH': 'bin',\n    'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')],\n    'PYTHONPATH': 'lib/python2.7/dist-packages',\n}\n\n\ndef rollback_env_variables(environ, env_var_subfolders):\n    '''\n    Generate shell code to reset environment variables\n    by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH.\n    This does not cover modifications performed by environment hooks.\n    '''\n    lines = []\n    unmodified_environ = copy.copy(environ)\n    for key in sorted(env_var_subfolders.keys()):\n        subfolders = env_var_subfolders[key]\n        if not isinstance(subfolders, list):\n            subfolders = [subfolders]\n        value = _rollback_env_variable(unmodified_environ, key, subfolders)\n        if value is not None:\n            environ[key] = value\n            lines.append(assignment(key, value))\n    if lines:\n        lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH'))\n    return lines\n\n\ndef _rollback_env_variable(environ, name, subfolders):\n    '''\n    For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder.\n\n    :param subfolders: list of str '' or subfoldername that may start with '/'\n    :returns: the updated value of the environment variable.\n    '''\n    value = environ[name] if name in environ else ''\n    env_paths = [path for path in value.split(os.pathsep) if path]\n    value_modified = False\n    for subfolder in subfolders:\n        if subfolder:\n            if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)):\n                subfolder = subfolder[1:]\n            if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)):\n                subfolder = subfolder[:-1]\n        for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True):\n            path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path\n            path_to_remove = None\n            for env_path in env_paths:\n                env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path\n                if env_path_clean == path_to_find:\n                    path_to_remove = env_path\n                    break\n            if path_to_remove:\n                env_paths.remove(path_to_remove)\n                value_modified = True\n    new_value = os.pathsep.join(env_paths)\n    return new_value if value_modified else None\n\n\ndef _get_workspaces(environ, include_fuerte=False, include_non_existing=False):\n    '''\n    Based on CMAKE_PREFIX_PATH return all catkin workspaces.\n\n    :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool``\n    '''\n    # get all cmake prefix paths\n    env_name = 'CMAKE_PREFIX_PATH'\n    value = environ[env_name] if env_name in environ else ''\n    paths = [path for path in value.split(os.pathsep) if path]\n    # remove non-workspace paths\n    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))]\n    return workspaces\n\n\ndef prepend_env_variables(environ, env_var_subfolders, workspaces):\n    '''\n    Generate shell code to prepend environment variables\n    for the all workspaces.\n    '''\n    lines = []\n    lines.append(comment('prepend folders of workspaces to environment variables'))\n\n    paths = [path for path in workspaces.split(os.pathsep) if path]\n\n    prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '')\n    lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix))\n\n    for key in sorted([key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH']):\n        subfolder = env_var_subfolders[key]\n        prefix = _prefix_env_variable(environ, key, paths, subfolder)\n        lines.append(prepend(environ, key, prefix))\n    return lines\n\n\ndef _prefix_env_variable(environ, name, paths, subfolders):\n    '''\n    Return the prefix to prepend to the environment variable NAME, adding any path in NEW_PATHS_STR without creating duplicate or empty items.\n    '''\n    value = environ[name] if name in environ else ''\n    environ_paths = [path for path in value.split(os.pathsep) if path]\n    checked_paths = []\n    for path in paths:\n        if not isinstance(subfolders, list):\n            subfolders = [subfolders]\n        for subfolder in subfolders:\n            path_tmp = path\n            if subfolder:\n                path_tmp = os.path.join(path_tmp, subfolder)\n            # skip nonexistent paths\n            if not os.path.exists(path_tmp):\n                continue\n            # exclude any path already in env and any path we already added\n            if path_tmp not in environ_paths and path_tmp not in checked_paths:\n                checked_paths.append(path_tmp)\n    prefix_str = os.pathsep.join(checked_paths)\n    if prefix_str != '' and environ_paths:\n        prefix_str += os.pathsep\n    return prefix_str\n\n\ndef assignment(key, value):\n    if not IS_WINDOWS:\n        return 'export %s=\"%s\"' % (key, value)\n    else:\n        return 'set %s=%s' % (key, value)\n\n\ndef comment(msg):\n    if not IS_WINDOWS:\n        return '# %s' % msg\n    else:\n        return 'REM %s' % msg\n\n\ndef prepend(environ, key, prefix):\n    if key not in environ or not environ[key]:\n        return assignment(key, prefix)\n    if not IS_WINDOWS:\n        return 'export %s=\"%s$%s\"' % (key, prefix, key)\n    else:\n        return 'set %s=%s%%%s%%' % (key, prefix, key)\n\n\ndef find_env_hooks(environ, cmake_prefix_path):\n    '''\n    Generate shell code with found environment hooks\n    for the all workspaces.\n    '''\n    lines = []\n    lines.append(comment('found environment hooks in workspaces'))\n\n    generic_env_hooks = []\n    generic_env_hooks_workspace = []\n    specific_env_hooks = []\n    specific_env_hooks_workspace = []\n    generic_env_hooks_by_filename = {}\n    specific_env_hooks_by_filename = {}\n    generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh'\n    specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None\n    # remove non-workspace paths\n    workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))]\n    for workspace in reversed(workspaces):\n        env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d')\n        if os.path.isdir(env_hook_dir):\n            for filename in sorted(os.listdir(env_hook_dir)):\n                if filename.endswith('.%s' % generic_env_hook_ext):\n                    # remove previous env hook with same name if present\n                    if filename in generic_env_hooks_by_filename:\n                        i = generic_env_hooks.index(generic_env_hooks_by_filename[filename])\n                        generic_env_hooks.pop(i)\n                        generic_env_hooks_workspace.pop(i)\n                    # append env hook\n                    generic_env_hooks.append(os.path.join(env_hook_dir, filename))\n                    generic_env_hooks_workspace.append(workspace)\n                    generic_env_hooks_by_filename[filename] = generic_env_hooks[-1]\n                elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext):\n                    # remove previous env hook with same name if present\n                    if filename in specific_env_hooks_by_filename:\n                        i = specific_env_hooks.index(specific_env_hooks_by_filename[filename])\n                        specific_env_hooks.pop(i)\n                        specific_env_hooks_workspace.pop(i)\n                    # append env hook\n                    specific_env_hooks.append(os.path.join(env_hook_dir, filename))\n                    specific_env_hooks_workspace.append(workspace)\n                    specific_env_hooks_by_filename[filename] = specific_env_hooks[-1]\n    env_hooks = generic_env_hooks + specific_env_hooks\n    env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace\n    count = len(env_hooks)\n    lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count))\n    for i in range(count):\n        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i]))\n        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i]))\n    return lines\n\n\ndef _parse_arguments(args=None):\n    parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.')\n    parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context')\n    return parser.parse_known_args(args=args)[0]\n\n\nif __name__ == '__main__':\n    try:\n        try:\n            args = _parse_arguments()\n        except Exception as e:\n            print(e, file=sys.stderr)\n            sys.exit(1)\n\n        # environment at generation time\n        CMAKE_PREFIX_PATH = '/home/zn/artrobot/devel;/opt/ros/kinetic'.split(';')\n        # prepend current workspace if not already part of CPP\n        base_path = os.path.dirname(__file__)\n        if base_path not in CMAKE_PREFIX_PATH:\n            CMAKE_PREFIX_PATH.insert(0, base_path)\n        CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH)\n\n        environ = dict(os.environ)\n        lines = []\n        if not args.extend:\n            lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS)\n        lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH)\n        lines += find_env_hooks(environ, CMAKE_PREFIX_PATH)\n        print('\\n'.join(lines))\n\n        # need to explicitly flush the output\n        sys.stdout.flush()\n    except IOError as e:\n        # and catch potential \"broken pipe\" if stdout is not writable\n        # which can happen when piping the output to a file but the disk is full\n        if e.errno == errno.EPIPE:\n            print(e, file=sys.stderr)\n            sys.exit(2)\n        raise\n\n    sys.exit(0)\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/stamps/rf2o_laser_odometry/interrogate_setup_dot_py.py.stamp",
    "content": "#!/usr/bin/env python\n\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2012, Willow Garage, Inc.\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of Willow Garage, Inc. nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\nfrom __future__ import print_function\nimport os\nimport runpy\nimport sys\n\nimport distutils.core\ntry:\n    import setuptools\nexcept ImportError:\n    pass\n\nfrom argparse import ArgumentParser\n\n\ndef _get_locations(pkgs, package_dir):\n    \"\"\"\n    based on setuptools logic and the package_dir dict, builds a dict\n    of location roots for each pkg in pkgs.\n    See http://docs.python.org/distutils/setupscript.html\n\n    :returns: a dict {pkgname: root} for each pkgname in pkgs (and each of their parents)\n    \"\"\"\n    # package_dir contains a dict {package_name: relativepath}\n    # Example {'': 'src', 'foo': 'lib', 'bar': 'lib2'}\n    #\n    # '' means where to look for any package unless a parent package\n    # is listed so package bar.pot is expected at lib2/bar/pot,\n    # whereas package sup.dee is expected at src/sup/dee\n    #\n    # if package_dir does not state anything about a package,\n    # setuptool expects the package folder to be in the root of the\n    # project\n    locations = {}\n    allprefix = package_dir.get('', '')\n    for pkg in pkgs:\n        parent_location = None\n        splits = pkg.split('.')\n        # we iterate over compound name from parent to child\n        # so once we found parent, children just append to their parent\n        for key_len in range(len(splits)):\n            key = '.'.join(splits[:key_len + 1])\n            if key not in locations:\n                if key in package_dir:\n                    locations[key] = package_dir[key]\n                elif parent_location is not None:\n                    locations[key] = os.path.join(parent_location, splits[key_len])\n                else:\n                    locations[key] = os.path.join(allprefix, key)\n            parent_location = locations[key]\n    return locations\n\n\ndef generate_cmake_file(package_name, version, scripts, package_dir, pkgs, modules):\n    \"\"\"\n    Generates lines to add to a cmake file which will set variables\n\n    :param version: str, format 'int.int.int'\n    :param scripts: [list of str]: relative paths to scripts\n    :param package_dir: {modulename: path}\n    :pkgs: [list of str] python_packages declared in catkin package\n    :modules: [list of str] python modules\n    \"\"\"\n    prefix = '%s_SETUP_PY' % package_name\n    result = []\n    result.append(r'set(%s_VERSION \"%s\")' % (prefix, version))\n    result.append(r'set(%s_SCRIPTS \"%s\")' % (prefix, ';'.join(scripts)))\n\n    # Remove packages with '.' separators.\n    #\n    # setuptools allows specifying submodules in other folders than\n    # their parent\n    #\n    # The symlink approach of catkin does not work with such submodules.\n    # In the common case, this does not matter as the submodule is\n    # within the containing module.  We verify this assumption, and if\n    # it passes, we remove submodule packages.\n    locations = _get_locations(pkgs, package_dir)\n    for pkgname, location in locations.items():\n        if not '.' in pkgname:\n            continue\n        splits = pkgname.split('.')\n        # hack: ignore write-combining setup.py files for msg and srv files\n        if splits[1] in ['msg', 'srv']:\n            continue\n        # check every child has the same root folder as its parent\n        root_name = splits[0]\n        root_location = location\n        for _ in range(len(splits) - 1):\n            root_location = os.path.dirname(root_location)\n        if root_location != locations[root_name]:\n            raise RuntimeError(\n                \"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]))\n\n    # If checks pass, remove all submodules\n    pkgs = [p for p in pkgs if '.' not in p]\n\n    resolved_pkgs = []\n    for pkg in pkgs:\n        resolved_pkgs += [locations[pkg]]\n\n    result.append(r'set(%s_PACKAGES \"%s\")' % (prefix, ';'.join(pkgs)))\n    result.append(r'set(%s_PACKAGE_DIRS \"%s\")' % (prefix, ';'.join(resolved_pkgs).replace(\"\\\\\", \"/\")))\n\n    # skip modules which collide with package names\n    filtered_modules = []\n    for modname in modules:\n        splits = modname.split('.')\n        # check all parents too\n        equals_package = [('.'.join(splits[:-i]) in locations) for i in range(len(splits))]\n        if any(equals_package):\n            continue\n        filtered_modules.append(modname)\n    module_locations = _get_locations(filtered_modules, package_dir)\n\n    result.append(r'set(%s_MODULES \"%s\")' % (prefix, ';'.join(['%s.py' % m.replace('.', '/') for m in filtered_modules])))\n    result.append(r'set(%s_MODULE_DIRS \"%s\")' % (prefix, ';'.join([module_locations[m] for m in filtered_modules]).replace(\"\\\\\", \"/\")))\n\n    return result\n\n\ndef _create_mock_setup_function(package_name, outfile):\n    \"\"\"\n    Creates a function to call instead of distutils.core.setup or\n    setuptools.setup, which just captures some args and writes them\n    into a file that can be used from cmake\n\n    :param package_name: name of the package\n    :param outfile: filename that cmake will use afterwards\n    :returns: a function to replace disutils.core.setup and setuptools.setup\n    \"\"\"\n\n    def setup(*args, **kwargs):\n        '''\n        Checks kwargs and writes a scriptfile\n        '''\n        if 'version' not in kwargs:\n            sys.stderr.write(\"\\n*** Unable to find 'version' in setup.py of %s\\n\" % package_name)\n            raise RuntimeError(\"version not found in setup.py\")\n        version = kwargs['version']\n        package_dir = kwargs.get('package_dir', {})\n\n        pkgs = kwargs.get('packages', [])\n        scripts = kwargs.get('scripts', [])\n        modules = kwargs.get('py_modules', [])\n\n        unsupported_args = [\n            'entry_points',\n            'exclude_package_data',\n            'ext_modules ',\n            'ext_package',\n            'include_package_data',\n            'namespace_packages',\n            'setup_requires',\n            'use_2to3',\n            'zip_safe']\n        used_unsupported_args = [arg for arg in unsupported_args if arg in kwargs]\n        if used_unsupported_args:\n            sys.stderr.write(\"*** Arguments %s to setup() not supported in catkin devel space in setup.py of %s\\n\" % (used_unsupported_args, package_name))\n\n        result = generate_cmake_file(package_name=package_name,\n                                     version=version,\n                                     scripts=scripts,\n                                     package_dir=package_dir,\n                                     pkgs=pkgs,\n                                     modules=modules)\n        with open(outfile, 'w') as out:\n            out.write('\\n'.join(result))\n\n    return setup\n\n\ndef main():\n    \"\"\"\n    Script main, parses arguments and invokes Dummy.setup indirectly.\n    \"\"\"\n    parser = ArgumentParser(description='Utility to read setup.py values from cmake macros. Creates a file with CMake set commands setting variables.')\n    parser.add_argument('package_name', help='Name of catkin package')\n    parser.add_argument('setupfile_path', help='Full path to setup.py')\n    parser.add_argument('outfile', help='Where to write result to')\n\n    args = parser.parse_args()\n\n    # print(\"%s\" % sys.argv)\n    # PACKAGE_NAME = sys.argv[1]\n    # OUTFILE = sys.argv[3]\n    # print(\"Interrogating setup.py for package %s into %s \" % (PACKAGE_NAME, OUTFILE),\n    #      file=sys.stderr)\n\n    # print(\"executing %s\" % args.setupfile_path)\n\n    # be sure you're in the directory containing\n    # setup.py so the sys.path manipulation works,\n    # so the import of __version__ works\n    os.chdir(os.path.dirname(os.path.abspath(args.setupfile_path)))\n\n    # patch setup() function of distutils and setuptools for the\n    # context of evaluating setup.py\n    try:\n        fake_setup = _create_mock_setup_function(package_name=args.package_name,\n                                                outfile=args.outfile)\n\n        distutils_backup = distutils.core.setup\n        distutils.core.setup = fake_setup\n        try:\n            setuptools_backup = setuptools.setup\n            setuptools.setup = fake_setup\n        except NameError:\n            pass\n\n        runpy.run_path(args.setupfile_path)\n    finally:\n        distutils.core.setup = distutils_backup\n        try:\n            setuptools.setup = setuptools_backup\n        except NameError:\n            pass\n\nif __name__ == '__main__':\n    main()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/stamps/rf2o_laser_odometry/package.xml.stamp",
    "content": "<?xml version=\"1.0\"?>\n<package>\n\n  <name>rf2o_laser_odometry</name>\n  <version>1.0.0</version>\n  <description>\n    Estimation of 2D odometry based on planar laser scans. Useful for mobile robots with innacurate base odometry.\n    For full description of the algorithm, please refer to:\n    Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA 2016\n    Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217\n  </description>\n\n  <maintainer email=\"jgmonroy@uma.es\">Javier G. Monroy</maintainer>\n  <author email=\"marianojt@uma.es\"> Mariano Jaimez</author>\n  <author email=\"jgmonroy@uma.es\"> Javier G. Monroy</author>\n  <license>GPL v3</license> \n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>nav_msgs</build_depend>\n  <build_depend>roscpp</build_depend>\n  <build_depend>sensor_msgs</build_depend>\n  <build_depend>std_msgs</build_depend>\n  <build_depend>tf</build_depend>\n  <build_depend>cmake_modules</build_depend>   <!-- A common repository for CMake Modules which are not distributed with CMake but are commonly used by ROS packages. -->\n                                               <!-- https://github.com/ros/cmake_modules/blob/0.3-devel/README.md -->\n  <build_depend>mrpt</build_depend>            <!-- Depend on mrpt system pkgs: http://www.mrpt.org/ -->\n\n\n  <run_depend>nav_msgs</run_depend>\n  <run_depend>roscpp</run_depend>\n  <run_depend>sensor_msgs</run_depend>\n  <run_depend>std_msgs</run_depend>\n  <run_depend>tf</run_depend>\n  <run_depend>cmake_modules</run_depend>       <!-- For aditional dependencies such as Eigen -->\n  <run_depend>mrpt</run_depend>                <!-- Depend on mrpt system pkgs -->\n\n</package>\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/stamps/rf2o_laser_odometry/pkg.pc.em.stamp",
    "content": "prefix=@PROJECT_SPACE_DIR\n\nName: @(CATKIN_PACKAGE_PREFIX + PROJECT_NAME)\nDescription: Description of @PROJECT_NAME\nVersion: @PROJECT_VERSION\nCflags: @(' '.join(['-I%s' % include for include in PROJECT_PKG_CONFIG_INCLUDE_DIRS]))\nLibs: -L@PROJECT_SPACE_DIR/lib @(' '.join(PKG_CONFIG_LIBRARIES_WITH_PREFIX))\nRequires: @(PROJECT_CATKIN_DEPENDS)\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/cmake_install.cmake",
    "content": "# Install script for directory: /home/zn/racecar/src/rf2o_laser_odometry\n\n# Set the install prefix\nif(NOT DEFINED CMAKE_INSTALL_PREFIX)\n  set(CMAKE_INSTALL_PREFIX \"/usr/local\")\nendif()\nstring(REGEX REPLACE \"/$\" \"\" CMAKE_INSTALL_PREFIX \"${CMAKE_INSTALL_PREFIX}\")\n\n# Set the install configuration name.\nif(NOT DEFINED CMAKE_INSTALL_CONFIG_NAME)\n  if(BUILD_TYPE)\n    string(REGEX REPLACE \"^[^A-Za-z0-9_]+\" \"\"\n           CMAKE_INSTALL_CONFIG_NAME \"${BUILD_TYPE}\")\n  else()\n    set(CMAKE_INSTALL_CONFIG_NAME \"Debug\")\n  endif()\n  message(STATUS \"Install configuration: \\\"${CMAKE_INSTALL_CONFIG_NAME}\\\"\")\nendif()\n\n# Set the component getting installed.\nif(NOT CMAKE_INSTALL_COMPONENT)\n  if(COMPONENT)\n    message(STATUS \"Install component: \\\"${COMPONENT}\\\"\")\n    set(CMAKE_INSTALL_COMPONENT \"${COMPONENT}\")\n  else()\n    set(CMAKE_INSTALL_COMPONENT)\n  endif()\nendif()\n\n# Install shared libraries without execute permission?\nif(NOT DEFINED CMAKE_INSTALL_SO_NO_EXE)\n  set(CMAKE_INSTALL_SO_NO_EXE \"1\")\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  \n      if (NOT EXISTS \"$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}\")\n        file(MAKE_DIRECTORY \"$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}\")\n      endif()\n      if (NOT EXISTS \"$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/.catkin\")\n        file(WRITE \"$ENV{DESTDIR}${CMAKE_INSTALL_PREFIX}/.catkin\" \"\")\n      endif()\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES\n   \"/usr/local/_setup_util.py\")\n  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(WARNING \"ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\n  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(FATAL_ERROR \"ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\nfile(INSTALL DESTINATION \"/usr/local\" TYPE PROGRAM FILES \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/_setup_util.py\")\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES\n   \"/usr/local/env.sh\")\n  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(WARNING \"ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\n  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(FATAL_ERROR \"ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\nfile(INSTALL DESTINATION \"/usr/local\" TYPE PROGRAM FILES \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/env.sh\")\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES\n   \"/usr/local/setup.bash\")\n  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(WARNING \"ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\n  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(FATAL_ERROR \"ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\nfile(INSTALL DESTINATION \"/usr/local\" TYPE FILE FILES \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.bash\")\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES\n   \"/usr/local/setup.sh\")\n  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(WARNING \"ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\n  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(FATAL_ERROR \"ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\nfile(INSTALL DESTINATION \"/usr/local\" TYPE FILE FILES \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.sh\")\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES\n   \"/usr/local/setup.zsh\")\n  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(WARNING \"ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\n  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(FATAL_ERROR \"ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\nfile(INSTALL DESTINATION \"/usr/local\" TYPE FILE FILES \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/setup.zsh\")\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  list(APPEND CMAKE_ABSOLUTE_DESTINATION_FILES\n   \"/usr/local/.rosinstall\")\n  if(CMAKE_WARN_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(WARNING \"ABSOLUTE path INSTALL DESTINATION : ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\n  if(CMAKE_ERROR_ON_ABSOLUTE_INSTALL_DESTINATION)\n    message(FATAL_ERROR \"ABSOLUTE path INSTALL DESTINATION forbidden (by caller): ${CMAKE_ABSOLUTE_DESTINATION_FILES}\")\n  endif()\nfile(INSTALL DESTINATION \"/usr/local\" TYPE FILE FILES \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/.rosinstall\")\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  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\")\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  file(INSTALL DESTINATION \"${CMAKE_INSTALL_PREFIX}/share/rf2o_laser_odometry/cmake\" TYPE FILE FILES\n    \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometryConfig.cmake\"\n    \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/rf2o_laser_odometryConfig-version.cmake\"\n    )\nendif()\n\nif(\"${CMAKE_INSTALL_COMPONENT}\" STREQUAL \"Unspecified\" OR NOT CMAKE_INSTALL_COMPONENT)\n  file(INSTALL DESTINATION \"${CMAKE_INSTALL_PREFIX}/share/rf2o_laser_odometry\" TYPE FILE FILES \"/home/zn/racecar/src/rf2o_laser_odometry/package.xml\")\nendif()\n\nif(CMAKE_INSTALL_COMPONENT)\n  set(CMAKE_INSTALL_MANIFEST \"install_manifest_${CMAKE_INSTALL_COMPONENT}.txt\")\nelse()\n  set(CMAKE_INSTALL_MANIFEST \"install_manifest.txt\")\nendif()\n\nstring(REPLACE \";\" \"\\n\" CMAKE_INSTALL_MANIFEST_CONTENT\n       \"${CMAKE_INSTALL_MANIFEST_FILES}\")\nfile(WRITE \"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/${CMAKE_INSTALL_MANIFEST}\"\n     \"${CMAKE_INSTALL_MANIFEST_CONTENT}\")\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/.catkin",
    "content": "/home/zn/racecar/src/rf2o_laser_odometry"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/.rosinstall",
    "content": "- setup-file:\n    local-name: /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/setup.sh\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/_setup_util.py",
    "content": "#!/usr/bin/python\n# -*- coding: utf-8 -*-\n\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2012, Willow Garage, Inc.\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of Willow Garage, Inc. nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\n'''This file generates shell code for the setup.SHELL scripts to set environment variables'''\n\nfrom __future__ import print_function\nimport argparse\nimport copy\nimport errno\nimport os\nimport platform\nimport sys\n\nCATKIN_MARKER_FILE = '.catkin'\n\nsystem = platform.system()\nIS_DARWIN = (system == 'Darwin')\nIS_WINDOWS = (system == 'Windows')\n\n# subfolder of workspace prepended to CMAKE_PREFIX_PATH\nENV_VAR_SUBFOLDERS = {\n    'CMAKE_PREFIX_PATH': '',\n    'LD_LIBRARY_PATH' if not IS_DARWIN else 'DYLD_LIBRARY_PATH': ['lib', os.path.join('lib', 'x86_64-linux-gnu')],\n    'PATH': 'bin',\n    'PKG_CONFIG_PATH': [os.path.join('lib', 'pkgconfig'), os.path.join('lib', 'x86_64-linux-gnu', 'pkgconfig')],\n    'PYTHONPATH': 'lib/python2.7/dist-packages',\n}\n\n\ndef rollback_env_variables(environ, env_var_subfolders):\n    '''\n    Generate shell code to reset environment variables\n    by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH.\n    This does not cover modifications performed by environment hooks.\n    '''\n    lines = []\n    unmodified_environ = copy.copy(environ)\n    for key in sorted(env_var_subfolders.keys()):\n        subfolders = env_var_subfolders[key]\n        if not isinstance(subfolders, list):\n            subfolders = [subfolders]\n        value = _rollback_env_variable(unmodified_environ, key, subfolders)\n        if value is not None:\n            environ[key] = value\n            lines.append(assignment(key, value))\n    if lines:\n        lines.insert(0, comment('reset environment variables by unrolling modifications based on all workspaces in CMAKE_PREFIX_PATH'))\n    return lines\n\n\ndef _rollback_env_variable(environ, name, subfolders):\n    '''\n    For each catkin workspace in CMAKE_PREFIX_PATH remove the first entry from env[NAME] matching workspace + subfolder.\n\n    :param subfolders: list of str '' or subfoldername that may start with '/'\n    :returns: the updated value of the environment variable.\n    '''\n    value = environ[name] if name in environ else ''\n    env_paths = [path for path in value.split(os.pathsep) if path]\n    value_modified = False\n    for subfolder in subfolders:\n        if subfolder:\n            if subfolder.startswith(os.path.sep) or (os.path.altsep and subfolder.startswith(os.path.altsep)):\n                subfolder = subfolder[1:]\n            if subfolder.endswith(os.path.sep) or (os.path.altsep and subfolder.endswith(os.path.altsep)):\n                subfolder = subfolder[:-1]\n        for ws_path in _get_workspaces(environ, include_fuerte=True, include_non_existing=True):\n            path_to_find = os.path.join(ws_path, subfolder) if subfolder else ws_path\n            path_to_remove = None\n            for env_path in env_paths:\n                env_path_clean = env_path[:-1] if env_path and env_path[-1] in [os.path.sep, os.path.altsep] else env_path\n                if env_path_clean == path_to_find:\n                    path_to_remove = env_path\n                    break\n            if path_to_remove:\n                env_paths.remove(path_to_remove)\n                value_modified = True\n    new_value = os.pathsep.join(env_paths)\n    return new_value if value_modified else None\n\n\ndef _get_workspaces(environ, include_fuerte=False, include_non_existing=False):\n    '''\n    Based on CMAKE_PREFIX_PATH return all catkin workspaces.\n\n    :param include_fuerte: The flag if paths starting with '/opt/ros/fuerte' should be considered workspaces, ``bool``\n    '''\n    # get all cmake prefix paths\n    env_name = 'CMAKE_PREFIX_PATH'\n    value = environ[env_name] if env_name in environ else ''\n    paths = [path for path in value.split(os.pathsep) if path]\n    # remove non-workspace paths\n    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))]\n    return workspaces\n\n\ndef prepend_env_variables(environ, env_var_subfolders, workspaces):\n    '''\n    Generate shell code to prepend environment variables\n    for the all workspaces.\n    '''\n    lines = []\n    lines.append(comment('prepend folders of workspaces to environment variables'))\n\n    paths = [path for path in workspaces.split(os.pathsep) if path]\n\n    prefix = _prefix_env_variable(environ, 'CMAKE_PREFIX_PATH', paths, '')\n    lines.append(prepend(environ, 'CMAKE_PREFIX_PATH', prefix))\n\n    for key in sorted([key for key in env_var_subfolders.keys() if key != 'CMAKE_PREFIX_PATH']):\n        subfolder = env_var_subfolders[key]\n        prefix = _prefix_env_variable(environ, key, paths, subfolder)\n        lines.append(prepend(environ, key, prefix))\n    return lines\n\n\ndef _prefix_env_variable(environ, name, paths, subfolders):\n    '''\n    Return the prefix to prepend to the environment variable NAME, adding any path in NEW_PATHS_STR without creating duplicate or empty items.\n    '''\n    value = environ[name] if name in environ else ''\n    environ_paths = [path for path in value.split(os.pathsep) if path]\n    checked_paths = []\n    for path in paths:\n        if not isinstance(subfolders, list):\n            subfolders = [subfolders]\n        for subfolder in subfolders:\n            path_tmp = path\n            if subfolder:\n                path_tmp = os.path.join(path_tmp, subfolder)\n            # skip nonexistent paths\n            if not os.path.exists(path_tmp):\n                continue\n            # exclude any path already in env and any path we already added\n            if path_tmp not in environ_paths and path_tmp not in checked_paths:\n                checked_paths.append(path_tmp)\n    prefix_str = os.pathsep.join(checked_paths)\n    if prefix_str != '' and environ_paths:\n        prefix_str += os.pathsep\n    return prefix_str\n\n\ndef assignment(key, value):\n    if not IS_WINDOWS:\n        return 'export %s=\"%s\"' % (key, value)\n    else:\n        return 'set %s=%s' % (key, value)\n\n\ndef comment(msg):\n    if not IS_WINDOWS:\n        return '# %s' % msg\n    else:\n        return 'REM %s' % msg\n\n\ndef prepend(environ, key, prefix):\n    if key not in environ or not environ[key]:\n        return assignment(key, prefix)\n    if not IS_WINDOWS:\n        return 'export %s=\"%s$%s\"' % (key, prefix, key)\n    else:\n        return 'set %s=%s%%%s%%' % (key, prefix, key)\n\n\ndef find_env_hooks(environ, cmake_prefix_path):\n    '''\n    Generate shell code with found environment hooks\n    for the all workspaces.\n    '''\n    lines = []\n    lines.append(comment('found environment hooks in workspaces'))\n\n    generic_env_hooks = []\n    generic_env_hooks_workspace = []\n    specific_env_hooks = []\n    specific_env_hooks_workspace = []\n    generic_env_hooks_by_filename = {}\n    specific_env_hooks_by_filename = {}\n    generic_env_hook_ext = 'bat' if IS_WINDOWS else 'sh'\n    specific_env_hook_ext = environ['CATKIN_SHELL'] if not IS_WINDOWS and 'CATKIN_SHELL' in environ and environ['CATKIN_SHELL'] else None\n    # remove non-workspace paths\n    workspaces = [path for path in cmake_prefix_path.split(os.pathsep) if path and os.path.isfile(os.path.join(path, CATKIN_MARKER_FILE))]\n    for workspace in reversed(workspaces):\n        env_hook_dir = os.path.join(workspace, 'etc', 'catkin', 'profile.d')\n        if os.path.isdir(env_hook_dir):\n            for filename in sorted(os.listdir(env_hook_dir)):\n                if filename.endswith('.%s' % generic_env_hook_ext):\n                    # remove previous env hook with same name if present\n                    if filename in generic_env_hooks_by_filename:\n                        i = generic_env_hooks.index(generic_env_hooks_by_filename[filename])\n                        generic_env_hooks.pop(i)\n                        generic_env_hooks_workspace.pop(i)\n                    # append env hook\n                    generic_env_hooks.append(os.path.join(env_hook_dir, filename))\n                    generic_env_hooks_workspace.append(workspace)\n                    generic_env_hooks_by_filename[filename] = generic_env_hooks[-1]\n                elif specific_env_hook_ext is not None and filename.endswith('.%s' % specific_env_hook_ext):\n                    # remove previous env hook with same name if present\n                    if filename in specific_env_hooks_by_filename:\n                        i = specific_env_hooks.index(specific_env_hooks_by_filename[filename])\n                        specific_env_hooks.pop(i)\n                        specific_env_hooks_workspace.pop(i)\n                    # append env hook\n                    specific_env_hooks.append(os.path.join(env_hook_dir, filename))\n                    specific_env_hooks_workspace.append(workspace)\n                    specific_env_hooks_by_filename[filename] = specific_env_hooks[-1]\n    env_hooks = generic_env_hooks + specific_env_hooks\n    env_hooks_workspace = generic_env_hooks_workspace + specific_env_hooks_workspace\n    count = len(env_hooks)\n    lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_COUNT', count))\n    for i in range(count):\n        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d' % i, env_hooks[i]))\n        lines.append(assignment('_CATKIN_ENVIRONMENT_HOOKS_%d_WORKSPACE' % i, env_hooks_workspace[i]))\n    return lines\n\n\ndef _parse_arguments(args=None):\n    parser = argparse.ArgumentParser(description='Generates code blocks for the setup.SHELL script.')\n    parser.add_argument('--extend', action='store_true', help='Skip unsetting previous environment variables to extend context')\n    return parser.parse_known_args(args=args)[0]\n\n\nif __name__ == '__main__':\n    try:\n        try:\n            args = _parse_arguments()\n        except Exception as e:\n            print(e, file=sys.stderr)\n            sys.exit(1)\n\n        # environment at generation time\n        CMAKE_PREFIX_PATH = '/home/zn/artrobot/devel;/opt/ros/kinetic'.split(';')\n        # prepend current workspace if not already part of CPP\n        base_path = os.path.dirname(__file__)\n        if base_path not in CMAKE_PREFIX_PATH:\n            CMAKE_PREFIX_PATH.insert(0, base_path)\n        CMAKE_PREFIX_PATH = os.pathsep.join(CMAKE_PREFIX_PATH)\n\n        environ = dict(os.environ)\n        lines = []\n        if not args.extend:\n            lines += rollback_env_variables(environ, ENV_VAR_SUBFOLDERS)\n        lines += prepend_env_variables(environ, ENV_VAR_SUBFOLDERS, CMAKE_PREFIX_PATH)\n        lines += find_env_hooks(environ, CMAKE_PREFIX_PATH)\n        print('\\n'.join(lines))\n\n        # need to explicitly flush the output\n        sys.stdout.flush()\n    except IOError as e:\n        # and catch potential \"broken pipe\" if stdout is not writable\n        # which can happen when piping the output to a file but the disk is full\n        if e.errno == errno.EPIPE:\n            print(e, file=sys.stderr)\n            sys.exit(2)\n        raise\n\n    sys.exit(0)\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/env.sh",
    "content": "#!/usr/bin/env sh\n# generated from catkin/cmake/templates/env.sh.in\n\nif [ $# -eq 0 ] ; then\n  /bin/echo \"Usage: env.sh COMMANDS\"\n  /bin/echo \"Calling env.sh without arguments is not supported anymore. Instead spawn a subshell and source a setup file manually.\"\n  exit 1\nfi\n\n# ensure to not use different shell type which was set before\nCATKIN_SHELL=sh\n\n# source setup.sh from same directory as this file\n_CATKIN_SETUP_DIR=$(cd \"`dirname \"$0\"`\" > /dev/null && pwd)\n. \"$_CATKIN_SETUP_DIR/setup.sh\"\nexec \"$@\"\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/lib/pkgconfig/rf2o_laser_odometry.pc",
    "content": "prefix=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel\n\nName: rf2o_laser_odometry\nDescription: Description of rf2o_laser_odometry\nVersion: 1.0.0\nCflags: -I/home/zn/racecar/src/rf2o_laser_odometry/include\nLibs: -L/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/lib -llaser_odometry\nRequires: nav_msgs roscpp sensor_msgs std_msgs tf\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/setup.bash",
    "content": "#!/usr/bin/env bash\n# generated from catkin/cmake/templates/setup.bash.in\n\nCATKIN_SHELL=bash\n\n# source setup.sh from same directory as this file\n_CATKIN_SETUP_DIR=$(builtin cd \"`dirname \"${BASH_SOURCE[0]}\"`\" > /dev/null && pwd)\n. \"$_CATKIN_SETUP_DIR/setup.sh\"\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/setup.sh",
    "content": "#!/usr/bin/env sh\n# generated from catkin/cmake/template/setup.sh.in\n\n# Sets various environment variables and sources additional environment hooks.\n# It tries it's best to undo changes from a previously sourced setup file before.\n# Supported command line options:\n# --extend: skips the undoing of changes from a previously sourced setup file\n#   (in plain sh shell which does't support arguments for sourced scripts you\n#   can set the environment variable `CATKIN_SETUP_UTIL_ARGS=--extend` instead)\n\n# since this file is sourced either use the provided _CATKIN_SETUP_DIR\n# or fall back to the destination set at configure time\n: ${_CATKIN_SETUP_DIR:=/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel}\n_SETUP_UTIL=\"$_CATKIN_SETUP_DIR/_setup_util.py\"\nunset _CATKIN_SETUP_DIR\n\nif [ ! -f \"$_SETUP_UTIL\" ]; then\n  echo \"Missing Python script: $_SETUP_UTIL\"\n  return 22\nfi\n\n# detect if running on Darwin platform\n_UNAME=`uname -s`\n_IS_DARWIN=0\nif [ \"$_UNAME\" = \"Darwin\" ]; then\n  _IS_DARWIN=1\nfi\nunset _UNAME\n\n# make sure to export all environment variables\nexport CMAKE_PREFIX_PATH\nif [ $_IS_DARWIN -eq 0 ]; then\n  export LD_LIBRARY_PATH\nelse\n  export DYLD_LIBRARY_PATH\nfi\nunset _IS_DARWIN\nexport PATH\nexport PKG_CONFIG_PATH\nexport PYTHONPATH\n\n# remember type of shell if not already set\nif [ -z \"$CATKIN_SHELL\" ]; then\n  CATKIN_SHELL=sh\nfi\n\n# invoke Python script to generate necessary exports of environment variables\n# use TMPDIR if it exists, otherwise fall back to /tmp\nif [ -d \"${TMPDIR:-}\" ]; then\n  _TMPDIR=\"${TMPDIR}\"\nelse\n  _TMPDIR=/tmp\nfi\n_SETUP_TMP=`mktemp \"${_TMPDIR}/setup.sh.XXXXXXXXXX\"`\nunset _TMPDIR\nif [ $? -ne 0 -o ! -f \"$_SETUP_TMP\" ]; then\n  echo \"Could not create temporary file: $_SETUP_TMP\"\n  return 1\nfi\nCATKIN_SHELL=$CATKIN_SHELL \"$_SETUP_UTIL\" $@ ${CATKIN_SETUP_UTIL_ARGS:-} >> \"$_SETUP_TMP\"\n_RC=$?\nif [ $_RC -ne 0 ]; then\n  if [ $_RC -eq 2 ]; then\n    echo \"Could not write the output of '$_SETUP_UTIL' to temporary file '$_SETUP_TMP': may be the disk if full?\"\n  else\n    echo \"Failed to run '\\\"$_SETUP_UTIL\\\" $@': return code $_RC\"\n  fi\n  unset _RC\n  unset _SETUP_UTIL\n  rm -f \"$_SETUP_TMP\"\n  unset _SETUP_TMP\n  return 1\nfi\nunset _RC\nunset _SETUP_UTIL\n. \"$_SETUP_TMP\"\nrm -f \"$_SETUP_TMP\"\nunset _SETUP_TMP\n\n# source all environment hooks\n_i=0\nwhile [ $_i -lt $_CATKIN_ENVIRONMENT_HOOKS_COUNT ]; do\n  eval _envfile=\\$_CATKIN_ENVIRONMENT_HOOKS_$_i\n  unset _CATKIN_ENVIRONMENT_HOOKS_$_i\n  eval _envfile_workspace=\\$_CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE\n  unset _CATKIN_ENVIRONMENT_HOOKS_${_i}_WORKSPACE\n  # set workspace for environment hook\n  CATKIN_ENV_HOOK_WORKSPACE=$_envfile_workspace\n  . \"$_envfile\"\n  unset CATKIN_ENV_HOOK_WORKSPACE\n  _i=$((_i + 1))\ndone\nunset _i\n\nunset _CATKIN_ENVIRONMENT_HOOKS_COUNT\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/setup.zsh",
    "content": "#!/usr/bin/env zsh\n# generated from catkin/cmake/templates/setup.zsh.in\n\nCATKIN_SHELL=zsh\n\n# source setup.sh from same directory as this file\n_CATKIN_SETUP_DIR=$(builtin cd -q \"`dirname \"$0\"`\" > /dev/null && pwd)\nemulate -R zsh -c 'source \"$_CATKIN_SETUP_DIR/setup.sh\"'\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/share/rf2o_laser_odometry/cmake/rf2o_laser_odometryConfig-version.cmake",
    "content": "# generated from catkin/cmake/template/pkgConfig-version.cmake.in\nset(PACKAGE_VERSION \"1.0.0\")\n\nset(PACKAGE_VERSION_EXACT False)\nset(PACKAGE_VERSION_COMPATIBLE False)\n\nif(\"${PACKAGE_FIND_VERSION}\" VERSION_EQUAL \"${PACKAGE_VERSION}\")\n  set(PACKAGE_VERSION_EXACT True)\n  set(PACKAGE_VERSION_COMPATIBLE True)\nendif()\n\nif(\"${PACKAGE_FIND_VERSION}\" VERSION_LESS \"${PACKAGE_VERSION}\")\n  set(PACKAGE_VERSION_COMPATIBLE True)\nendif()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/devel/share/rf2o_laser_odometry/cmake/rf2o_laser_odometryConfig.cmake",
    "content": "# generated from catkin/cmake/template/pkgConfig.cmake.in\n\n# append elements to a list and remove existing duplicates from the list\n# copied from catkin/cmake/list_append_deduplicate.cmake to keep pkgConfig\n# self contained\nmacro(_list_append_deduplicate listname)\n  if(NOT \"${ARGN}\" STREQUAL \"\")\n    if(${listname})\n      list(REMOVE_ITEM ${listname} ${ARGN})\n    endif()\n    list(APPEND ${listname} ${ARGN})\n  endif()\nendmacro()\n\n# append elements to a list if they are not already in the list\n# copied from catkin/cmake/list_append_unique.cmake to keep pkgConfig\n# self contained\nmacro(_list_append_unique listname)\n  foreach(_item ${ARGN})\n    list(FIND ${listname} ${_item} _index)\n    if(_index EQUAL -1)\n      list(APPEND ${listname} ${_item})\n    endif()\n  endforeach()\nendmacro()\n\n# pack a list of libraries with optional build configuration keywords\n# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig\n# self contained\nmacro(_pack_libraries_with_build_configuration VAR)\n  set(${VAR} \"\")\n  set(_argn ${ARGN})\n  list(LENGTH _argn _count)\n  set(_index 0)\n  while(${_index} LESS ${_count})\n    list(GET _argn ${_index} lib)\n    if(\"${lib}\" MATCHES \"^(debug|optimized|general)$\")\n      math(EXPR _index \"${_index} + 1\")\n      if(${_index} EQUAL ${_count})\n        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\")\n      endif()\n      list(GET _argn ${_index} library)\n      list(APPEND ${VAR} \"${lib}${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}${library}\")\n    else()\n      list(APPEND ${VAR} \"${lib}\")\n    endif()\n    math(EXPR _index \"${_index} + 1\")\n  endwhile()\nendmacro()\n\n# unpack a list of libraries with optional build configuration keyword prefixes\n# copied from catkin/cmake/catkin_libraries.cmake to keep pkgConfig\n# self contained\nmacro(_unpack_libraries_with_build_configuration VAR)\n  set(${VAR} \"\")\n  foreach(lib ${ARGN})\n    string(REGEX REPLACE \"^(debug|optimized|general)${CATKIN_BUILD_CONFIGURATION_KEYWORD_SEPARATOR}(.+)$\" \"\\\\1;\\\\2\" lib \"${lib}\")\n    list(APPEND ${VAR} \"${lib}\")\n  endforeach()\nendmacro()\n\n\nif(rf2o_laser_odometry_CONFIG_INCLUDED)\n  return()\nendif()\nset(rf2o_laser_odometry_CONFIG_INCLUDED TRUE)\n\n# set variables for source/devel/install prefixes\nif(\"TRUE\" STREQUAL \"TRUE\")\n  set(rf2o_laser_odometry_SOURCE_PREFIX /home/zn/racecar/src/rf2o_laser_odometry)\n  set(rf2o_laser_odometry_DEVEL_PREFIX /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel)\n  set(rf2o_laser_odometry_INSTALL_PREFIX \"\")\n  set(rf2o_laser_odometry_PREFIX ${rf2o_laser_odometry_DEVEL_PREFIX})\nelse()\n  set(rf2o_laser_odometry_SOURCE_PREFIX \"\")\n  set(rf2o_laser_odometry_DEVEL_PREFIX \"\")\n  set(rf2o_laser_odometry_INSTALL_PREFIX /usr/local)\n  set(rf2o_laser_odometry_PREFIX ${rf2o_laser_odometry_INSTALL_PREFIX})\nendif()\n\n# warn when using a deprecated package\nif(NOT \"\" STREQUAL \"\")\n  set(_msg \"WARNING: package 'rf2o_laser_odometry' is deprecated\")\n  # append custom deprecation text if available\n  if(NOT \"\" STREQUAL \"TRUE\")\n    set(_msg \"${_msg} ()\")\n  endif()\n  message(\"${_msg}\")\nendif()\n\n# flag project as catkin-based to distinguish if a find_package()-ed project is a catkin project\nset(rf2o_laser_odometry_FOUND_CATKIN_PROJECT TRUE)\n\nif(NOT \"/home/zn/racecar/src/rf2o_laser_odometry/include \" STREQUAL \" \")\n  set(rf2o_laser_odometry_INCLUDE_DIRS \"\")\n  set(_include_dirs \"/home/zn/racecar/src/rf2o_laser_odometry/include\")\n  if(NOT \" \" STREQUAL \" \")\n    set(_report \"Check the issue tracker '' and consider creating a ticket if the problem has not been reported yet.\")\n  elseif(NOT \" \" STREQUAL \" \")\n    set(_report \"Check the website '' for information and consider reporting the problem.\")\n  else()\n    set(_report \"Report the problem to the maintainer 'Javier G. Monroy <jgmonroy@uma.es>' and request to fix the problem.\")\n  endif()\n  foreach(idir ${_include_dirs})\n    if(IS_ABSOLUTE ${idir} AND IS_DIRECTORY ${idir})\n      set(include ${idir})\n    elseif(\"${idir} \" STREQUAL \"include \")\n      get_filename_component(include \"${rf2o_laser_odometry_DIR}/../../../include\" ABSOLUTE)\n      if(NOT IS_DIRECTORY ${include})\n        message(FATAL_ERROR \"Project 'rf2o_laser_odometry' specifies '${idir}' as an include dir, which is not found.  It does not exist in '${include}'.  ${_report}\")\n      endif()\n    else()\n      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}\")\n    endif()\n    _list_append_unique(rf2o_laser_odometry_INCLUDE_DIRS ${include})\n  endforeach()\nendif()\n\nset(libraries \"laser_odometry\")\nforeach(library ${libraries})\n  # keep build configuration keywords, target names and absolute libraries as-is\n  if(\"${library}\" MATCHES \"^(debug|optimized|general)$\")\n    list(APPEND rf2o_laser_odometry_LIBRARIES ${library})\n  elseif(TARGET ${library})\n    list(APPEND rf2o_laser_odometry_LIBRARIES ${library})\n  elseif(IS_ABSOLUTE ${library})\n    list(APPEND rf2o_laser_odometry_LIBRARIES ${library})\n  else()\n    set(lib_path \"\")\n    set(lib \"${library}-NOTFOUND\")\n    # since the path where the library is found is returned we have to iterate over the paths manually\n    foreach(path /home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/lib;/home/zn/artrobot/devel/lib;/opt/ros/kinetic/lib)\n      find_library(lib ${library}\n        PATHS ${path}\n        NO_DEFAULT_PATH NO_CMAKE_FIND_ROOT_PATH)\n      if(lib)\n        set(lib_path ${path})\n        break()\n      endif()\n    endforeach()\n    if(lib)\n      _list_append_unique(rf2o_laser_odometry_LIBRARY_DIRS ${lib_path})\n      list(APPEND rf2o_laser_odometry_LIBRARIES ${lib})\n    else()\n      # as a fall back for non-catkin libraries try to search globally\n      find_library(lib ${library})\n      if(NOT lib)\n        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?\")\n      endif()\n      list(APPEND rf2o_laser_odometry_LIBRARIES ${lib})\n    endif()\n  endif()\nendforeach()\n\nset(rf2o_laser_odometry_EXPORTED_TARGETS \"\")\n# create dummy targets for exported code generation targets to make life of users easier\nforeach(t ${rf2o_laser_odometry_EXPORTED_TARGETS})\n  if(NOT TARGET ${t})\n    add_custom_target(${t})\n  endif()\nendforeach()\n\nset(depends \"nav_msgs;roscpp;sensor_msgs;std_msgs;tf\")\nforeach(depend ${depends})\n  string(REPLACE \" \" \";\" depend_list ${depend})\n  # the package name of the dependency must be kept in a unique variable so that it is not overwritten in recursive calls\n  list(GET depend_list 0 rf2o_laser_odometry_dep)\n  list(LENGTH depend_list count)\n  if(${count} EQUAL 1)\n    # simple dependencies must only be find_package()-ed once\n    if(NOT ${rf2o_laser_odometry_dep}_FOUND)\n      find_package(${rf2o_laser_odometry_dep} REQUIRED NO_MODULE)\n    endif()\n  else()\n    # dependencies with components must be find_package()-ed again\n    list(REMOVE_AT depend_list 0)\n    find_package(${rf2o_laser_odometry_dep} REQUIRED NO_MODULE ${depend_list})\n  endif()\n  _list_append_unique(rf2o_laser_odometry_INCLUDE_DIRS ${${rf2o_laser_odometry_dep}_INCLUDE_DIRS})\n\n  # merge build configuration keywords with library names to correctly deduplicate\n  _pack_libraries_with_build_configuration(rf2o_laser_odometry_LIBRARIES ${rf2o_laser_odometry_LIBRARIES})\n  _pack_libraries_with_build_configuration(_libraries ${${rf2o_laser_odometry_dep}_LIBRARIES})\n  _list_append_deduplicate(rf2o_laser_odometry_LIBRARIES ${_libraries})\n  # undo build configuration keyword merging after deduplication\n  _unpack_libraries_with_build_configuration(rf2o_laser_odometry_LIBRARIES ${rf2o_laser_odometry_LIBRARIES})\n\n  _list_append_unique(rf2o_laser_odometry_LIBRARY_DIRS ${${rf2o_laser_odometry_dep}_LIBRARY_DIRS})\n  list(APPEND rf2o_laser_odometry_EXPORTED_TARGETS ${${rf2o_laser_odometry_dep}_EXPORTED_TARGETS})\nendforeach()\n\nset(pkg_cfg_extras \"\")\nforeach(extra ${pkg_cfg_extras})\n  if(NOT IS_ABSOLUTE ${extra})\n    set(extra ${rf2o_laser_odometry_DIR}/${extra})\n  endif()\n  include(${extra})\nendforeach()\n"
  },
  {
    "path": "src/rf2o_laser_odometry/cmake-build-debug/rf2o_laser_odometry.cbp",
    "content": "<?xml version=\"1.0\" encoding=\"UTF-8\"?>\n<CodeBlocks_project_file>\n\t<FileVersion major=\"1\" minor=\"6\"/>\n\t<Project>\n\t\t<Option title=\"rf2o_laser_odometry\"/>\n\t\t<Option makefile_is_custom=\"1\"/>\n\t\t<Option compiler=\"gcc\"/>\n\t\t<Option virtualFolders=\"CMake Files\\;CMake Files\\..\\;CMake Files\\..\\..\\;CMake Files\\..\\..\\..\\;CMake Files\\..\\..\\..\\..\\;CMake Files\\..\\..\\..\\..\\..\\;CMake Files\\..\\..\\..\\..\\..\\opt\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\platform\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\test\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\tools\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\em\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cpp_common\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cpp_common\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_runtime\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_runtime\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp_serialization\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp_serialization\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp_traits\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp_traits\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rostime\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rostime\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosconsole\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosconsole\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph_msgs\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph_msgs\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\std_msgs\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\std_msgs\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\xmlrpcpp\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\xmlrpcpp\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rospy\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rospy\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\nav_msgs\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\nav_msgs\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geometry_msgs\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geometry_msgs\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib_msgs\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib_msgs\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genmsg\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genmsg\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gencpp\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gencpp\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geneus\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geneus\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genlisp\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genlisp\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gennodejs\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gennodejs\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genpy\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genpy\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\sensor_msgs\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\sensor_msgs\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_filters\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_filters\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_ros\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_ros\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_msgs\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_msgs\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_generation\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_generation\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_py\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_py\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cmake_modules\\;CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cmake_modules\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\usr\\;CMake Files\\..\\..\\..\\..\\..\\usr\\lib\\;CMake Files\\..\\..\\..\\..\\..\\usr\\lib\\cmake\\;CMake Files\\..\\..\\..\\..\\..\\usr\\lib\\cmake\\eigen3\\;CMake Files\\..\\..\\..\\..\\..\\usr\\share\\;CMake Files\\..\\..\\..\\..\\..\\usr\\share\\mrpt\\;CMake Files\\cmake-build-debug\\;CMake Files\\cmake-build-debug\\catkin\\;CMake Files\\cmake-build-debug\\catkin\\catkin_generated\\;CMake Files\\cmake-build-debug\\catkin\\catkin_generated\\version\\;CMake Files\\cmake-build-debug\\catkin_generated\\;CMake Files\\cmake-build-debug\\catkin_generated\\installspace\\;\"/>\n\t\t<Build>\n\t\t\t<Target title=\"all\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 all\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"install/local\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 install/local\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"edit_cache\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 edit_cache\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf2_msgs_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf2_msgs_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf2_msgs_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf2_msgs_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf2_msgs_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf2_msgs_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf2_msgs_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf2_msgs_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"install/strip\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 install/strip\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"nav_msgs_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 nav_msgs_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"std_msgs_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 std_msgs_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"roscpp_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 roscpp_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"rosgraph_msgs_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 rosgraph_msgs_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tests\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tests\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"rf2o_laser_odometry_node\">\n\t\t\t\t<Option output=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node\" prefix_auto=\"0\" extension_auto=\"0\"/>\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/lib/rf2o_laser_odometry\"/>\n\t\t\t\t<Option object_output=\"./\"/>\n\t\t\t\t<Option type=\"1\"/>\n\t\t\t\t<Option compiler=\"gcc\"/>\n\t\t\t\t<Compiler>\n\t\t\t\t\t<Add option=\"-DROS_PACKAGE_NAME=&quot;rf2o_laser_odometry&quot;\"/>\n\t\t\t\t\t<Add option=\"-DROSCONSOLE_BACKEND_LOG4CXX\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/eigen3\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/mrpt-config\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/bayes/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/graphs/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/vision/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/tfest/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/maps/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/obs/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/opengl/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/base/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/slam/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/topography/include\"/>\n\t\t\t\t\t<Add directory=\"/home/zn/racecar/src/rf2o_laser_odometry/include\"/>\n\t\t\t\t\t<Add directory=\"/opt/ros/kinetic/include\"/>\n\t\t\t\t\t<Add directory=\"/opt/ros/kinetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/c++/5\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/x86_64-linux-gnu/c++/5\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/c++/5/backward\"/>\n\t\t\t\t\t<Add directory=\"/usr/lib/gcc/x86_64-linux-gnu/5/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/local/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/lib/gcc/x86_64-linux-gnu/5/include-fixed\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/x86_64-linux-gnu\"/>\n\t\t\t\t\t<Add directory=\"/usr/include\"/>\n\t\t\t\t</Compiler>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 rf2o_laser_odometry_node\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"rf2o_laser_odometry_node/fast\">\n\t\t\t\t<Option output=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/lib/rf2o_laser_odometry/rf2o_laser_odometry_node\" prefix_auto=\"0\" extension_auto=\"0\"/>\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/devel/lib/rf2o_laser_odometry\"/>\n\t\t\t\t<Option object_output=\"./\"/>\n\t\t\t\t<Option type=\"1\"/>\n\t\t\t\t<Option compiler=\"gcc\"/>\n\t\t\t\t<Compiler>\n\t\t\t\t\t<Add option=\"-DROS_PACKAGE_NAME=&quot;rf2o_laser_odometry&quot;\"/>\n\t\t\t\t\t<Add option=\"-DROSCONSOLE_BACKEND_LOG4CXX\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/eigen3\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/mrpt-config\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/bayes/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/graphs/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/vision/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/tfest/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/maps/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/obs/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/opengl/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/base/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/slam/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/mrpt/topography/include\"/>\n\t\t\t\t\t<Add directory=\"/home/zn/racecar/src/rf2o_laser_odometry/include\"/>\n\t\t\t\t\t<Add directory=\"/opt/ros/kinetic/include\"/>\n\t\t\t\t\t<Add directory=\"/opt/ros/kinetic/share/xmlrpcpp/cmake/../../../include/xmlrpcpp\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/c++/5\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/x86_64-linux-gnu/c++/5\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/c++/5/backward\"/>\n\t\t\t\t\t<Add directory=\"/usr/lib/gcc/x86_64-linux-gnu/5/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/local/include\"/>\n\t\t\t\t\t<Add directory=\"/usr/lib/gcc/x86_64-linux-gnu/5/include-fixed\"/>\n\t\t\t\t\t<Add directory=\"/usr/include/x86_64-linux-gnu\"/>\n\t\t\t\t\t<Add directory=\"/usr/include\"/>\n\t\t\t\t</Compiler>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 rf2o_laser_odometry_node/fast\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"roscpp_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 roscpp_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"rebuild_cache\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 rebuild_cache\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"rosgraph_msgs_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 rosgraph_msgs_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"nav_msgs_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 nav_msgs_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"install\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 install\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"std_msgs_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 std_msgs_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"geometry_msgs_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 geometry_msgs_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"rosgraph_msgs_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 rosgraph_msgs_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"run_tests\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 run_tests\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_msgs_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_msgs_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"list_install_components\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 list_install_components\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"roscpp_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 roscpp_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"roscpp_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 roscpp_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"geometry_msgs_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 geometry_msgs_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_msgs_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_msgs_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"clean_test_results\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean_test_results\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"geometry_msgs_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 geometry_msgs_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"rosgraph_msgs_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 rosgraph_msgs_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"doxygen\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 doxygen\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"nav_msgs_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 nav_msgs_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"nav_msgs_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 nav_msgs_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"std_msgs_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 std_msgs_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"nav_msgs_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 nav_msgs_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"test\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 test\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"geometry_msgs_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 geometry_msgs_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"sensor_msgs_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 sensor_msgs_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"std_msgs_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 std_msgs_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"geometry_msgs_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 geometry_msgs_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_msgs_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_msgs_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf2_msgs_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf2_msgs_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_msgs_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_msgs_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"sensor_msgs_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 sensor_msgs_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_msgs_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_msgs_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"std_msgs_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 std_msgs_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"sensor_msgs_generate_messages_eus\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 sensor_msgs_generate_messages_eus\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"download_extra_data\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 download_extra_data\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"sensor_msgs_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 sensor_msgs_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"actionlib_generate_messages_cpp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 actionlib_generate_messages_cpp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"sensor_msgs_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 sensor_msgs_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"rosgraph_msgs_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 rosgraph_msgs_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf_generate_messages_lisp\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf_generate_messages_lisp\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"roscpp_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 roscpp_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf_generate_messages_nodejs\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf_generate_messages_nodejs\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t\t<Target title=\"tf_generate_messages_py\">\n\t\t\t\t<Option working_dir=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug\"/>\n\t\t\t\t<Option type=\"4\"/>\n\t\t\t\t<MakeCommands>\n\t\t\t\t\t<Build command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 tf_generate_messages_py\"/>\n\t\t\t\t\t<CompileFile command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 &quot;$file&quot;\"/>\n\t\t\t\t\t<Clean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t\t<DistClean command=\"/usr/bin/make -j8 -f &quot;/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/Makefile&quot;  VERBOSE=1 clean\"/>\n\t\t\t\t</MakeCommands>\n\t\t\t</Target>\n\t\t</Build>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp\">\n\t\t\t<Option target=\"rf2o_laser_odometry_node\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/CMakeLists.txt\">\n\t\t\t<Option virtualFolder=\"CMake Files\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/package.xml\">\n\t\t\t<Option virtualFolder=\"CMake Files\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/package.xml\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkinConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/all.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/assert.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/atomic_configure_file.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_add_env_hooks.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_destinations.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_download.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_generate_environment.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_install_python.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_libraries.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_metapackage.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_package.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_package_xml.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_workspace.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/debug_message.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/em_expand.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/python.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/empy.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/find_program_required.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/legacy.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/list_append_deduplicate.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/list_append_unique.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/list_insert_in_workspace_order.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/safe_execute_process.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/stamp.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/string_starts_with.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkin_python_setup.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/interrogate_setup_dot_py.py\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkinConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/platform/lsb.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\platform\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/platform/ubuntu.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\platform\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/platform/windows.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\platform\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/test/tests.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\test\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/test/catkin_download_test_data.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\test\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/test/gtest.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\test\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/test/nosetests.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\test\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/tools/doxygen.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\tools\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/tools/libraries.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\tools\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/tools/rt.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\tools\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/_setup_util.py.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/env.sh.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/setup.bash.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/setup.sh.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/setup.zsh.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/rosinstall.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/_setup_util.py.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/env.sh.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/setup.bash.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/setup.sh.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/setup.zsh.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/rosinstall.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/generate_cached_setup.py.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/env.sh.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/pkg.context.pc.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/pkgConfig.cmake.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/pkgConfig-version.cmake.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/pkg.context.pc.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/pkgConfig.cmake.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/templates/pkgConfig-version.cmake.in\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\templates\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/em/pkg.pc.em\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\em\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/catkin/cmake/em/pkg.pc.em\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\catkin\\cmake\\em\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/roscpp/cmake/roscppConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/roscpp/cmake/roscppConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/roscpp/cmake/roscpp-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/cpp_common/cmake/cpp_commonConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cpp_common\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/cpp_common/cmake/cpp_commonConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cpp_common\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/message_runtime/cmake/message_runtimeConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_runtime\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/message_runtime/cmake/message_runtimeConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_runtime\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/roscpp_serialization/cmake/roscpp_serializationConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp_serialization\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/roscpp_serialization/cmake/roscpp_serializationConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp_serialization\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/roscpp_traits/cmake/roscpp_traitsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp_traits\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/roscpp_traits/cmake/roscpp_traitsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\roscpp_traits\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rostime/cmake/rostimeConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rostime\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rostime/cmake/rostimeConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rostime\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rosconsole/cmake/rosconsoleConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosconsole\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rosconsole/cmake/rosconsoleConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosconsole\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rosconsole/cmake/rosconsole-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosconsole\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rosgraph_msgs/cmake/rosgraph_msgs-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/std_msgs/cmake/std_msgsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\std_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/std_msgs/cmake/std_msgsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\std_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/std_msgs/cmake/std_msgs-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\std_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/std_msgs/cmake/std_msgsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\std_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/std_msgs/cmake/std_msgsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\std_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcppConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\xmlrpcpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcppConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\xmlrpcpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/xmlrpcpp/cmake/xmlrpcpp-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\xmlrpcpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rospy/cmake/rospyConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rospy\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rospy/cmake/rospyConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rospy\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/nav_msgs/cmake/nav_msgsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\nav_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/nav_msgs/cmake/nav_msgsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\nav_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/nav_msgs/cmake/nav_msgs-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\nav_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geometry_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geometry_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/geometry_msgs/cmake/geometry_msgs-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geometry_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgs-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/actionlib_msgs/cmake/actionlib_msgs-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genmsg/cmake/genmsgConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genmsg\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genmsg/cmake/genmsgConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genmsg\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genmsg/cmake/genmsg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genmsg\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genmsg/cmake/genmsgConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genmsg\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genmsg/cmake/genmsgConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genmsg\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/gencpp/cmake/gencppConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gencpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/gencpp/cmake/gencppConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gencpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/gencpp/cmake/gencpp-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gencpp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/geneus/cmake/geneusConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geneus\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/geneus/cmake/geneusConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geneus\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/geneus/cmake/geneus-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\geneus\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genlisp/cmake/genlispConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genlisp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genlisp/cmake/genlispConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genlisp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genlisp/cmake/genlisp-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genlisp\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/gennodejs/cmake/gennodejsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gennodejs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/gennodejs/cmake/gennodejsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gennodejs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/gennodejs/cmake/gennodejs-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\gennodejs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genpy/cmake/genpyConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genpy\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genpy/cmake/genpyConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genpy\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/genpy/cmake/genpy-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\genpy\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\sensor_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\sensor_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/sensor_msgs/cmake/sensor_msgs-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\sensor_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf/cmake/tfConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf/cmake/tfConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf/cmake/tf-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/message_filters/cmake/message_filtersConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_filters\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/message_filters/cmake/message_filtersConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_filters\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2_ros/cmake/tf2_rosConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_ros\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2_ros/cmake/tf2_rosConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_ros\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/actionlib/cmake/actionlibConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/actionlib/cmake/actionlibConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/actionlib/cmake/actionlib-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\actionlib\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rosgraph/cmake/rosgraphConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/rosgraph/cmake/rosgraphConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\rosgraph\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2/cmake/tf2Config-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2/cmake/tf2Config.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgsConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgsConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2_msgs/cmake/tf2_msgs-msg-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_msgs\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/message_generation/cmake/message_generationConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_generation\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/message_generation/cmake/message_generationConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\message_generation\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2_py/cmake/tf2_pyConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_py\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/tf2_py/cmake/tf2_pyConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\tf2_py\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/cmake_modules/cmake/cmake_modulesConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cmake_modules\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/cmake_modules/cmake/cmake_modulesConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cmake_modules\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../opt/ros/kinetic/share/cmake_modules/cmake/cmake_modules-extras.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\opt\\ros\\kinetic\\share\\cmake_modules\\cmake\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../usr/lib/cmake/eigen3/Eigen3Config.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\usr\\lib\\cmake\\eigen3\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../usr/share/mrpt/MRPTConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\usr\\share\\mrpt\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../usr/share/mrpt/MRPTConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\usr\\share\\mrpt\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../usr/share/mrpt/MRPTConfig-version.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\usr\\share\\mrpt\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/../../../../../usr/share/mrpt/MRPTConfig.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\..\\..\\..\\..\\..\\usr\\share\\mrpt\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin/catkin_generated/version/package.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\cmake-build-debug\\catkin\\catkin_generated\\version\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/ordered_paths.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\cmake-build-debug\\catkin_generated\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/ordered_paths.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\cmake-build-debug\\catkin_generated\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/package.cmake\">\n\t\t\t<Option virtualFolder=\"CMake Files\\cmake-build-debug\\catkin_generated\\\"/>\n\t\t</Unit>\n\t\t<Unit filename=\"/home/zn/racecar/src/rf2o_laser_odometry/cmake-build-debug/catkin_generated/installspace/_setup_util.py\">\n\t\t\t<Option virtualFolder=\"CMake Files\\cmake-build-debug\\catkin_generated\\installspace\\\"/>\n\t\t</Unit>\n\t</Project>\n</CodeBlocks_project_file>\n"
  },
  {
    "path": "src/rf2o_laser_odometry/include/rf2o_laser_odometry/CLaserOdometry2D.h",
    "content": "/** ****************************************************************************************\n*  This node presents a fast and precise method to estimate the planar motion of a lidar\n*  from consecutive range scans. It is very useful for the estimation of the robot odometry from\n*  2D laser range measurements.\n*  This module is developed for mobile robots with innacurate or inexistent built-in odometry.\n*  It allows the estimation of a precise odometry with low computational cost.\n*  For more information, please refer to:\n*\n*  Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA'16.\n*  Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217\n*\n* Maintainer: Javier G. Monroy\n* MAPIR group: http://mapir.isa.uma.es/\n******************************************************************************************** */\n\n#ifndef CLaserOdometry2D_H\n#define CLaserOdometry2D_H\n\n#include <ros/ros.h>\n#include <tf/transform_broadcaster.h>\n#include <tf/transform_listener.h>\n#include <nav_msgs/Odometry.h>\n#include <sensor_msgs/LaserScan.h>\n#include <geometry_msgs/Twist.h>\n\n// MRPT related headers\n#include <mrpt/version.h>\n#if MRPT_VERSION>=0x130\n    #include <mrpt/obs/CObservation2DRangeScan.h>\n    #include <mrpt/obs/CObservationOdometry.h>\n    #include <mrpt/utils/CTicTac.h>\n    using namespace mrpt::obs;\n#else\n#   include <mrpt/slam/CObservation2DRangeScan.h>\n#   include <mrpt/slam/CObservationOdometry.h>\n    using namespace mrpt::slam;\n    #include <mrpt/utils.h>\n#endif\n\n#if MRPT_VERSION<0x150\n#   include <mrpt/system/threads.h>\n#endif\n\n#include <mrpt/system/os.h>\n#include <mrpt/poses/CPose3D.h>\n#include <mrpt/opengl.h>\n#include <mrpt/math/CHistogram.h>\n\n#include <boost/bind.hpp>\n#include <Eigen/Dense>\n#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n#include <fstream>\n#include <numeric>\n\n\n\nclass CLaserOdometry2D\n{\npublic:\n\tCLaserOdometry2D();\n    ~CLaserOdometry2D();\n    bool is_initialized();\n    bool scan_available();\n    void Init();\n    void odometryCalculation();\n\n    std::string         laser_scan_topic;\n    std::string         odom_topic;\n    bool                publish_tf;\n    std::string         base_frame_id;\n    std::string         odom_frame_id;\n    std::string         init_pose_from_topic;\n    double              freq;\n\nprotected:\n    ros::NodeHandle             n;\n    sensor_msgs::LaserScan      last_scan;\n    bool                        module_initialized,first_laser_scan,new_scan_available, GT_pose_initialized, verbose;\n    tf::TransformListener       tf_listener;          //Do not put inside the callback\n    tf::TransformBroadcaster    odom_broadcaster;\n    nav_msgs::Odometry          initial_robot_pose;\n\n    //Subscriptions & Publishers\n    ros::Subscriber laser_sub, initPose_sub;\n    ros::Publisher odom_pub;\n\n    //CallBacks\n    void LaserCallBack(const sensor_msgs::LaserScan::ConstPtr& new_scan);\n    void initPoseCallBack(const nav_msgs::Odometry::ConstPtr& new_initPose);\n\n    // Internal Data\n\tstd::vector<Eigen::MatrixXf> range;\n\tstd::vector<Eigen::MatrixXf> range_old;\n\tstd::vector<Eigen::MatrixXf> range_inter;\n\tstd::vector<Eigen::MatrixXf> range_warped;\n\tstd::vector<Eigen::MatrixXf> xx;\n\tstd::vector<Eigen::MatrixXf> xx_inter;\n\tstd::vector<Eigen::MatrixXf> xx_old;\n\tstd::vector<Eigen::MatrixXf> xx_warped;\n\tstd::vector<Eigen::MatrixXf> yy;\n\tstd::vector<Eigen::MatrixXf> yy_inter;\n\tstd::vector<Eigen::MatrixXf> yy_old;\n\tstd::vector<Eigen::MatrixXf> yy_warped;\n\tstd::vector<Eigen::MatrixXf> transformations;\n\t\n\tEigen::MatrixXf range_wf;\n\tEigen::MatrixXf dtita;\n\tEigen::MatrixXf dt;\n\tEigen::MatrixXf rtita;\n\tEigen::MatrixXf normx, normy, norm_ang;\n\tEigen::MatrixXf weights;\n\tEigen::MatrixXi null;\n\n    Eigen::MatrixXf A,Aw;\n    Eigen::MatrixXf B,Bw;\n\tEigen::Matrix<float, 3, 1> Var;\t//3 unknowns: vx, vy, w\n\tEigen::Matrix<float, 3, 3> cov_odo;\n\n\n\n    //std::string LaserVarName;\t\t\t\t//Name of the topic containing the scan lasers \\laser_scan\n\tfloat fps;\t\t\t\t\t\t\t\t//In Hz\n\tfloat fovh;\t\t\t\t\t\t\t\t//Horizontal FOV\n\tunsigned int cols;\n\tunsigned int cols_i;\n\tunsigned int width;\n\tunsigned int ctf_levels;\n\tunsigned int image_level, level;\n\tunsigned int num_valid_range;\n    unsigned int iter_irls;\n\tfloat g_mask[5];\n\n    //mrpt::gui::CDisplayWindowPlots window;\n\tmrpt::utils::CTicTac\t\tm_clock;\n\tfloat\t\tm_runtime;\n    ros::Time last_odom_time;\n\n\tmrpt::math::CMatrixFloat31 kai_abs;\n\tmrpt::math::CMatrixFloat31 kai_loc;\n\tmrpt::math::CMatrixFloat31 kai_loc_old;\n\tmrpt::math::CMatrixFloat31 kai_loc_level;\n\n\tmrpt::poses::CPose3D laser_pose;\n\tmrpt::poses::CPose3D laser_oldpose;\n    mrpt::poses::CPose3D robot_pose;\n    mrpt::poses::CPose3D robot_oldpose;\n\tbool test;\n    std::vector<double> last_m_lin_speeds;\n    std::vector<double> last_m_ang_speeds;\n\n\n\t// Methods\n\tvoid createImagePyramid();\n\tvoid calculateCoord();\n\tvoid performWarping();\n\tvoid calculaterangeDerivativesSurface();\n\tvoid computeNormals();\t\n\tvoid computeWeights();\n\tvoid findNullPoints();\n\tvoid solveSystemOneLevel();\n    void solveSystemNonLinear();\n\tvoid filterLevelSolution();\n\tvoid PoseUpdate();\n    void Reset(mrpt::poses::CPose3D ini_pose, CObservation2DRangeScan scan);\n};\n\n#endif\n"
  },
  {
    "path": "src/rf2o_laser_odometry/launch/rf2o_laser_odometry.launch",
    "content": "<!-- \n  This node presents a fast and precise method to estimate the planar motion of a lidar\n  from consecutive range scans. It is very useful for the estimation of the robot odometry from\n  2D laser range measurements.\n  \n  For more info please visit: http://mapir.isa.uma.es/work/rf2o\n  \n  Requirements:\n  - 2D laser scan, publishing sensor_msgs::LaserScan\n  - TF transform from the laser to the robot base\n  - MRPT (http://www.mrpt.org/)\n        - Tested with v1.3 (official ubuntu release)\n-->\n\n<launch>\n\n  <node pkg=\"rf2o_laser_odometry\" type=\"rf2o_laser_odometry_node\" name=\"rf2o_laser_odometry\" output=\"screen\">\n    <param name=\"laser_scan_topic\" value=\"/laser_scan\"/>        # topic where the lidar scans are being published\n    <param name=\"odom_topic\" value=\"/odom_rf2o\" />              # topic where tu publish the odometry estimations\n    <param name=\"publish_tf\" value=\"false\" />                   # wheter or not to publish the tf::transform (base->odom)\n    <param name=\"base_frame_id\" value=\"/base_link\"/>            # frame_id (tf) of the mobile robot base. A tf transform from the laser_frame to the base_frame is mandatory\n    <param name=\"odom_frame_id\" value=\"/odom\" />                # frame_id (tf) to publish the odometry estimations    \n    <param name=\"init_pose_from_topic\" value=\"/base_pose_ground_truth\" /> # (Odom topic) Leave empty to start at point (0,0)\n    <param name=\"freq\" value=\"6.0\"/>                            # Execution frequency.\n    <param name=\"verbose\" value=\"true\" />                       # verbose\n  </node>\n  \n</launch>\n"
  },
  {
    "path": "src/rf2o_laser_odometry/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package>\n\n  <name>rf2o_laser_odometry</name>\n  <version>1.0.0</version>\n  <description>\n    Estimation of 2D odometry based on planar laser scans. Useful for mobile robots with innacurate base odometry.\n    For full description of the algorithm, please refer to:\n    Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA 2016\n    Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217\n  </description>\n\n  <maintainer email=\"jgmonroy@uma.es\">Javier G. Monroy</maintainer>\n  <author email=\"marianojt@uma.es\"> Mariano Jaimez</author>\n  <author email=\"jgmonroy@uma.es\"> Javier G. Monroy</author>\n  <license>GPL v3</license> \n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <build_depend>nav_msgs</build_depend>\n  <build_depend>roscpp</build_depend>\n  <build_depend>sensor_msgs</build_depend>\n  <build_depend>std_msgs</build_depend>\n  <build_depend>tf</build_depend>\n  <build_depend>cmake_modules</build_depend>   <!-- A common repository for CMake Modules which are not distributed with CMake but are commonly used by ROS packages. -->\n                                               <!-- https://github.com/ros/cmake_modules/blob/0.3-devel/README.md -->\n  <build_depend>mrpt</build_depend>            <!-- Depend on mrpt system pkgs: http://www.mrpt.org/ -->\n\n\n  <run_depend>nav_msgs</run_depend>\n  <run_depend>roscpp</run_depend>\n  <run_depend>sensor_msgs</run_depend>\n  <run_depend>std_msgs</run_depend>\n  <run_depend>tf</run_depend>\n  <run_depend>cmake_modules</run_depend>       <!-- For aditional dependencies such as Eigen -->\n  <run_depend>mrpt</run_depend>                <!-- Depend on mrpt system pkgs -->\n\n</package>\n"
  },
  {
    "path": "src/rf2o_laser_odometry/src/CLaserOdometry2D.cpp",
    "content": "/** ****************************************************************************************\n*  This node presents a fast and precise method to estimate the planar motion of a lidar\n*  from consecutive range scans. It is very useful for the estimation of the robot odometry from\n*  2D laser range measurements.\n*  This module is developed for mobile robots with innacurate or inexistent built-in odometry.\n*  It allows the estimation of a precise odometry with low computational cost.\n*  For more information, please refer to:\n*\n*  Planar Odometry from a Radial Laser Scanner. A Range Flow-based Approach. ICRA'16.\n*  Available at: http://mapir.isa.uma.es/mapirwebsite/index.php/mapir-downloads/papers/217\n*\n* Maintainer: Javier G. Monroy\n* MAPIR group: http://mapir.isa.uma.es/\n******************************************************************************************** */\n//#define rplidar\n#include \"rf2o_laser_odometry/CLaserOdometry2D.h\"\nusing namespace mrpt;\nusing namespace mrpt::math;\nusing namespace mrpt::utils;\nusing namespace mrpt::poses;\nusing namespace std;\nusing namespace Eigen;\n\n\n// --------------------------------------------\n// CLaserOdometry2D\n//---------------------------------------------\n\nCLaserOdometry2D::CLaserOdometry2D()\n{\t\n    ROS_INFO(\"Initializing RF2O node...\");\n\n    //Read Parameters\n    //----------------\n    ros::NodeHandle pn(\"~\");\n    pn.param<std::string>(\"laser_scan_topic\",laser_scan_topic,\"/laser_scan\");\n    pn.param<std::string>(\"base_frame_id\", base_frame_id, \"/base_link\");\n    pn.param<std::string>(\"odom_frame_id\", odom_frame_id, \"/odom\");\n    pn.param<double>(\"freq\",freq,10.0);\n\n    //Publishers and Subscribers\n    //--------------------------    \n    odom_pub = pn.advertise<nav_msgs::Odometry>(odom_frame_id, 5);\n    laser_sub = n.subscribe<sensor_msgs::LaserScan>(laser_scan_topic,1,&CLaserOdometry2D::LaserCallBack,this);\n\n    //Init variables\n    module_initialized = false;\n    first_laser_scan = true;\n}\n\n\nCLaserOdometry2D::~CLaserOdometry2D()\n{\n}\n\n\nbool CLaserOdometry2D::is_initialized()\n{\n    return module_initialized;\n}\n\nbool CLaserOdometry2D::scan_available()\n{\n    return new_scan_available;\n}\n\nvoid CLaserOdometry2D::Init()\n{\n    //Got an initial scan laser, obtain its parametes\n    ROS_INFO(\"Got first Laser Scan .... Configuring node\");\n    width = last_scan.ranges.size();    // Num of samples (size) of the scan laser\n    cols = width;\t\t\t\t\t\t// Max reolution. Should be similar to the width parameter\n    fovh = fabs(last_scan.angle_max - last_scan.angle_min); // Horizontal Laser's FOV\n    ctf_levels = 5;                     // Coarse-to-Fine levels\n    iter_irls = 5;                      //Num iterations to solve iterative reweighted least squares\n\n    //Set laser pose on the robot (through tF)\n    // This allow estimation of the odometry with respect to the robot base reference system.\n    mrpt::poses::CPose3D LaserPoseOnTheRobot;\n    tf::StampedTransform transform;\n    try\n    {\n        tf_listener.lookupTransform(\"/base_link\", last_scan.header.frame_id, ros::Time(0), transform);\n    }\n    catch (tf::TransformException &ex)\n    {\n        ROS_ERROR(\"%s\",ex.what());\n        ros::Duration(1.0).sleep();\n    }\n\n    //TF:transform -> mrpt::CPose3D (see mrpt-ros-bridge)\n    const tf::Vector3 &t = transform.getOrigin();\n    LaserPoseOnTheRobot.x() = t[0];\n    LaserPoseOnTheRobot.y() = t[1];\n    LaserPoseOnTheRobot.z() = t[2];\n    const tf::Matrix3x3 &basis = transform.getBasis();\n    mrpt::math::CMatrixDouble33 R;\n    for(int r = 0; r < 3; r++)\n        for(int c = 0; c < 3; c++)\n            R(r,c) = basis[r][c];\n    LaserPoseOnTheRobot.setRotationMatrix(R);\n\n\n    //Set the initial pose\n    laser_pose = LaserPoseOnTheRobot;\n    laser_oldpose = LaserPoseOnTheRobot;\n\n    // Init module\n    //-------------\n    range_wf.setSize(1, width);\n\n    //Resize vectors according to levels\n    transformations.resize(ctf_levels);\n    for (unsigned int i = 0; i < ctf_levels; i++)\n        transformations[i].resize(3, 3);\n\n    //Resize pyramid\n    unsigned int s, cols_i;\n    const unsigned int pyr_levels = round(log2(round(float(width) / float(cols)))) + ctf_levels;\n    range.resize(pyr_levels);\n    range_old.resize(pyr_levels);\n    range_inter.resize(pyr_levels);\n    xx.resize(pyr_levels);\n    xx_inter.resize(pyr_levels);\n    xx_old.resize(pyr_levels);\n    yy.resize(pyr_levels);\n    yy_inter.resize(pyr_levels);\n    yy_old.resize(pyr_levels);\n    range_warped.resize(pyr_levels);\n    xx_warped.resize(pyr_levels);\n    yy_warped.resize(pyr_levels);\n\n    for (unsigned int i = 0; i < pyr_levels; i++)\n    {\n        s = pow(2.f, int(i));\n        cols_i = ceil(float(width) / float(s));\n\n        range[i].resize(1, cols_i);\n        range_inter[i].resize(1, cols_i);\n        range_old[i].resize(1, cols_i);\n        range[i].assign(0.0f);\n        range_old[i].assign(0.0f);\n        xx[i].resize(1, cols_i);\n        xx_inter[i].resize(1, cols_i);\n        xx_old[i].resize(1, cols_i);\n        xx[i].assign(0.0f);\n        xx_old[i].assign(0.0f);\n        yy[i].resize(1, cols_i);\n        yy_inter[i].resize(1, cols_i);\n        yy_old[i].resize(1, cols_i);\n        yy[i].assign(0.f);\n        yy_old[i].assign(0.f);\n\n        if (cols_i <= cols)\n        {\n            range_warped[i].resize(1, cols_i);\n            xx_warped[i].resize(1, cols_i);\n            yy_warped[i].resize(1, cols_i);\n        }\n    }\n\n    dt.resize(1, cols);\n    dtita.resize(1, cols);\n    normx.resize(1, cols);\n    normy.resize(1, cols);\n    norm_ang.resize(1, cols);\n    weights.setSize(1, cols);\n    null.setSize(1, cols);\n    null.assign(0);\n    cov_odo.assign(0.f);\n\n\n    fps = 1.f;\t\t//In Hz\n    num_valid_range = 0;\n\n    //Compute gaussian mask\n    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];\n\n    kai_abs.assign(0.f);\n    kai_loc_old.assign(0.f);\n\n    module_initialized = true;\n    last_odom_time = ros::Time::now();\n}\n\n\nvoid CLaserOdometry2D::odometryCalculation()\n{\n    //==================================================================================\n    //\t\t\t\t\t\tDIFERENTIAL  ODOMETRY  MULTILEVEL\n    //==================================================================================\n\n    m_clock.Tic();\n    createImagePyramid();\n\n    //Coarse-to-fine scheme\n    for (unsigned int i=0; i<ctf_levels; i++)\n    {\n        //Previous computations\n        transformations[i].setIdentity();\n\n        level = i;\n        unsigned int s = pow(2.f,int(ctf_levels-(i+1)));\n        cols_i = ceil(float(cols)/float(s));\n        image_level = ctf_levels - i + round(log2(round(float(width)/float(cols)))) - 1;\n\n        //1. Perform warping\n        if (i == 0)\n        {\n            range_warped[image_level] = range[image_level];\n            xx_warped[image_level] = xx[image_level];\n            yy_warped[image_level] = yy[image_level];\n        }\n        else\n            performWarping();\n\n        //2. Calculate inter coords\n        calculateCoord();\n\n        //3. Find null points\n        findNullPoints();\n\n        //4. Compute derivatives\n        calculaterangeDerivativesSurface();\n\n        //5. Compute normals\n        //computeNormals();\n\n        //6. Compute weights\n        computeWeights();\n\n        //7. Solve odometry\n        if (num_valid_range > 3)\n        {\n            solveSystemNonLinear();\n            //solveSystemOneLevel();    //without robust-function\n        }\n\n        //8. Filter solution\n        filterLevelSolution();\n    }\n\n    m_runtime = 1000*m_clock.Tac();\n    ROS_INFO(\"Time odometry (ms): %f\", m_runtime);\n\n    //Update poses\n    PoseUpdate();\n    new_scan_available = false;     //avoids the possibility to run twice on the same laser scan\n}\n\n\nvoid CLaserOdometry2D::createImagePyramid()\n{\n\tconst float max_range_dif = 0.3f;\n\t\n\t//Push the frames back\n\trange_old.swap(range);\n\txx_old.swap(xx);\n\tyy_old.swap(yy);\n\n    //The number of levels of the pyramid does not match the number of levels used\n    //in the odometry computation (because we sometimes want to finish with lower resolutions)\n\n    unsigned int pyr_levels = round(log2(round(float(width)/float(cols)))) + ctf_levels;\n\n    //Generate levels\n    for (unsigned int i = 0; i<pyr_levels; i++)\n    {\n        unsigned int s = pow(2.f,int(i));\n        cols_i = ceil(float(width)/float(s));\n\t\t\n\t\tconst unsigned int i_1 = i-1;\n\n\t\t//First level -> Filter (not downsampling);\n        if (i == 0)\n\t\t{\n\t\t\tfor (unsigned int u = 0; u < cols_i; u++)\n            {\t\n\t\t\t\tconst float dcenter = range_wf(u);\n\t\t\t\t\t\n\t\t\t\t//Inner pixels\n                if ((u>1)&&(u<cols_i-2))\n                {\t\t\n\t\t\t\t\tif (dcenter > 0.f)\n\t\t\t\t\t{\t\n\t\t\t\t\t\tfloat sum = 0.f;\n\t\t\t\t\t\tfloat weight = 0.f;\n\n\t\t\t\t\t\tfor (int l=-2; l<3; l++)\n\t\t\t\t\t\t{\n\t\t\t\t\t\t\tconst float abs_dif = abs(range_wf(u+l)-dcenter);\n\t\t\t\t\t\t\tif (abs_dif < max_range_dif)\n\t\t\t\t\t\t\t{\n\t\t\t\t\t\t\t\tconst float aux_w = g_mask[2+l]*(max_range_dif - abs_dif);\n\t\t\t\t\t\t\t\tweight += aux_w;\n\t\t\t\t\t\t\t\tsum += aux_w*range_wf(u+l);\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t\trange[i](u) = sum/weight;\n\t\t\t\t\t}\n\t\t\t\t\telse\n\t\t\t\t\t\trange[i](u) = 0.f;\n\n                }\n\n                //Boundary\n                else\n                {\n                    if (dcenter > 0.f)\n\t\t\t\t\t{\t\t\t\t\t\t\n\t\t\t\t\t\tfloat sum = 0.f;\n\t\t\t\t\t\tfloat weight = 0.f;\n\n\t\t\t\t\t\tfor (int l=-2; l<3; l++)\t\n\t\t\t\t\t\t{\n\t\t\t\t\t\t\tconst int indu = u+l;\n\t\t\t\t\t\t\tif ((indu>=0)&&(indu<cols_i))\n\t\t\t\t\t\t\t{\n\t\t\t\t\t\t\t\tconst float abs_dif = abs(range_wf(indu)-dcenter);\t\t\t\t\t\t\t\t\t\t\n\t\t\t\t\t\t\t\tif (abs_dif < max_range_dif)\n\t\t\t\t\t\t\t\t{\n\t\t\t\t\t\t\t\t\tconst float aux_w = g_mask[2+l]*(max_range_dif - abs_dif);\n\t\t\t\t\t\t\t\t\tweight += aux_w;\n\t\t\t\t\t\t\t\t\tsum += aux_w*range_wf(indu);\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t\trange[i](u) = sum/weight;\n\t\t\t\t\t}\n\t\t\t\t\telse\n\t\t\t\t\t\trange[i](u) = 0.f;\n\n                }\n            }\n\t\t}\n\n        //                              Downsampling\n        //-----------------------------------------------------------------------------\n        else\n        {            \n\t\t\tfor (unsigned int u = 0; u < cols_i; u++)\n            {\n                const int u2 = 2*u;\t\t\n\t\t\t\tconst float dcenter = range[i_1](u2);\n\t\t\t\t\t\n\t\t\t\t//Inner pixels\n                if ((u>0)&&(u<cols_i-1))\n                {\t\t\n\t\t\t\t\tif (dcenter > 0.f)\n\t\t\t\t\t{\t\n\t\t\t\t\t\tfloat sum = 0.f;\n\t\t\t\t\t\tfloat weight = 0.f;\n\n\t\t\t\t\t\tfor (int l=-2; l<3; l++)\n\t\t\t\t\t\t{\n\t\t\t\t\t\t\tconst float abs_dif = abs(range[i_1](u2+l)-dcenter);\n\t\t\t\t\t\t\tif (abs_dif < max_range_dif)\n\t\t\t\t\t\t\t{\n\t\t\t\t\t\t\t\tconst float aux_w = g_mask[2+l]*(max_range_dif - abs_dif);\n\t\t\t\t\t\t\t\tweight += aux_w;\n\t\t\t\t\t\t\t\tsum += aux_w*range[i_1](u2+l);\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t\trange[i](u) = sum/weight;\n\t\t\t\t\t}\n\t\t\t\t\telse\n\t\t\t\t\t\trange[i](u) = 0.f;\n\n                }\n\n                //Boundary\n                else\n                {\n                    if (dcenter > 0.f)\n\t\t\t\t\t{\t\t\t\t\t\t\n\t\t\t\t\t\tfloat sum = 0.f;\n\t\t\t\t\t\tfloat weight = 0.f;\n\t\t\t\t\t\tconst unsigned int cols_i2 = range[i_1].cols();\n\n\n\t\t\t\t\t\tfor (int l=-2; l<3; l++)\t\n\t\t\t\t\t\t{\n\t\t\t\t\t\t\tconst int indu = u2+l;\n\t\t\t\t\t\t\tif ((indu>=0)&&(indu<cols_i2))\n\t\t\t\t\t\t\t{\n\t\t\t\t\t\t\t\tconst float abs_dif = abs(range[i_1](indu)-dcenter);\t\t\t\t\t\t\t\t\t\t\n\t\t\t\t\t\t\t\tif (abs_dif < max_range_dif)\n\t\t\t\t\t\t\t\t{\n\t\t\t\t\t\t\t\t\tconst float aux_w = g_mask[2+l]*(max_range_dif - abs_dif);\n\t\t\t\t\t\t\t\t\tweight += aux_w;\n\t\t\t\t\t\t\t\t\tsum += aux_w*range[i_1](indu);\n\t\t\t\t\t\t\t\t}\n\t\t\t\t\t\t\t}\n\t\t\t\t\t\t}\n\t\t\t\t\t\trange[i](u) = sum/weight;\n\t\t\t\t\t}\n\t\t\t\t\telse\n\t\t\t\t\t\trange[i](u) = 0.f;\n\n                }\n            }\n        }\n\n        //Calculate coordinates \"xy\" of the points\n        for (unsigned int u = 0; u < cols_i; u++) \n\t\t{\n            if (range[i](u) > 0.f)\n\t\t\t{\n\t\t\t\tconst float tita = -0.5*fovh + float(u)*fovh/float(cols_i-1);\n\t\t\t\txx[i](u) = range[i](u)*cos(tita);\n\t\t\t\tyy[i](u) = range[i](u)*sin(tita);\n\t\t\t}\n\t\t\telse\n\t\t\t{\n\t\t\t\txx[i](u) = 0.f;\n\t\t\t\tyy[i](u) = 0.f;\n\t\t\t}\n\t\t}\n    }\n}\n\n\n\nvoid CLaserOdometry2D::calculateCoord()\n{\t\t\n\tfor (unsigned int u = 0; u < cols_i; u++)\n\t{\n\t\tif ((range_old[image_level](u) == 0.f) || (range_warped[image_level](u) == 0.f))\n\t\t{\n\t\t\trange_inter[image_level](u) = 0.f;\n\t\t\txx_inter[image_level](u) = 0.f;\n\t\t\tyy_inter[image_level](u) = 0.f;\n\t\t}\n\t\telse\n\t\t{\n\t\t\trange_inter[image_level](u) = 0.5f*(range_old[image_level](u) + range_warped[image_level](u));\n\t\t\txx_inter[image_level](u) = 0.5f*(xx_old[image_level](u) + xx_warped[image_level](u));\n\t\t\tyy_inter[image_level](u) = 0.5f*(yy_old[image_level](u) + yy_warped[image_level](u));\n\t\t}\n\t}\n}\n\n\nvoid CLaserOdometry2D::calculaterangeDerivativesSurface()\n{\t\n\t//The gradient size ir reserved at the maximum size (at the constructor)\n\n    //Compute connectivity\n\trtita.resize(1,cols_i); \t\t//Defined in a different way now, without inversion\n    rtita.assign(1.f); \n\n\tfor (unsigned int u = 0; u < cols_i-1; u++)\n    {\n\t\tconst float dist = square(xx_inter[image_level](u+1) - xx_inter[image_level](u))\n\t\t\t\t\t\t\t+ square(yy_inter[image_level](u+1) - yy_inter[image_level](u));\n\t\tif (dist  > 0.f)\n\t\t\trtita(u) = sqrt(dist);\n\t}\n\n    //Spatial derivatives\n    for (unsigned int u = 1; u < cols_i-1; u++)\n\t\tdtita(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));\n\n\tdtita(0) = dtita(1);\n\tdtita(cols_i-1) = dtita(cols_i-2);\n\n\t//Temporal derivative\n\tfor (unsigned int u = 0; u < cols_i; u++)\n\t\tdt(u) = fps*(range_warped[image_level](u) - range_old[image_level](u));\n\n\n\t//Apply median filter to the range derivatives\n\t//MatrixXf dtitamed = dtita, dtmed = dt;\n\t//vector<float> svector(3);\n\t//for (unsigned int u=1; u<cols_i-1; u++)\n\t//{\n\t//\tsvector.at(0) = dtita(u-1); svector.at(1) = dtita(u); svector.at(2) = dtita(u+1);\n\t//\tstd::sort(svector.begin(), svector.end());\n\t//\tdtitamed(u) = svector.at(1);\n\n\t//\tsvector.at(0) = dt(u-1); svector.at(1) = dt(u); svector.at(2) = dt(u+1);\n\t//\tstd::sort(svector.begin(), svector.end());\n\t//\tdtmed(u) = svector.at(1);\n\t//}\n\n\t//dtitamed(0) = dtitamed(1);\n\t//dtitamed(cols_i-1) = dtitamed(cols_i-2);\n\t//dtmed(0) = dtmed(1);\n\t//dtmed(cols_i-1) = dtmed(cols_i-2);\n\n\t//dtitamed.swap(dtita);\n\t//dtmed.swap(dt);\n}\n\n\nvoid CLaserOdometry2D::computeNormals()\n{\n\tnormx.assign(0.f);\n\tnormy.assign(0.f);\n\tnorm_ang.assign(0.f);\n\n\tconst float incr_tita = fovh/float(cols_i-1);\n\tfor (unsigned int u=0; u<cols_i; u++)\n\t{\n\t\tif (null(u) == 0.f)\n\t\t{\n\t\t\tconst float tita = -0.5f*fovh + float(u)*incr_tita;\n\t\t\tconst float alfa = -atan2(2.f*dtita(u), 2.f*range[image_level](u)*incr_tita);\n\t\t\tnorm_ang(u) = tita + alfa;\n\t\t\tif (norm_ang(u) < -M_PI)\n\t\t\t\tnorm_ang(u) += 2.f*M_PI;\n\t\t\telse if (norm_ang(u) < 0.f)\n\t\t\t\tnorm_ang(u) += M_PI;\n\t\t\telse if (norm_ang(u) > M_PI)\n\t\t\t\tnorm_ang(u) -= M_PI;\n\n\t\t\tnormx(u) = cos(tita + alfa);\n\t\t\tnormy(u) = sin(tita + alfa);\n\t\t}\n\t}\n}\n\n\nvoid CLaserOdometry2D::computeWeights()\n{\n\t//The maximum weight size is reserved at the constructor\n\tweights.assign(0.f);\n\t\n\t//Parameters for error_linearization\n\tconst float kdtita = 1.f;\n\tconst float kdt = kdtita/square(fps);\n\tconst float k2d = 0.2f;\n\t\n\tfor (unsigned int u = 1; u < cols_i-1; u++)\n\t\tif (null(u) == 0)\n\t\t{\t\n\t\t\t//\t\t\t\t\t\t\tCompute derivatives\n\t\t\t//-----------------------------------------------------------------------\n\t\t\tconst float ini_dtita = range_old[image_level](u+1) - range_old[image_level](u-1);\n\t\t\tconst float final_dtita = range_warped[image_level](u+1) - range_warped[image_level](u-1);\n\n\t\t\tconst float dtitat = ini_dtita - final_dtita;\n\t\t\tconst float dtita2 = dtita(u+1) - dtita(u-1);\n\n\t\t\tconst float w_der = kdt*square(dt(u)) + kdtita*square(dtita(u)) + k2d*(abs(dtitat) + abs(dtita2));\n\n\t\t\tweights(u) = sqrt(1.f/w_der);\n\t\t}\n\n\tconst float inv_max = 1.f/weights.maximum();\n\tweights = inv_max*weights;\n}\n\n\nvoid CLaserOdometry2D::findNullPoints()\n{\n\t//Size of null matrix is set to its maximum size (constructor)\n\tnum_valid_range = 0;\n\n\tfor (unsigned int u = 1; u < cols_i-1; u++)\n\t{\n\t\tif (range_inter[image_level](u) == 0.f)\n\t\t\tnull(u) = 1;\n\t\telse\n\t\t{\n\t\t\tnum_valid_range++;\n\t\t\tnull(u) = 0;\n\t\t}\n\t}\n}\n\n\n// Solves the system without considering any robust-function\nvoid CLaserOdometry2D::solveSystemOneLevel()\n{\n\tA.resize(num_valid_range,3);\n\tB.setSize(num_valid_range,1);\n\tunsigned int cont = 0;\n\tconst float kdtita = (cols_i-1)/fovh;\n\n\t//Fill the matrix A and the vector B\n\t//The order of the variables will be (vx, vy, wz)\n\n\tfor (unsigned int u = 1; u < cols_i-1; u++)\n\t\tif (null(u) == 0)\n\t\t{\n\t\t\t// Precomputed expressions\n\t\t\tconst float tw = weights(u);\n\t\t\tconst float tita = -0.5*fovh + u/kdtita;\n\n\t\t\t//Fill the matrix A\n\t\t\tA(cont, 0) = tw*(cos(tita) + dtita(u)*kdtita*sin(tita)/range_inter[image_level](u));\n\t\t\tA(cont, 1) = tw*(sin(tita) - dtita(u)*kdtita*cos(tita)/range_inter[image_level](u));\n\t\t\tA(cont, 2) = tw*(-yy[image_level](u)*cos(tita) + xx[image_level](u)*sin(tita) - dtita(u)*kdtita);\n\t\t\tB(cont,0) = tw*(-dt(u));\n\n\t\t\tcont++;\n\t\t}\n\t\n\t//Solve the linear system of equations using a minimum least squares method\n\tMatrixXf AtA, AtB;\n\tAtA.multiply_AtA(A);\n\tAtB.multiply_AtB(A,B);\n\tVar = AtA.ldlt().solve(AtB);\n\n\t//Covariance matrix calculation \tCov Order -> vx,vy,wz\n\tMatrixXf res(num_valid_range,1);\n\tres = A*Var - B;\n\tcov_odo = (1.f/float(num_valid_range-3))*AtA.inverse()*res.squaredNorm();\n\n\tkai_loc_level = Var;\n}\n\n\n// Solves the system by considering the Cauchy M-estimatorrobust-function\nvoid CLaserOdometry2D::solveSystemNonLinear()\n{\n    A.resize(num_valid_range,3); Aw.resize(num_valid_range,3);\n    B.setSize(num_valid_range,1); Bw.setSize(num_valid_range,1);\n    unsigned int cont = 0;\n    const float kdtita = float(cols_i-1)/fovh;\n\n    //Fill the matrix A and the vector B\n    //The order of the variables will be (vx, vy, wz)\n\n    for (unsigned int u = 1; u < cols_i-1; u++)\n        if (null(u) == 0)\n        {\n            // Precomputed expressions\n            const float tw = weights(u);\n            const float tita = -0.5*fovh + u/kdtita;\n\n            //Fill the matrix A\n            A(cont, 0) = tw*(cos(tita) + dtita(u)*kdtita*sin(tita)/range_inter[image_level](u));\n            A(cont, 1) = tw*(sin(tita) - dtita(u)*kdtita*cos(tita)/range_inter[image_level](u));\n            A(cont, 2) = tw*(-yy[image_level](u)*cos(tita) + xx[image_level](u)*sin(tita) - dtita(u)*kdtita);\n            B(cont,0) = tw*(-dt(u));\n\n            cont++;\n        }\n\n    //Solve the linear system of equations using a minimum least squares method\n    MatrixXf AtA, AtB;\n    AtA.multiply_AtA(A);\n    AtB.multiply_AtB(A,B);\n    Var = AtA.ldlt().solve(AtB);\n\n    //Covariance matrix calculation \tCov Order -> vx,vy,wz\n    MatrixXf res(num_valid_range,1);\n    res = A*Var - B;\n    //cout << endl << \"max res: \" << res.maxCoeff();\n    //cout << endl << \"min res: \" << res.minCoeff();\n\n    ////Compute the energy\n    //Compute the average dt\n    float aver_dt = 0.f, aver_res = 0.f; unsigned int ind = 0;\n    for (unsigned int u = 1; u < cols_i-1; u++)\n        if (null(u) == 0)\n        {\n            aver_dt += fabsf(dt(u));\n            aver_res += fabsf(res(ind++));\n        }\n    aver_dt /= cont; aver_res /= cont;\n//    printf(\"\\n Aver dt = %f, aver res = %f\", aver_dt, aver_res);\n\n\n    const float k = 10.f/aver_dt; //200\n    //float energy = 0.f;\n    //for (unsigned int i=0; i<res.rows(); i++)\n    //\tenergy += log(1.f + square(k*res(i)));\n    //printf(\"\\n\\nEnergy(0) = %f\", energy);\n\n    //Solve iterative reweighted least squares\n    //===================================================================\n    for (unsigned int i=1; i<=iter_irls; i++)\n    {\n        cont = 0;\n\n        for (unsigned int u = 1; u < cols_i-1; u++)\n            if (null(u) == 0)\n            {\n                const float res_weight = sqrt(1.f/(1.f + square(k*res(cont))));\n\n                //Fill the matrix Aw\n                Aw(cont,0) = res_weight*A(cont,0);\n                Aw(cont,1) = res_weight*A(cont,1);\n                Aw(cont,2) = res_weight*A(cont,2);\n                Bw(cont) = res_weight*B(cont);\n                cont++;\n            }\n\n        //Solve the linear system of equations using a minimum least squares method\n        AtA.multiply_AtA(Aw);\n        AtB.multiply_AtB(Aw,Bw);\n        Var = AtA.ldlt().solve(AtB);\n        res = A*Var - B;\n\n        ////Compute the energy\n        //energy = 0.f;\n        //for (unsigned int j=0; j<res.rows(); j++)\n        //\tenergy += log(1.f + square(k*res(j)));\n        //printf(\"\\nEnergy(%d) = %f\", i, energy);\n    }\n\n    cov_odo = (1.f/float(num_valid_range-3))*AtA.inverse()*res.squaredNorm();\n    kai_loc_level = Var;\n    std::cout << endl << \"COV_ODO: \" << cov_odo  << endl;\n}\n\nvoid CLaserOdometry2D::Reset(CPose3D ini_pose, CObservation2DRangeScan scan)\n{\n\t//Set the initial pose\n\tlaser_pose = ini_pose;\n\tlaser_oldpose = ini_pose;\n\n    //readLaser(scan);\n\tcreateImagePyramid();\n    //readLaser(scan);\n\tcreateImagePyramid();\n}\n\n\nvoid CLaserOdometry2D::performWarping()\n{\n\tMatrix3f acu_trans; \n\tacu_trans.setIdentity();\n\tfor (unsigned int i=1; i<=level; i++)\n\t\tacu_trans = transformations[i-1]*acu_trans;\n\n\tMatrixXf wacu(1,cols_i);\n\twacu.assign(0.f);\n\trange_warped[image_level].assign(0.f);\n\n\tconst float cols_lim = float(cols_i-1);\n\tconst float kdtita = cols_lim/fovh;\n\n\tfor (unsigned int j = 0; j<cols_i; j++)\n\t{\t\t\t\t\n\t\tif (range[image_level](j) > 0.f)\n\t\t{\n\t\t\t//Transform point to the warped reference frame\n\t\t\tconst float x_w = acu_trans(0,0)*xx[image_level](j) + acu_trans(0,1)*yy[image_level](j) + acu_trans(0,2);\n\t\t\tconst float y_w = acu_trans(1,0)*xx[image_level](j) + acu_trans(1,1)*yy[image_level](j) + acu_trans(1,2);\n\t\t\tconst float tita_w = atan2(y_w, x_w);\n\t\t\tconst float range_w = sqrt(x_w*x_w + y_w*y_w);\n\n\t\t\t//Calculate warping\n\t\t\tconst float uwarp = kdtita*(tita_w + 0.5*fovh);\n\n\t\t\t//The warped pixel (which is not integer in general) contributes to all the surrounding ones\n\t\t\tif (( uwarp >= 0.f)&&( uwarp < cols_lim))\n\t\t\t{\n\t\t\t\tconst int uwarp_l = uwarp;\n\t\t\t\tconst int uwarp_r = uwarp_l + 1;\n\t\t\t\tconst float delta_r = float(uwarp_r) - uwarp;\n\t\t\t\tconst float delta_l = uwarp - float(uwarp_l);\n\n\t\t\t\t//Very close pixel\n\t\t\t\tif (abs(round(uwarp) - uwarp) < 0.05f)\n\t\t\t\t{\n\t\t\t\t\trange_warped[image_level](round(uwarp)) += range_w;\n\t\t\t\t\twacu(round(uwarp)) += 1.f;\n\t\t\t\t}\n\t\t\t\telse\n\t\t\t\t{\n\t\t\t\t\tconst float w_r = square(delta_l);\n\t\t\t\t\trange_warped[image_level](uwarp_r) += w_r*range_w;\n\t\t\t\t\twacu(uwarp_r) += w_r;\n\n\t\t\t\t\tconst float w_l = square(delta_r);\n\t\t\t\t\trange_warped[image_level](uwarp_l) += w_l*range_w;\n\t\t\t\t\twacu(uwarp_l) += w_l;\n\t\t\t\t}\n\t\t\t}\n\t\t}\n\t}\n\n\t//Scale the averaged range and compute coordinates\n\tfor (unsigned int u = 0; u<cols_i; u++)\n\t{\t\n\t\tif (wacu(u) > 0.f)\n\t\t{\n\t\t\tconst float tita = -0.5f*fovh + float(u)/kdtita;\n\t\t\trange_warped[image_level](u) /= wacu(u);\n\t\t\txx_warped[image_level](u) = range_warped[image_level](u)*cos(tita);\n\t\t\tyy_warped[image_level](u) = range_warped[image_level](u)*sin(tita);\n\t\t}\n\t\telse\n\t\t{\n\t\t\trange_warped[image_level](u) = 0.f;\n\t\t\txx_warped[image_level](u) = 0.f;\n\t\t\tyy_warped[image_level](u) = 0.f;\n\t\t}\n\t}\n}\n\n\n\n\n\nvoid CLaserOdometry2D::filterLevelSolution()\n{\n\t//\t\tCalculate Eigenvalues and Eigenvectors\n\t//----------------------------------------------------------\n\tSelfAdjointEigenSolver<MatrixXf> eigensolver(cov_odo);\n\tif (eigensolver.info() != Success) \n\t{ \n\t\tprintf(\"Eigensolver couldn't find a solution. Pose is not updated\");\n\t\treturn;\n\t}\n\t\n\t//First, we have to describe both the new linear and angular speeds in the \"eigenvector\" basis\n\t//-------------------------------------------------------------------------------------------------\n\tMatrix<float,3,3> Bii;\n\tMatrix<float,3,1> kai_b;\n\tBii = eigensolver.eigenvectors();\n\n\tkai_b = Bii.colPivHouseholderQr().solve(kai_loc_level);\n\n\t//Second, we have to describe both the old linear and angular speeds in the \"eigenvector\" basis too\n\t//-------------------------------------------------------------------------------------------------\n\tCMatrixFloat31 kai_loc_sub;\n\n\t//Important: we have to substract the solutions from previous levels\n\tMatrix3f acu_trans;\n\tacu_trans.setIdentity();\n\tfor (unsigned int i=0; i<level; i++)\n\t\tacu_trans = transformations[i]*acu_trans;\n\n\tkai_loc_sub(0) = -fps*acu_trans(0,2);\n\tkai_loc_sub(1) = -fps*acu_trans(1,2);\n\tif (acu_trans(0,0) > 1.f)\n\t\tkai_loc_sub(2) = 0.f;\n\telse\n\t\tkai_loc_sub(2) = -fps*acos(acu_trans(0,0))*sign(acu_trans(1,0));\n\tkai_loc_sub += kai_loc_old;\n\n\tMatrix<float,3,1> kai_b_old;\n\tkai_b_old = Bii.colPivHouseholderQr().solve(kai_loc_sub);\n\n\t//Filter speed\n\tconst float cf = 15e3f*expf(-int(level)), df = 0.05f*expf(-int(level));\n\n\tMatrix<float,3,1> kai_b_fil;\n\tfor (unsigned int i=0; i<3; i++)\n\t{\n\t\t\tkai_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);\n\t\t\t//kai_b_fil_f(i,0) = (1.f*kai_b(i,0) + 0.f*kai_b_old_f(i,0))/(1.0f + 0.f);\n\t}\n\n\t//Transform filtered speed to local reference frame and compute transformation\n\tMatrix<float,3,1> kai_loc_fil = Bii.inverse().colPivHouseholderQr().solve(kai_b_fil);\n\n\t//transformation\n\tconst float incrx = kai_loc_fil(0)/fps;\n\tconst float incry = kai_loc_fil(1)/fps;\n\tconst float rot = kai_loc_fil(2)/fps;\n\ttransformations[level](0,0) = cos(rot);\n\ttransformations[level](0,1) = -sin(rot);\n\ttransformations[level](1,0) = sin(rot);\n\ttransformations[level](1,1) = cos(rot);\n\ttransformations[level](0,2) = incrx;\n\ttransformations[level](1,2) = incry;\n}\n\n\nvoid CLaserOdometry2D::PoseUpdate()\n{\n\t//First, compute the overall transformation\n\t//---------------------------------------------------\n\tMatrix3f acu_trans;\n\tacu_trans.setIdentity();\n\tfor (unsigned int i=1; i<=ctf_levels; i++)\n\t\tacu_trans = transformations[i-1]*acu_trans;\n\n\n\t//\t\t\t\tCompute kai_loc and kai_abs\n\t//--------------------------------------------------------\n\tkai_loc(0) = fps*acu_trans(0,2);\n\tkai_loc(1) = fps*acu_trans(1,2);\n\tif (acu_trans(0,0) > 1.f)\n\t\tkai_loc(2) = 0.f;\n\telse\n\t\tkai_loc(2) = fps*acos(acu_trans(0,0))*sign(acu_trans(1,0));\n\n\t//cout << endl << \"Arc cos (incr tita): \" << kai_loc(2);\n\n\tfloat phi = laser_pose.yaw();\n\n\tkai_abs(0) = kai_loc(0)*cos(phi) - kai_loc(1)*sin(phi);\n\tkai_abs(1) = kai_loc(0)*sin(phi) + kai_loc(1)*cos(phi);\n\tkai_abs(2) = kai_loc(2);\n\n\n\t//\t\t\t\t\t\tUpdate poses\n\t//-------------------------------------------------------\n\tlaser_oldpose = laser_pose;\n\tmath::CMatrixDouble33 aux_acu = acu_trans;\n\tposes::CPose3D pose_aux_2D(acu_trans(0,2), acu_trans(1,2),0, kai_loc(2)/fps,0,0);\n    laser_pose = laser_pose + pose_aux_2D;\n    //laser_pose = laser_pose + pose_aux_2D;\n\n\n\n\t//\t\t\t\tCompute kai_loc_old\n\t//-------------------------------------------------------\n\t//phi = laser_pose.yaw();\n    phi = laser_pose.yaw() + pose_aux_2D.y();\n\tkai_loc_old(0) = kai_abs(0)*cos(phi) + kai_abs(1)*sin(phi);\n\tkai_loc_old(1) = -kai_abs(0)*sin(phi) + kai_abs(1)*cos(phi);\n\tkai_loc_old(2) = kai_abs(2);\n\n\n    ROS_INFO(\"LASERodom = [%f %f %f]\",laser_pose.x(),laser_pose.y(),laser_pose.yaw());\n\n\n    // GET ROBOT POSE from LASER POSE\n    //------------------------------  \n    mrpt::poses::CPose3D LaserPoseOnTheRobot_inv;\n    tf::StampedTransform transform;\n    try\n    {\n        tf_listener.lookupTransform(last_scan.header.frame_id, \"/base_link\", ros::Time(0), transform);\n    }\n    catch (tf::TransformException &ex)\n    {\n        ROS_ERROR(\"%s\",ex.what());\n        ros::Duration(1.0).sleep();\n    }\n\n    //TF:transform -> mrpt::CPose3D (see mrpt-ros-bridge)\n    const tf::Vector3 &t = transform.getOrigin();\n    LaserPoseOnTheRobot_inv.x() = t[0];\n    LaserPoseOnTheRobot_inv.y() = t[1];\n    LaserPoseOnTheRobot_inv.z() = t[2];\n    const tf::Matrix3x3 &basis = transform.getBasis();\n    mrpt::math::CMatrixDouble33 R;\n    for(int r = 0; r < 3; r++)\n        for(int c = 0; c < 3; c++)\n            R(r,c) = basis[r][c];\n    LaserPoseOnTheRobot_inv.setRotationMatrix(R);\n\n    //Compose Transformations\n    robot_pose = laser_pose + LaserPoseOnTheRobot_inv;\n    ROS_INFO(\"BASEodom = [%f %f %f]\",robot_pose.x(),robot_pose.y(),robot_pose.yaw());\n\n\n    // Estimate linear/angular speeds (mandatory for base_local_planner)\n    // last_scan -> the last scan received\n    // last_odom_time -> The time of the previous scan lasser used to estimate the pose\n    //-------------------------------------------------------------------------------------\n    double time_inc_sec = (last_scan.header.stamp - last_odom_time).toSec();\n    last_odom_time = last_scan.header.stamp;\n    double lin_speed = acu_trans(0,2) / time_inc_sec;\n    //double lin_speed = sqrt( square(robot_oldpose.x()-robot_pose.x()) + square(robot_oldpose.y()-robot_pose.y()) )/time_inc_sec;\n    double ang_inc = robot_pose.yaw() - robot_oldpose.yaw();\n    if (ang_inc > 3.14159)\n        ang_inc -= 2*3.14159;\n    if (ang_inc < -3.14159)\n        ang_inc += 2*3.14159;\n    double ang_speed = ang_inc/time_inc_sec;\n    robot_oldpose = robot_pose;\n\n    //filter speeds\n    /*\n    last_m_lin_speeds.push_back(lin_speed);\n    if (last_m_lin_speeds.size()>4)\n        last_m_lin_speeds.erase(last_m_lin_speeds.begin());\n    double sum = std::accumulate(last_m_lin_speeds.begin(), last_m_lin_speeds.end(), 0.0);\n    lin_speed = sum / last_m_lin_speeds.size();\n\n    last_m_ang_speeds.push_back(ang_speed);\n    if (last_m_ang_speeds.size()>4)\n        last_m_ang_speeds.erase(last_m_ang_speeds.begin());\n    double sum2 = std::accumulate(last_m_ang_speeds.begin(), last_m_ang_speeds.end(), 0.0);\n    ang_speed = sum2 / last_m_ang_speeds.size();\n    */\n\n    //first, we'll publish the odometry over tf\n    //---------------------------------------\n    geometry_msgs::TransformStamped odom_trans;\n    odom_trans.header.stamp = ros::Time::now();\n    odom_trans.header.frame_id = odom_frame_id;\n    odom_trans.child_frame_id = base_frame_id;\n    odom_trans.transform.translation.x = robot_pose.x();\n    odom_trans.transform.translation.y = robot_pose.y();\n    odom_trans.transform.translation.z = 0.0;\n    odom_trans.transform.rotation = tf::createQuaternionMsgFromYaw(robot_pose.yaw());\n    //send the transform\n    //odom_broadcaster.sendTransform(odom_trans);\n\n    //next, we'll publish the odometry message over ROS\n    //-------------------------------------------------\n    nav_msgs::Odometry odom;\n    odom.header.stamp = ros::Time::now();\n    odom.header.frame_id = odom_frame_id;\n    //set the position\n    odom.pose.pose.position.x = robot_pose.x();\n    odom.pose.pose.position.y = robot_pose.y();\n    odom.pose.pose.position.z = 0.0;\n    odom.pose.pose.orientation = tf::createQuaternionMsgFromYaw(robot_pose.yaw());\n    //set the velocity\n    odom.child_frame_id = base_frame_id;\n    #ifdef rplidar \n    \todom.twist.twist.linear.x = lin_speed;    //linear speed\n    #else\n    \todom.twist.twist.linear.x = -lin_speed;    //linear speed\n    #endif\n    odom.twist.twist.linear.y = 0.0;\n    odom.twist.twist.angular.z = ang_speed;   //angular speed\n\n\t\n    odom.pose.covariance[0] = 0.1;\n    odom.pose.covariance[7] = 0.1;\n    odom.pose.covariance[14] = 0.1;\n    odom.pose.covariance[21] = 0.0025;\n    odom.pose.covariance[28] = 0.0025;\n    odom.pose.covariance[25] = 0.0025;\n\n    odom.twist.covariance[0] = 0.25;\n    odom.twist.covariance[7] = 0.25;\n    odom.twist.covariance[14] = 0.1;\n    odom.twist.covariance[21] = 0.02;\n    odom.twist.covariance[28] = 0.02;\n    odom.twist.covariance[25] = 0.02;\n\n    /*\n    //set the pose covariance DAVID\n    odom.pose.covariance = {0.1,  0.0,  0.0,  0.0,  0.0,  0.0,\n                            0.0,  0.1,  0.0,  0.0,  0.0,  0.0,\n                            0.0,  0.0,  0.1,  0.0,  0.0,  0.0,\n                            0.0,  0.0,  0.0,  0.0025,  0.0,  0.0,\n                            0.0,  0.0,  0.0,  0.0,  0.0025,  0.0,\n                            0.0,  0.0,  0.0,  0.0,  0.0,  0.0025};\n\n    //set the twist covariance DAVID\n    odom.twist.covariance = {0.25,  0.0,  0.0,  0.0,  0.0,  0.0,\t\n                            0.0,  0.25,  0.0,  0.0,  0.0,  0.0,\n                            0.0,   0.0,  0.1,  0.0,  0.0,  0.0,\n                            0.0,   0.0,  0.0,  0.02,  0.0,  0.0,\n                            0.0,   0.0,  0.0,  0.0,  0.02,  0.0,\n                            0.0,   0.0,  0.0,  0.0,  0.0,  0.02};\n    */\n    //publish the message\n    odom_pub.publish(odom);\n}\n\n\n\n//-----------------------------------------------------------------------------------\n//                                   CALLBACKS\n//-----------------------------------------------------------------------------------\n\nvoid CLaserOdometry2D::LaserCallBack(const sensor_msgs::LaserScan::ConstPtr& new_scan)\n{\n    //Keep in memory the last received laser_scan\n    last_scan = *new_scan;\n\n    //Initialize module on first scan\n    if (first_laser_scan)\n    {\n        Init();\n        first_laser_scan = false;\n    }\n    else\n    {\n        //copy laser scan to internal variable\n        for (unsigned int i = 0; i<width; i++)\n            range_wf(i) = new_scan->ranges[i];\n        new_scan_available = true;\n    }\n}\n\n//-----------------------------------------------------------------------------------\n//                                   MAIN\n//-----------------------------------------------------------------------------------\nint main(int argc, char** argv)\n{\n    ros::init(argc, argv, \"RF2O_LaserOdom\");\n\n    CLaserOdometry2D myLaserOdom;\n\n    //Main Loop\n    //----------\n    ROS_INFO(\"initialization complete...Looping\");\n    ros::Rate loop_rate(myLaserOdom.freq);\n    while (ros::ok())\n    {\n        ros::spinOnce();        //Check for new laser scans\n        ROS_INFO(\"LOOP\");\n        if( myLaserOdom.is_initialized() && myLaserOdom.scan_available() )\n        {            \n            //Process odometry estimation\n            myLaserOdom.odometryCalculation();\n            ROS_INFO(\"odom calc\");\n        }\n        else\n        {\n            ROS_WARN(\"Waiting for laser_scans....\") ;\n        }\n\n        loop_rate.sleep();\n    }\n    return(0);\n}\n"
  },
  {
    "path": "src/robot_localization/CHANGELOG.rst",
    "content": "^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nChangelog for package robot_localization\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\n\n2.4.3 (2018-04-11)\n------------------\n* Add published accel topic to documentation\n* Adding log statements for nans in the invertable matrix\n* Fixing issue with potential seg fault\n* Contributors: Oleg Kalachev, Tom Moore, stevemacenski\n\n2.4.2 (2018-01-03)\n------------------\n* Fixing CMakeLists\n* Contributors: Tom Moore\n\n2.4.1 (2017-12-15)\n------------------\n* Fixing datum precision\n* Fixing state history reversion\n* Silencing unnecessary errors and warnings\n* Fixing critical bug with dynamic process noise covariance\n* Some trivial changes to lessen the differences to lunar\n* Fix typo in reading Mahalanobis thresholds.\n* Zero out rotation in GPS to base_link transform\n* Update xmlrpcpp includes for Indigo support\n* Removing lastUpdateTime\n* Fixing timestamps in map->odom transform\n* Simplify enabledAtStartup logic\n* Add std_srvs dependency\n* Add enabling service\n* Ensure all raw sensor input orientations are normalized even if messages are not\n* Install params directory\n* Add robot localization estimator\n* Contributors: Jacob Perron, Jacob Seibert, Jiri Hubacek, Mike Purvis, Miquel Massot, Pavlo Kolomiiets, Rein Appeldoorn, Rokus Ottervanger, Tom Moore, stevemacenski\n\n2.4.0 (2017-06-12)\n------------------\n* Updated documentation\n* Added reset_on_time_jump option\n* Added feature to optionally publish utm frame as parent in navsat_transform_node\n* Moved global callback queue reset\n* Added initial_state parameter and documentation\n* Fixed ac/deceleration gains default logic\n* Added gravity parameter\n* Added delay and throttle if tf lookup fails\n* Fixed UKF IMUTwistBasicIO test\n* Added transform_timeout parameter\n* Set gps_odom timestamp before tf2 lookuptransform\n* Removed non-portable sincos calls\n* Simplified logic to account for correlated error\n* Added dynamic process noise covariance calculation\n* Fixed catkin_package Eigen warning\n* Added optional publication of acceleration state\n* Contributors: Brian Gerkey, Enrique Fernandez, Jochen Sprickerhof, Rein Appeldoorn, Simon Gene Gottlieb, Tom Moore\n\n2.3.1 (2016-10-27)\n------------------\n* Adding gitignore\n* Adding remaining wiki pages\n* Adding config and prep pages\n* Adding navsat_transform_node documentation\n* use_odometry_yaw fix for n_t_n\n* Fixing issue with manual pose reset when history is not empty\n* Getting inverse transform when looking up robot's pose.\n* Sphinx documentation\n* Removing forward slashes from navsat_transform input topics for template launch file\n* Adding example launch and parameter files for a two-level EKF setup with navsat_transform_node\n* Adding yaml file for navsat_transform_node, and moving parameter documentation to it.\n* Updating EKF and UKF parameter templates with usage comments\n* Contributors: Tom Moore, asimay\n\n2.3.0 (2016-07-28)\n------------------\n* Fixed issues with datum usage and frame_ids\n* Fixed comment for wait_for_datum\n* Fixing issue with non-zero navsat sensor orientation offsets\n* Fixing issue with base_link->gps transform wrecking the 'true' UTM position computation\n* Using correct covariance for filtered GPS\n* Fixed unitialized odometry covariance bug\n* Added filter history and measurement queue behavior\n* Changing output timestamp to more accurately use the time stamp of the most recently-processed measurement\n* Added TcpNoDelay()\n* Added parameter to make transform publishing optional\n* Fixed differential handling for pose data so that it doesn't care about the message's frame_id\n* Updated UKF config and launch\n* Added a test case for the timestamp diagnostics\n* Added reporting of bad timestamps via diagnostics\n* Updated tests to match new method signatures\n* Added control term\n* Added smoothing capability for delayed measurements\n* Making variables in navsat_transform conform to ROS coding standards\n* Contributors: Adel Fakih, Ivor Wanders, Marc Essinger, Tobias Tueylue, Tom Moore\n\n2.2.3 (2016-04-24)\n------------------\n* Cleaning up callback data structure and callbacks and updating doxygen comments in headers\n* Removing MessageFilters\n* Removing deprecated parameters\n* Adding the ability to handle GPS offsets from the vehicle's origin\n* Cleaning up navsat_transform.h\n* Making variables in navsat_transform conform to ROS coding standards\n\n2.2.2 (2016-02-04)\n------------------\n* Updating trig functions to use sincos for efficiency\n* Updating licensing information and adding Eigen MPL-only flag\n* Added state to imu frame transformation\n* Using state orientation if imu orientation is missing\n* Manually adding second spin for odometry and IMU data that is passed to message filters\n* Reducing delay between measurement reception and filter output\n* Zero altitute in intital transform too, when zero altitude param is set\n* Fixing regression with conversion back to GPS coordinates\n* Switched cropping of orientation data in inovationSubset with mahalanobis check to prevent excluding measurements with orientations bigger/smaller than ± PI\n* Fix Jacobian for EKF.\n* Removing warning about orientation variables when only their velocities are measured\n* Checking for -1 in IMU covariances and ignoring relevant message data\n* roslint and catkin_lint applied\n* 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.\n* Contributors: Adnan Ademovic, Jit Ray Chowdhury, Philipp Tscholl, Tom Moore, ayrton04, kphil\n\n2.2.1 (2015-05-27)\n------------------\n* Fixed handling of IMU data w.r.t. differential mode and relative mode\n\n2.2.0 (2015-05-22)\n------------------\n* Added tf2-friendly tf_prefix appending\n* Corrected for IMU orientation in navsat_transform\n* Fixed issue with out-of-order measurements and pose resets\n* Nodes now assume ENU standard for yaw data\n* Removed gps_common dependency\n* Adding option to navsat_transform_node that enables the use of the heading from the odometry message instead of an IMU.\n* Changed frame_id used in setPoseCallback to be the world_frame\n* Optimized Eigen arithmetic for signficiant performance boost\n* Migrated to tf2\n* Code refactoring and reorganization\n* Removed roll and pitch from navsat_transform calculations\n* Fixed transform for IMU data to better support mounting IMUs in non-standard orientations\n* Added feature to navsat_transform_node whereby filtered odometry data can be coverted back into navsat data\n* Added a parameter to allow future dating the world_frame->base_link_frame transform.\n* Removed deprecated differential setting handler\n* Added relative mode\n* Updated and improved tests\n* Fixing source frame_id in pose data handling\n* Added initial covariance parameter\n* Fixed bug in covariance copyinh\n* Added parameters for topic queue sizes\n* Improved motion model's handling of angular velocities when robot has non-zero roll and pitch\n* Changed the way differential measurements are handled\n* Added diagnostics\n\n2.1.7 (2015-01-05)\n------------------\n* Added some checks to eliminate unnecessary callbacks\n* Updated launch file templates\n* Added measurement outlier rejection\n* Added failure callbacks for tf message filters\n* Added optional broadcast of world_frame->utm transform for navsat_transform_node\n* Bug fixes for differential mode and handling of Z acceleration in 2D mode\n\n2.1.6 (2014-11-06)\n------------------\n* Added unscented Kalman filter (UKF) localization node\n* Fixed map->odom tf calculation\n* Acceleration data from IMUs is now used in computing the state estimate\n* Added 2D mode\n\n2.1.5 (2014-10-07)\n------------------\n* Changed initial estimate error covariance to be much smaller\n* Fixed some debug output\n* Added test suite\n* Better compliance with REP-105\n* Fixed differential measurement handling\n* Implemented message filters\n* Added navsat_transform_node\n\n2.1.4 (2014-08-22)\n------------------\n* Adding utm_transform_node to install targets\n\n2.1.3 (2014-06-22)\n------------------\n* Some changes to ease GPS integration\n* Addition of differential integration of pose data\n* Some documentation cleanup\n* Added UTM transform node and launch file\n* Bug fixes\n\n2.1.2 (2014-04-11)\n------------------\n* Updated covariance correction formulation to \"Joseph form\" to improve filter stability.\n* Implemented new versioning scheme.\n\n2.1.1 (2014-04-11)\n------------------\n* Added cmake_modules dependency for Eigen support, and added include to silence boost::signals warning from tf include\n\n"
  },
  {
    "path": "src/robot_localization/CMakeLists.txt",
    "content": "cmake_minimum_required(VERSION 2.8.3)\nproject(robot_localization)\n\nfind_package(catkin REQUIRED COMPONENTS\n  diagnostic_msgs\n  diagnostic_updater\n  eigen_conversions\n  geographic_msgs\n  geometry_msgs\n  message_filters\n  message_generation\n  nav_msgs\n  roscpp\n  roslint\n  sensor_msgs\n  std_msgs\n  std_srvs\n  tf2\n  tf2_geometry_msgs\n  tf2_ros\n  xmlrpcpp)\n\nfind_package(PkgConfig REQUIRED)\npkg_check_modules(YAML_CPP yaml-cpp)\n\n# Attempt to find Eigen using its own CMake module.\n# If that fails, fall back to cmake_modules package.\nfind_package(Eigen3)\nset(EIGEN_PACKAGE EIGEN3)\nif(NOT EIGEN3_FOUND)\n  find_package(cmake_modules REQUIRED)\n  find_package(Eigen REQUIRED)\n  set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS})\n  set(EIGEN3_LIBRARIES ${EIGEN_LIBRARIES})\n  set(EIGEN_PACKAGE Eigen)\nendif()\n\nadd_definitions(-DEIGEN_NO_DEBUG -DEIGEN_MPL2_ONLY)\n\nroslint_cpp()\n\n###################################\n## catkin specific configuration ##\n###################################\nadd_service_files(\n  FILES\n    GetState.srv\n    SetDatum.srv\n    SetPose.srv\n)\n\ngenerate_messages(\n  DEPENDENCIES\n    geographic_msgs\n    geometry_msgs\n    std_msgs\n)\n\ncatkin_package(\n  INCLUDE_DIRS\n    include\n  LIBRARIES \n    ekf\n    filter_base\n    filter_utilities\n    navsat_transform\n    ros_filter\n    ros_filter_utilities\n    robot_localization_estimator\n    ros_robot_localization_listener\n    ukf\n  CATKIN_DEPENDS\n    cmake_modules\n    diagnostic_msgs\n    diagnostic_updater\n    eigen_conversions\n    geographic_msgs\n    geometry_msgs\n    message_filters\n    message_runtime\n    nav_msgs\n    roscpp\n    sensor_msgs\n    std_msgs\n    std_srvs\n    tf2\n    tf2_geometry_msgs\n    tf2_ros\n    xmlrpcpp\n  DEPENDS\n    ${EIGEN_PACKAGE}\n    YAML_CPP\n)\n\n###########\n## Build ##\n###########\n\ninclude_directories(\n  include\n  ${catkin_INCLUDE_DIRS}\n  ${EIGEN3_INCLUDE_DIRS}\n  ${YAML_CPP_INCLUDE_DIRS})\n\nlink_directories(${YAML_CPP_LIBRARY_DIRS})\n\n# Library definitions\nadd_library(filter_utilities src/filter_utilities.cpp)\nadd_library(filter_base src/filter_base.cpp)\nadd_library(ekf src/ekf.cpp)\nadd_library(ukf src/ukf.cpp)\nadd_library(robot_localization_estimator src/robot_localization_estimator.cpp)\nadd_library(ros_robot_localization_listener src/ros_robot_localization_listener.cpp)\nadd_library(ros_filter_utilities src/ros_filter_utilities.cpp)\nadd_library(ros_filter src/ros_filter.cpp)\nadd_library(navsat_transform src/navsat_transform.cpp)\n\n# Executables\nadd_executable(ekf_localization_node src/ekf_localization_node.cpp)\nadd_executable(ukf_localization_node src/ukf_localization_node.cpp)\nadd_executable(navsat_transform_node src/navsat_transform_node.cpp)\nadd_executable(robot_localization_listener_node src/robot_localization_listener_node.cpp)\n\n# Dependencies\nadd_dependencies(filter_base ${PROJECT_NAME}_gencpp)\nadd_dependencies(navsat_transform ${PROJECT_NAME}_gencpp)\nadd_dependencies(robot_localization_listener_node ${PROJECT_NAME}_gencpp)\n\n# Linking\ntarget_link_libraries(ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES})\ntarget_link_libraries(filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES})\ntarget_link_libraries(filter_base filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES})\ntarget_link_libraries(ekf filter_base ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES})\ntarget_link_libraries(ukf filter_base ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES})\ntarget_link_libraries(ros_filter ekf ukf ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES})\ntarget_link_libraries(robot_localization_estimator filter_utilities filter_base ekf ukf ${EIGEN3_LIBRARIES})\ntarget_link_libraries(ros_robot_localization_listener robot_localization_estimator ros_filter_utilities\n  ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES} ${YAML_CPP_LIBRARIES})\ntarget_link_libraries(robot_localization_listener_node ros_robot_localization_listener ${catkin_LIBRARIES})\ntarget_link_libraries(ekf_localization_node ros_filter ${catkin_LIBRARIES})\ntarget_link_libraries(ukf_localization_node ros_filter ${catkin_LIBRARIES})\ntarget_link_libraries(navsat_transform filter_utilities ros_filter_utilities ${catkin_LIBRARIES} ${EIGEN3_LIBRARIES})\ntarget_link_libraries(navsat_transform_node navsat_transform ${catkin_LIBRARIES})\n\n#############\n## Install ##\n#############\n\n## Mark executables and/or libraries for installation\ninstall(TARGETS\n  ekf\n  ekf_localization_node\n  filter_base\n  filter_utilities\n  navsat_transform\n  navsat_transform_node\n  ros_filter\n  ros_filter_utilities\n  robot_localization_estimator\n  ros_robot_localization_listener\n  robot_localization_listener_node\n  ukf\n  ukf_localization_node\n  ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}\n  RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})\n\n## Mark cpp header files for installation\ninstall(DIRECTORY include/${PROJECT_NAME}/\n  DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}\n  FILES_MATCHING PATTERN \"*.h\"\n  PATTERN \".svn\" EXCLUDE)\n\ninstall(DIRECTORY launch/\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch\n  FILES_MATCHING PATTERN \"*.launch\")\n\ninstall(DIRECTORY params/\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/params)\n\ninstall(FILES\n  LICENSE\n  DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}\n)\n\n#############\n## Testing ##\n#############\n\nif (CATKIN_ENABLE_TESTING)\n\n  # Not really necessary, but it will cause the build to fail if it's\n  # missing, rather than failing once the tests are being executed\n  find_package(rosbag REQUIRED)\n  find_package(rostest REQUIRED)\n\n  #### FILTER BASE TESTS ####\n  catkin_add_gtest(filter_base-test test/test_filter_base.cpp)\n  target_link_libraries(filter_base-test filter_base ${catkin_LIBRARIES})\n\n  # This test uses ekf_localization node for convenience.\n  add_rostest_gtest(test_filter_base_diagnostics_timestamps\n                    test/test_filter_base_diagnostics_timestamps.test\n                    test/test_filter_base_diagnostics_timestamps.cpp)\n  target_link_libraries(test_filter_base_diagnostics_timestamps ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n  add_dependencies(test_filter_base_diagnostics_timestamps ekf_localization_node)\n\n  #### EKF TESTS #####\n  add_rostest_gtest(test_ekf\n                    test/test_ekf.test\n                    test/test_ekf.cpp)\n  target_link_libraries(test_ekf ros_filter ekf ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n\n  add_rostest_gtest(test_ekf_localization_node_interfaces\n                    test/test_ekf_localization_node_interfaces.test\n                    test/test_ekf_localization_node_interfaces.cpp)\n  target_link_libraries(test_ekf_localization_node_interfaces ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  add_rostest_gtest(test_ekf_localization_node_bag1\n                    test/test_ekf_localization_node_bag1.test\n                    test/test_localization_node_bag_pose_tester.cpp)\n  target_link_libraries(test_ekf_localization_node_bag1 ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  add_rostest_gtest(test_ekf_localization_node_bag2\n                    test/test_ekf_localization_node_bag2.test\n                    test/test_localization_node_bag_pose_tester.cpp)\n  target_link_libraries(test_ekf_localization_node_bag2 ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  add_rostest_gtest(test_ekf_localization_node_bag3\n                    test/test_ekf_localization_node_bag3.test\n                    test/test_localization_node_bag_pose_tester.cpp)\n  target_link_libraries(test_ekf_localization_node_bag3 ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  #### UKF TESTS #####\n  add_rostest_gtest(test_ukf\n                    test/test_ukf.test\n                    test/test_ukf.cpp)\n  target_link_libraries(test_ukf ros_filter ukf ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  add_rostest_gtest(test_ukf_localization_node_interfaces\n                    test/test_ukf_localization_node_interfaces.test\n                    test/test_ukf_localization_node_interfaces.cpp)\n  target_link_libraries(test_ukf_localization_node_interfaces ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  add_rostest_gtest(test_ukf_localization_node_bag1\n                    test/test_ukf_localization_node_bag1.test\n                    test/test_localization_node_bag_pose_tester.cpp)\n  target_link_libraries(test_ukf_localization_node_bag1 ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  add_rostest_gtest(test_ukf_localization_node_bag2\n                    test/test_ukf_localization_node_bag2.test\n                    test/test_localization_node_bag_pose_tester.cpp)\n  target_link_libraries(test_ukf_localization_node_bag2 ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  add_rostest_gtest(test_ukf_localization_node_bag3\n                    test/test_ukf_localization_node_bag3.test\n                    test/test_localization_node_bag_pose_tester.cpp)\n  target_link_libraries(test_ukf_localization_node_bag3 ${catkin_LIBRARIES} ${rostest_LIBRARIES})\n\n  #### RLE/RLL TESTS #####\n  add_rostest_gtest(test_robot_localization_estimator\n                    test/test_robot_localization_estimator.test\n                    test/test_robot_localization_estimator.cpp)\n  target_link_libraries(test_robot_localization_estimator\n                        robot_localization_estimator\n                        ${catkin_LIBRARIES}\n                        ${rostest_LIBRARIES})\n\n  add_executable(test_ros_robot_localization_listener_publisher test/test_ros_robot_localization_listener_publisher.cpp)\n  target_link_libraries(test_ros_robot_localization_listener_publisher\n                        ${catkin_LIBRARIES})\n\n  add_rostest_gtest(test_ros_robot_localization_listener\n                    test/test_ros_robot_localization_listener.test\n                    test/test_ros_robot_localization_listener.cpp)\n  target_link_libraries(test_ros_robot_localization_listener\n                        ros_robot_localization_listener\n                        ${catkin_LIBRARIES}\n                        ${rostest_LIBRARIES})\n\nendif()\n"
  },
  {
    "path": "src/robot_localization/LICENSE",
    "content": "All code within the robot_localization package that was developed by Charles\nRiver Analytics is released under the BSD license:\n\nCopyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\nAll rights reserved.\n\nRedistribution and use in source and binary forms, with or without\nmodification, are permitted provided that the following conditions are met:\n\n* Redistributions of source code must retain the above copyright notice, this\n  list of conditions and the following disclaimer.\n\n* Redistributions in binary form must reproduce the above copyright notice,\n  this list of conditions and the following disclaimer in the documentation\n  and/or other materials provided with the distribution.\n\n* Neither the name of the {organization} nor the names of its\n  contributors may be used to endorse or promote products derived from\n  this software without specific prior written permission.\n\nTHIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\nAND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\nIMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\nDISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE\nFOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\nDAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR\nSERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\nCAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,\nOR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\nOF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n==========================================================================\n\nThe robot_localization package also makes use of code written by The University\nof Texas at Austin. This code is released under a modified BSD license:\n\nCopyright (C) 2010 Austin Robot Technology, and others\nAll rights reserved.\n\nRedistribution and use in source and binary forms, with or without\nmodification, are permitted provided that the following conditions\nare met:\n\n* Redistributions of source code must retain the above copyright\n  notice, this list of conditions and the following disclaimer.\n\n* Redistributions in binary form must reproduce the above\n  copyright notice, this list of conditions and the following\n  disclaimer in the documentation and/or other materials provided\n  with the distribution.\n\n* Neither the names of the University of Texas at Austin, nor\n  Austin Robot Technology, nor the names of other contributors may\n  be used to endorse or promote products derived from this\n  software without specific prior written permission.\n\nTHIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n\"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\nLIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\nFOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\nCOPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\nINCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\nBUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\nLOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\nCAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\nLIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\nANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\nPOSSIBILITY OF SUCH DAMAGE.\n"
  },
  {
    "path": "src/robot_localization/README.md",
    "content": "robot_localization\n==================\n\nrobot_localization is a package of nonlinear state estimation nodes. The package was developed by Charles River Analytics, Inc.\n\nPlease see documentation here: http://wiki.ros.org/robot_localization\n"
  },
  {
    "path": "src/robot_localization/doc/.templates/full_globaltoc.html",
    "content": "<h3><a href=\"{{ pathto(master_doc) }}\">{{ _('Table Of Contents') }}</a></h3>\n{{ toctree(includehidden=True) }}\n\n<h3><a href=\"{{ pathto(master_doc) }}\">{{ _('Further Documentation') }}</a></h3>\n<ul>\n  <li class=\"toctree-l1\"><a href=\"api/index.html\"/>API Documentation</a></li>\n  <li class=\"toctree-l1\"><a href=\"https://github.com/cra-ros-pkg/robot_localization.git\"/>GitHub Repository</a></li>\n</ul>\n\n\n"
  },
  {
    "path": "src/robot_localization/doc/Makefile",
    "content": "# Makefile for Sphinx documentation\n#\n\n# You can set these variables from the command line.\nSPHINXOPTS    =\nSPHINXBUILD   = sphinx-build\nPAPER         =\nBUILDDIR      = .build\n\n# User-friendly check for sphinx-build\nifeq ($(shell which $(SPHINXBUILD) >/dev/null 2>&1; echo $$?), 1)\n$(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/)\nendif\n\n# Internal variables.\nPAPEROPT_a4     = -D latex_paper_size=a4\nPAPEROPT_letter = -D latex_paper_size=letter\nALLSPHINXOPTS   = -d $(BUILDDIR)/doctrees $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) .\n# the i18n builder cannot share the environment and doctrees with the others\nI18NSPHINXOPTS  = $(PAPEROPT_$(PAPER)) $(SPHINXOPTS) .\n\n.PHONY: help\nhelp:\n\t@echo \"Please use \\`make <target>' where <target> is one of\"\n\t@echo \"  html       to make standalone HTML files\"\n\t@echo \"  dirhtml    to make HTML files named index.html in directories\"\n\t@echo \"  singlehtml to make a single large HTML file\"\n\t@echo \"  pickle     to make pickle files\"\n\t@echo \"  json       to make JSON files\"\n\t@echo \"  htmlhelp   to make HTML files and a HTML help project\"\n\t@echo \"  qthelp     to make HTML files and a qthelp project\"\n\t@echo \"  applehelp  to make an Apple Help Book\"\n\t@echo \"  devhelp    to make HTML files and a Devhelp project\"\n\t@echo \"  epub       to make an epub\"\n\t@echo \"  latex      to make LaTeX files, you can set PAPER=a4 or PAPER=letter\"\n\t@echo \"  latexpdf   to make LaTeX files and run them through pdflatex\"\n\t@echo \"  latexpdfja to make LaTeX files and run them through platex/dvipdfmx\"\n\t@echo \"  text       to make text files\"\n\t@echo \"  man        to make manual pages\"\n\t@echo \"  texinfo    to make Texinfo files\"\n\t@echo \"  info       to make Texinfo files and run them through makeinfo\"\n\t@echo \"  gettext    to make PO message catalogs\"\n\t@echo \"  changes    to make an overview of all changed/added/deprecated items\"\n\t@echo \"  xml        to make Docutils-native XML files\"\n\t@echo \"  pseudoxml  to make pseudoxml-XML files for display purposes\"\n\t@echo \"  linkcheck  to check all external links for integrity\"\n\t@echo \"  doctest    to run all doctests embedded in the documentation (if enabled)\"\n\t@echo \"  coverage   to run coverage check of the documentation (if enabled)\"\n\n.PHONY: clean\nclean:\n\trm -rf $(BUILDDIR)/*\n\n.PHONY: html\nhtml:\n\t$(SPHINXBUILD) -b html $(ALLSPHINXOPTS) $(BUILDDIR)/html\n\t@echo\n\t@echo \"Build finished. The HTML pages are in $(BUILDDIR)/html.\"\n\n.PHONY: dirhtml\ndirhtml:\n\t$(SPHINXBUILD) -b dirhtml $(ALLSPHINXOPTS) $(BUILDDIR)/dirhtml\n\t@echo\n\t@echo \"Build finished. The HTML pages are in $(BUILDDIR)/dirhtml.\"\n\n.PHONY: singlehtml\nsinglehtml:\n\t$(SPHINXBUILD) -b singlehtml $(ALLSPHINXOPTS) $(BUILDDIR)/singlehtml\n\t@echo\n\t@echo \"Build finished. The HTML page is in $(BUILDDIR)/singlehtml.\"\n\n.PHONY: pickle\npickle:\n\t$(SPHINXBUILD) -b pickle $(ALLSPHINXOPTS) $(BUILDDIR)/pickle\n\t@echo\n\t@echo \"Build finished; now you can process the pickle files.\"\n\n.PHONY: json\njson:\n\t$(SPHINXBUILD) -b json $(ALLSPHINXOPTS) $(BUILDDIR)/json\n\t@echo\n\t@echo \"Build finished; now you can process the JSON files.\"\n\n.PHONY: htmlhelp\nhtmlhelp:\n\t$(SPHINXBUILD) -b htmlhelp $(ALLSPHINXOPTS) $(BUILDDIR)/htmlhelp\n\t@echo\n\t@echo \"Build finished; now you can run HTML Help Workshop with the\" \\\n\t      \".hhp project file in $(BUILDDIR)/htmlhelp.\"\n\n.PHONY: qthelp\nqthelp:\n\t$(SPHINXBUILD) -b qthelp $(ALLSPHINXOPTS) $(BUILDDIR)/qthelp\n\t@echo\n\t@echo \"Build finished; now you can run \"qcollectiongenerator\" with the\" \\\n\t      \".qhcp project file in $(BUILDDIR)/qthelp, like this:\"\n\t@echo \"# qcollectiongenerator $(BUILDDIR)/qthelp/robot_localization.qhcp\"\n\t@echo \"To view the help file:\"\n\t@echo \"# assistant -collectionFile $(BUILDDIR)/qthelp/robot_localization.qhc\"\n\n.PHONY: applehelp\napplehelp:\n\t$(SPHINXBUILD) -b applehelp $(ALLSPHINXOPTS) $(BUILDDIR)/applehelp\n\t@echo\n\t@echo \"Build finished. The help book is in $(BUILDDIR)/applehelp.\"\n\t@echo \"N.B. You won't be able to view it unless you put it in\" \\\n\t      \"~/Library/Documentation/Help or install it in your application\" \\\n\t      \"bundle.\"\n\n.PHONY: devhelp\ndevhelp:\n\t$(SPHINXBUILD) -b devhelp $(ALLSPHINXOPTS) $(BUILDDIR)/devhelp\n\t@echo\n\t@echo \"Build finished.\"\n\t@echo \"To view the help file:\"\n\t@echo \"# mkdir -p $$HOME/.local/share/devhelp/robot_localization\"\n\t@echo \"# ln -s $(BUILDDIR)/devhelp $$HOME/.local/share/devhelp/robot_localization\"\n\t@echo \"# devhelp\"\n\n.PHONY: epub\nepub:\n\t$(SPHINXBUILD) -b epub $(ALLSPHINXOPTS) $(BUILDDIR)/epub\n\t@echo\n\t@echo \"Build finished. The epub file is in $(BUILDDIR)/epub.\"\n\n.PHONY: latex\nlatex:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo\n\t@echo \"Build finished; the LaTeX files are in $(BUILDDIR)/latex.\"\n\t@echo \"Run \\`make' in that directory to run these through (pdf)latex\" \\\n\t      \"(use \\`make latexpdf' here to do that automatically).\"\n\n.PHONY: latexpdf\nlatexpdf:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo \"Running LaTeX files through pdflatex...\"\n\t$(MAKE) -C $(BUILDDIR)/latex all-pdf\n\t@echo \"pdflatex finished; the PDF files are in $(BUILDDIR)/latex.\"\n\n.PHONY: latexpdfja\nlatexpdfja:\n\t$(SPHINXBUILD) -b latex $(ALLSPHINXOPTS) $(BUILDDIR)/latex\n\t@echo \"Running LaTeX files through platex and dvipdfmx...\"\n\t$(MAKE) -C $(BUILDDIR)/latex all-pdf-ja\n\t@echo \"pdflatex finished; the PDF files are in $(BUILDDIR)/latex.\"\n\n.PHONY: text\ntext:\n\t$(SPHINXBUILD) -b text $(ALLSPHINXOPTS) $(BUILDDIR)/text\n\t@echo\n\t@echo \"Build finished. The text files are in $(BUILDDIR)/text.\"\n\n.PHONY: man\nman:\n\t$(SPHINXBUILD) -b man $(ALLSPHINXOPTS) $(BUILDDIR)/man\n\t@echo\n\t@echo \"Build finished. The manual pages are in $(BUILDDIR)/man.\"\n\n.PHONY: texinfo\ntexinfo:\n\t$(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo\n\t@echo\n\t@echo \"Build finished. The Texinfo files are in $(BUILDDIR)/texinfo.\"\n\t@echo \"Run \\`make' in that directory to run these through makeinfo\" \\\n\t      \"(use \\`make info' here to do that automatically).\"\n\n.PHONY: info\ninfo:\n\t$(SPHINXBUILD) -b texinfo $(ALLSPHINXOPTS) $(BUILDDIR)/texinfo\n\t@echo \"Running Texinfo files through makeinfo...\"\n\tmake -C $(BUILDDIR)/texinfo info\n\t@echo \"makeinfo finished; the Info files are in $(BUILDDIR)/texinfo.\"\n\n.PHONY: gettext\ngettext:\n\t$(SPHINXBUILD) -b gettext $(I18NSPHINXOPTS) $(BUILDDIR)/locale\n\t@echo\n\t@echo \"Build finished. The message catalogs are in $(BUILDDIR)/locale.\"\n\n.PHONY: changes\nchanges:\n\t$(SPHINXBUILD) -b changes $(ALLSPHINXOPTS) $(BUILDDIR)/changes\n\t@echo\n\t@echo \"The overview file is in $(BUILDDIR)/changes.\"\n\n.PHONY: linkcheck\nlinkcheck:\n\t$(SPHINXBUILD) -b linkcheck $(ALLSPHINXOPTS) $(BUILDDIR)/linkcheck\n\t@echo\n\t@echo \"Link check complete; look for any errors in the above output \" \\\n\t      \"or in $(BUILDDIR)/linkcheck/output.txt.\"\n\n.PHONY: doctest\ndoctest:\n\t$(SPHINXBUILD) -b doctest $(ALLSPHINXOPTS) $(BUILDDIR)/doctest\n\t@echo \"Testing of doctests in the sources finished, look at the \" \\\n\t      \"results in $(BUILDDIR)/doctest/output.txt.\"\n\n.PHONY: coverage\ncoverage:\n\t$(SPHINXBUILD) -b coverage $(ALLSPHINXOPTS) $(BUILDDIR)/coverage\n\t@echo \"Testing of coverage in the sources finished, look at the \" \\\n\t      \"results in $(BUILDDIR)/coverage/python.txt.\"\n\n.PHONY: xml\nxml:\n\t$(SPHINXBUILD) -b xml $(ALLSPHINXOPTS) $(BUILDDIR)/xml\n\t@echo\n\t@echo \"Build finished. The XML files are in $(BUILDDIR)/xml.\"\n\n.PHONY: pseudoxml\npseudoxml:\n\t$(SPHINXBUILD) -b pseudoxml $(ALLSPHINXOPTS) $(BUILDDIR)/pseudoxml\n\t@echo\n\t@echo \"Build finished. The pseudo-XML files are in $(BUILDDIR)/pseudoxml.\"\n"
  },
  {
    "path": "src/robot_localization/doc/conf.py",
    "content": "import sys\nimport os\n\nimport catkin_pkg.package\ncatkin_dir = os.path.dirname(os.path.dirname(os.path.abspath(__file__)))\ncatkin_package = catkin_pkg.package.parse_package(os.path.join(catkin_dir, catkin_pkg.package.PACKAGE_MANIFEST_FILENAME))\n\nextensions = [\n    'sphinx.ext.autodoc',\n    'sphinx.ext.doctest',\n    'sphinx.ext.intersphinx',\n    'sphinx.ext.todo',\n    'sphinx.ext.coverage',\n    'sphinx.ext.mathjax',\n]\n\ntemplates_path = ['.templates']\nsource_suffix = '.rst'\nmaster_doc = 'index'\n\nproject = u'robot_localization'\ncopyright = u'2016, Tom Moore'\nauthor = u'Tom Moore'\nversion = catkin_package.version\nrelease = catkin_package.version\n\nlanguage = None\nexclude_patterns = ['.build']\npygments_style = 'sphinx'\ntodo_include_todos = True\n\nhtml_theme = 'nature'\n\nhtml_theme_options = {\n  \"sidebarwidth\": \"350\"\n}\n\n# The name of an image file (relative to this directory) to place at the top\n# of the sidebar.\nhtml_logo = 'images/rl_small.png'\n\n# The name of an image file (relative to this directory) to use as a favicon of\n# the docs.  This file should be a Windows icon file (.ico) being 16x16 or 32x32\n# pixels large.\n#html_favicon = None\n\n# Add any paths that contain custom static files (such as style sheets) here,\n# relative to this directory. They are copied after the builtin static files,\n# so a file named \"default.css\" will overwrite the builtin \"default.css\".\n#html_static_path = ['.static']\n\n# Add any extra paths that contain custom files (such as robots.txt or\n# .htaccess) here, relative to this directory. These files are copied\n# directly to the root of the documentation.\n#html_extra_path = []\n\n# If not '', a 'Last updated on:' timestamp is inserted at every page bottom,\n# using the given strftime format.\n#html_last_updated_fmt = '%b %d, %Y'\n\n# If true, SmartyPants will be used to convert quotes and dashes to\n# typographically correct entities.\n#html_use_smartypants = True\n\n# Custom sidebar templates, maps document names to template names.\nhtml_sidebars = { '**': ['full_globaltoc.html', 'sourcelink.html', 'searchbox.html'], }\n\n# Additional templates that should be rendered to pages, maps page names to\n# template names.\n#html_additional_pages = {}\n\n# If false, no module index is generated.\n#html_domain_indices = True\n\n# If false, no index is generated.\n#html_use_index = True\n\n# If true, the index is split into individual pages for each letter.\n#html_split_index = False\n\n# If true, links to the reST sources are added to the pages.\n#html_show_sourcelink = True\n\n# If true, \"Created using Sphinx\" is shown in the HTML footer. Default is True.\n#html_show_sphinx = True\n\n# If true, \"(C) Copyright ...\" is shown in the HTML footer. Default is True.\n#html_show_copyright = True\n\n# If true, an OpenSearch description file will be output, and all pages will\n# contain a <link> tag referring to it.  The value of this option must be the\n# base URL from which the finished HTML is served.\n#html_use_opensearch = ''\n\n# This is the file name suffix for HTML files (e.g. \".xhtml\").\n#html_file_suffix = None\n\n# Language to be used for generating the HTML full-text search index.\n# Sphinx supports the following languages:\n#   'da', 'de', 'en', 'es', 'fi', 'fr', 'hu', 'it', 'ja'\n#   'nl', 'no', 'pt', 'ro', 'ru', 'sv', 'tr'\n#html_search_language = 'en'\n\n# A dictionary with options for the search language support, empty by default.\n# Now only 'ja' uses this config value\n#html_search_options = {'type': 'default'}\n\n# The name of a javascript file (relative to the configuration directory) that\n# implements a search results scorer. If empty, the default will be used.\n#html_search_scorer = 'scorer.js'\n\n# Output file base name for HTML help builder.\nhtmlhelp_basename = 'robot_localizationdoc'\n\n# -- Options for LaTeX output ---------------------------------------------\n\nlatex_elements = {\n# The paper size ('letterpaper' or 'a4paper').\n#'papersize': 'letterpaper',\n\n# The font size ('10pt', '11pt' or '12pt').\n#'pointsize': '10pt',\n\n# Additional stuff for the LaTeX preamble.\n#'preamble': '',\n\n# Latex figure (float) alignment\n#'figure_align': 'htbp',\n}\n\n# Grouping the document tree into LaTeX files. List of tuples\n# (source start file, target name, title,\n#  author, documentclass [howto, manual, or own class]).\nlatex_documents = [\n    (master_doc, 'robot_localization.tex', u'robot\\\\_localization Documentation',\n     u'Tom Moore', 'manual'),\n]\n\n# The name of an image file (relative to this directory) to place at the top of\n# the title page.\n#latex_logo = None\n\n# For \"manual\" documents, if this is true, then toplevel headings are parts,\n# not chapters.\n#latex_use_parts = False\n\n# If true, show page references after internal links.\n#latex_show_pagerefs = False\n\n# If true, show URL addresses after external links.\n#latex_show_urls = False\n\n# Documents to append as an appendix to all manuals.\n#latex_appendices = []\n\n# If false, no module index is generated.\n#latex_domain_indices = True\n\n\n# -- Options for manual page output ---------------------------------------\n\n# One entry per manual page. List of tuples\n# (source start file, name, description, authors, manual section).\nman_pages = [\n    (master_doc, 'robot_localization', u'robot_localization Documentation',\n     [author], 1)\n]\n\n# If true, show URL addresses after external links.\n#man_show_urls = False\n\n\n# -- Options for Texinfo output -------------------------------------------\n\n# Grouping the document tree into Texinfo files. List of tuples\n# (source start file, target name, title, author,\n#  dir menu entry, description, category)\ntexinfo_documents = [\n    (master_doc, 'robot_localization', u'robot_localization Documentation',\n     author, 'robot_localization', 'One line description of project.',\n     'Miscellaneous'),\n]\n\n# Documents to append as an appendix to all manuals.\n#texinfo_appendices = []\n\n# If false, no module index is generated.\n#texinfo_domain_indices = True\n\n# How to display URL addresses: 'footnote', 'no', or 'inline'.\n#texinfo_show_urls = 'footnote'\n\n# If true, do not generate a @detailmenu in the \"Top\" node's menu.\n#texinfo_no_detailmenu = False\n\n# Example configuration for intersphinx: refer to the Python standard library.\nintersphinx_mapping = {'https://docs.python.org/': None}\n"
  },
  {
    "path": "src/robot_localization/doc/configuring_robot_localization.rst",
    "content": ".. _configuring_robot_localization:\n\nConfiguring robot_localization\n##############################\n\n\nWhen 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.\n\nFor additional information, users are encouraged to watch this `presentation <https://vimeo.com/142624091>`_ from ROSCon 2015.\n\nSensor Configuration\n********************\n\nThe 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 <<MsgLink(geometry_msgs/TwistWithCovarianceStamped)>> lacks any pose data, but the configuration vector still has values for pose variables). Unused variables are simply ignored.\n\nNote 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 <http://docs.ros.org/api/geometry_msgs/html/msg/TwistWithCovarianceStamped.html>`_ 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:\n\n.. code-block:: xml\n\n <rosparam param=\"twist0_config\">[false, false, false,\n                                  false, false, false,\n                                  true,  false, false,\n                                  false, false, false,\n                                  false, false, false]</rosparam>\n\n.. 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})`.\n\nOperating in 2D?\n****************\n\nThe 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.\n\nFusing Unmeasured Variables\n***************************\n\nLet'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 <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ 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 <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ 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:\n\n.. code-block:: xml\n\n <rosparam param=\"odom0_config\">[true, true, false,\n                                 false, false, true,\n                                 true, false, false,\n                                 false, false, true,\n                                 false, false, false]</rosparam>\n\n <rosparam param=\"imu0_config\">[false, false, false,\n                                false, false, true,\n                                false, false, false,\n                                false, false, true,\n                                true, false, false]</rosparam>\n\nAs 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.\n\n1. 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:\n\n.. code-block:: xml\n\n <rosparam param=\"odom0_config\">[false, false, false,\n                                 false, false, false,\n                                 true, false, false,\n                                 false, false, true,\n                                 false, false, false]</rosparam>\n\n <rosparam param=\"imu0_config\">[false, false, false,\n                                false, false, true,\n                                false, false, false,\n                                false, false, true,\n                                true, false, false]</rosparam>\n\n2. 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 <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ 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:\n\n.. code-block:: xml\n\n <rosparam param=\"odom0_config\">[false, false, false,\n                                 false, false, false,\n                                 true, true, false,\n                                 false, false, true,\n                                 false, false, false]</rosparam>\n\n <rosparam param=\"imu0_config\">[false, false, false,\n                                false, false, true,\n                                false, false, false,\n                                false, false, true,\n                                true, false, false]</rosparam>\n\nYou 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.\n\n3. 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.\n\nThe *differential* and *relative* Parameters\n********************************************\n\nThe 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:\n\n1. Fuse all the absolute position/orientation data as-is, e.g.,\n\n.. code-block:: xml\n\n <rosparam param=\"imu0_config\">[false, false, false,\n                                true,  true,  true,\n                                false, false, false,\n                                false, false, false,\n                                false, false, false]</rosparam>\n\n <rosparam param=\"imu1_config\">[false, false, false,\n                                true,  true,  true,\n                                false, false, false,\n                                false, false, false,\n                                false, false, false]</rosparam>\n\n 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.\n\n2. 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.\n\nThe 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.\n\n\n"
  },
  {
    "path": "src/robot_localization/doc/index.rst",
    "content": ".. _index:\n\nrobot_localization wiki\n***********************\n\n``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.\n\n.. toctree::\n   :hidden:\n\n   state_estimation_nodes\n   navsat_transform_node\n   preparing_sensor_data\n   configuring_robot_localization\n   migrating_from_robot_pose_ekf\n   integrating_gps\n   CHANGELOG\n\nFeatures\n========\n\nAll the state estimation nodes in ``robot_localization`` share common features, namely:\n\n* 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.\n* Support for multiple ROS message types. All state estimation nodes in ``robot_localization`` can take in `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_, `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_, `geometry_msgs/PoseWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html>`_, or `geometry_msgs/TwistWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/TwistWithCovarianceStamped.html>`_ messages.\n* 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.\n* 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.\n\nAll 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})`.\n\nOther Resources\n===============\n\nIf you're new to ``robot_localization``, check out the `2015 ROSCon talk <https://vimeo.com/142624091>`_ for some pointers on getting started.\n\nFurther details can be found in :download:`this paper <robot_localization_ias13_revised.pdf>`:\n\n.. code-block:: none\n\n  @inproceedings{MooreStouchKeneralizedEkf2014,\n    author    = {T. Moore and D. Stouch},\n    title     = {A Generalized Extended Kalman Filter Implementation for the Robot Operating System},\n    year      = {2014},\n    month     = {July},\n    booktitle = {Proceedings of the 13th International Conference on Intelligent Autonomous Systems (IAS-13)},\n    publisher = {Springer}\n  }\n\nIndices and tables\n==================\n\n* :ref:`genindex`\n* :ref:`search`\n\n"
  },
  {
    "path": "src/robot_localization/doc/integrating_gps.rst",
    "content": "Integrating GPS Data\n####################\n\nIntegration 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.\n\nFor additional information, users are encouraged to watch this `presentation <https://vimeo.com/142624091>`_ from ROSCon 2015.\n\nNotes on Fusing GPS Data\n************************\n\nBefore beginning this tutorial, users should be sure to familiarize themselves with `REP-105 <http://www.ros.org/reps/rep-0105.html>`_. 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:\n\n1. 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.\n2. 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. \n\nThis 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. \n\nUsing navsat_transform_node\n***************************\n\nRequired Inputs\n===============\n\n``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). \n\nThese data can be obtained in three different ways:\n\n1. (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:\n\n * A `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message with raw GPS coordinates in it.\n * A `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message with an absolute (earth-referenced) heading.\n * A `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ 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).\n\n2. The datum (global frame origin) can be specified via the ``datum`` parameter. \n\n .. note:: In order to use this mode, the ``wait_for_datum`` parameter must be set to *true*.\n\n The ``datum`` parameter takes this form:\n\n .. code-block:: xml\n\n  <rosparam param=\"datum\">[55.944904, -3.186693, 0.0, map, base_link]</rosparam>\n\n 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). \n\n3. The datum can be set manually via the ``set_datum`` service and using the `robot_localization/SetDatum <http://docs.ros.org/api/robot_localization/html/srv/SetDatum.html>`_ service message. \n\n\nGPS Data\n^^^^^^^^\n\nPlease 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. \n\nThe excellent `nmea_navsat_driver <http://wiki.ros.org/nmea_navsat_driver>`_ package provides the required `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message. Here is the ``nmea_navsat_driver`` launch file we'll use for this tutorial:\n\n .. code-block:: xml\n\n  <node pkg=\"nmea_navsat_driver\" type=\"nmea_serial_driver\" name=\"navsat\" respawn=\"true\">\n    <param name=\"port\" value=\"/dev/ttyUSB0\"/>\n    <param name=\"baud\" value=\"19200\"/>\n  </node>\n\nThis information is only relevant if the user is not manually specifying the origin via the ``datum`` parameter or the ``set_datum`` service.\n\nIMU Data\n^^^^^^^^\n\n.. 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`).\n\nUsers should make sure their IMUs conform to `REP-105 <http://www.ros.org/reps/rep-0105.html>`_. In particular, check that the signs of your orientation angles increase in the right direction. In addition, users should look up the `magnetic declination <http://www.ngdc.noaa.gov/geomag-web/#declination>`_ for their robot's operating area, convert it to radians, and then use that value for the ``magnetic_declination_radians`` parameter.\n\nThis information is only relevant if the user is not manually specifying the origin via the ``datum`` parameter or the ``set_datum`` service.\n\nOdometry Data\n^^^^^^^^^^^^^\n\nThis should just be the output of whichever ``robot_localization`` state estimation node instance you are using to fuse GPS data.\n\nConfiguring navsat_transform_node\n=================================\n\nBelow is the ``navsat_transform_node`` launch file we'll use for this tutorial:\n\n.. code-block:: xml\n\n <launch>\n\n   <node pkg=\"robot_localization\" type=\"navsat_transform_node\" name=\"navsat_transform_node\" respawn=\"true\">\n\n     <param name=\"magnetic_declination_radians\" value=\"0\"/>\n\n     <param name=\"yaw_offset\" value=\"0\"/>\n\n     <remap from=\"/imu/data\" to=\"/your/imu/topic\" />\n     <remap from=\"/gps/fix\" to=\"/your/gps/fix/topic\" />\n     <remap from=\"/odometry/filtered\" to=\"/your/robot_localization/output/topic\" />\n\n   </node>\n\n </launch>\n\nThese parameters are discussed on the :ref:`main page <index>`.\n\nConfiguring robot_localization\n==============================\n\nIntegration with ``robot_localization`` is straightforward at this point. Simply add this block to your state estimation node launch file:\n\n.. code-block:: xml\n\n <param name=\"odomN\" value=\"/your_state_estimation_node_topic\">\n\n <rosparam param=\"odomN_config\">[true,  true,  false, \n                                 false, false, false, \n                                 false, false, false, \n                                 false, false, false,\n                                 false, false, false]</rosparam>\n <param name=\"odomN_differential\" value=\"false\"/>\n\nMake 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``.\n\n.. note:: If you are operating in 2D don't have any sensor measuring Z or Z velocity, you can either:\n\n * Set ``navsat_transform_node's`` ``zero_altitude`` parameter to *true*, and then set ``odomN_config``'s third value to *true*\n * Set ``two_d_mode`` to *true* in your ``robot_localization`` state estimation node\n\nYou 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.\n\nDetails\n=======\n\nWe'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:\n\n.. image:: images/figure1.png\n  :width: 800px\n  :align: center\n  :alt: Figure 1\n\n\n`REP-105 <http://www.ros.org/reps/rep-0105.html>`_ 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.\n\nReferring 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`.\n\nWe 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 <http://www.ros.org/reps/rep-0105.html>`_. 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: \n\n1. The IMU driver may not allow the user to apply the magnetic declination correction factor\n2. 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``, \n\n :math:`yaw_{imu} = -\\omega - offset_{yaw} + \\theta`\n\n :math:`\\theta = yaw_{imu} + \\omega + offset_{yaw}`\n\nWe 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*. \n\nIf you have any questions about this tutorial, please feel free to ask questions on `answers.ros.org <http://answers.ros.org>`_.\n\n\n"
  },
  {
    "path": "src/robot_localization/doc/manifest.yaml",
    "content": "actions: []\nauthors: Tom Moore <ayrton04@gmail.com>\nbrief: ''\nbugtracker: ''\ndepends:\n- catkin\n- eigen\n- diagnostic_updater\n- cmake_modules\n- tf2\n- nav_msgs\n- roscpp\n- rostest\n- tf2_ros\n- message_generation\n- message_filters\n- tf2_geometry_msgs\n- sensor_msgs\n- message_runtime\n- std_msgs\n- roslint\n- rosunit\n- diagnostic_msgs\n- geographic_msgs\n- xmlrpcpp\n- python-catkin-pkg\n- geometry_msgs\n- rosbag\ndescription: The robot_localization package provides nonlinear state estimation through\n  sensor fusion of an abritrary number of sensors.\nlicense: BSD\nmaintainers: Tom Moore <ayrton04@gmail.com>\nmsgs: []\npackage_type: package\nrepo_url: ''\nsrvs:\n- SetPose\n- SetDatum\nurl: http://ros.org/wiki/robot_localization\n"
  },
  {
    "path": "src/robot_localization/doc/migrating_from_robot_pose_ekf.rst",
    "content": ".. _migrating_from_robot_pose_ekf:\n\nMigrating from robot_pose_ekf\n#############################\n\nMigration from ``robot_pose_ekf`` is fairly straightforward. This page is meant to highlight relevant differences between the packages to facilitate rapid transitions. \n\nCovariances in Source Messages\n==============================\n\nFor ``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). \n\nHowever, 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.\n\nThe ''differential'' Parameter\n==============================\n\nBy 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.\n\nThis situation can be avoided using three different methods for the ``robot_localization`` state estimation nodes:\n\n1. 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.\n\n2. 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.\n\n3. 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.\n\n\n\n"
  },
  {
    "path": "src/robot_localization/doc/navsat_transform_node.rst",
    "content": "navsat_transform_node\n*********************\n\n``navsat_transform_node`` takes as input a `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message (usually the output of ``ekf_localization_node`` or ``ukf_localization_node``), a `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ containing an accurate estimate of your robot's heading, and a `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ 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.\n\n.. 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.\n\nParameters\n==========\n\n~frequency\n^^^^^^^^^^\nThe real-valued frequency, in Hz, at which ``navsat_transform_node`` checks for new `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ messages, and publishes filtered `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ when ``publish_filtered_gps`` is set to *true*.\n\n~delay\n^^^^^^\nThe time, in seconds, to wait before calculating the transform from GPS coordinates to your robot's world frame.\n\n~magnetic_declination_radians\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nEnter the magnetic declination for your location. If you don't know it, see `http://www.ngdc.noaa.gov/geomag-web <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.\n\n~yaw_offset\n^^^^^^^^^^^\nYour 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.\n\n~zero_altitude\n^^^^^^^^^^^^^^\nIf this is *true*, the `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message produced by this node has its pose Z value set to 0.\n\n~publish_filtered_gps\n^^^^^^^^^^^^^^^^^^^^^\nIf *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 <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message on the ``/gps/filtered`` topic.\n\n~broadcast_utm_transform\n^^^^^^^^^^^^^^^^^^^^^^^^\nIf 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.\n\n~use_odometry_yaw\n^^^^^^^^^^^^^^^^^\nIf *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*.\n\n~wait_for_datum\n^^^^^^^^^^^^^^^\nIf *true*, ``navsat_transform_node`` will wait to get a datum from either:\n\n* The ``datum`` parameter\n* The ``set_datum`` service\n\nSubscribed Topics\n=================\n* ``imu/data`` A `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ message with orientation data\n\n* ``odometry/filtered`` A `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ 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.\n\n* ``gps/fix`` A `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message containing your robot's GPS coordinates\n\nPublished Topics\n================\n* ``odometry/gps`` A `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ 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.\n\n* ``gps/filtered`` (optional) A `sensor_msgs/NavSatFix <http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html>`_ message containing your robot's world frame position, transformed into GPS coordinates\n\nPublished Transforms\n====================\n* ``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.\n"
  },
  {
    "path": "src/robot_localization/doc/preparing_sensor_data.rst",
    "content": "Preparing Your Data for Use with robot_localization\n###################################################\n\nBefore 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``.\n\nFor additional information, users are encouraged to watch this `presentation <https://vimeo.com/142624091>`_ from ROSCon 2015.\n\nAdherence to ROS Standards\n**************************\n\nThe two most important ROS REPs to consider are:\n\n* `REP-103 <http://www.ros.org/reps/rep-0103.html>`_ (Standard Units of Measure and Coordinate Conventions) \n* `REP-105 <http://www.ros.org/reps/rep-0105.html>`_ (Coordinate Frame Conventions). \n\nUsers 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.\n\nAlso, it will likely benefit users to look over the specifications for each of the supported ROS message types:\n\n* `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_\n\n* `geometry_msgs/PoseWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html>`_\n\n* `geometry_msgs/TwistWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/TwistWithCovarianceStamped.html>`_\n\n* `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_\n\nCoordinate Frames and Transforming Sensor Data\n**********************************************\n\n`REP-105 <http://www.ros.org/reps/rep-0105.html>`_ 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.\n\nThe 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:\n\n* `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ - 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*). \n* `geometry_msgs/PoseWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html>`_ - Handled in the same fashion as the pose data in the Odometry message.\n* `geometry_msgs/TwistWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/TwistWithCovarianceStamped.html>`_ - Handled in the same fashion as the twist data in the Odometry message.\n* `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ - 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 <http://www.ros.org/reps/rep-0103.html>`_ 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``.\n \nThe 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. \n\nHandling tf_prefix\n******************\n\nWith the migration to `tf2 <http://wiki.ros.org/tf2>`_ as of ROS Indigo, ``robot_localization`` still allows for the use of the ``tf_prefix`` parameter, but, in accordance with `tf2 <http://wiki.ros.org/tf2>`_, all ``frame_id`` values will have any leading '/' stripped.\n\nConsiderations for Each Sensor Message Type\n*******************************************\n\nOdometry\n========\n\nMany 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:\n\n1. **Velocities/Poses:** `robot_localization` can integrate velocities or absolute pose information. In general, the best practice is:\n\n * If the odometry provides both position and linear velocity, fuse the linear velocity. \n * If the odometry provides both orientation and angular velocity, fuse the orientation.\n\n .. 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. \n\n2. **frame_id:** See the section on coordinate frames and transforms above.\n\n3. **Covariance:** Covariance values **matter** to ``robot_localization``. `robot_pose_ekf <http://wiki.ros.org/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.\n\n .. note:: See :ref:`configuring_robot_localization` and :ref:`migrating_from_robot_pose_ekf` for more information.\n \n4. **Signs:** Adherence to `REP-103 <http://www.ros.org/reps/rep-0103.html>`_ 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*. \n\n5. **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 <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ 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.\n\nIMU\n===\n\nIn addition to the following, be sure to read the above section regarding coordinate frames and transforms for IMU data.\n\n1. **Adherence to specifications:** As with odometry, be sure your data adheres to `REP-103 <http://www.ros.org/reps/rep-0103.html>`_ and the `sensor_msgs/Imu <http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html>`_ specification. Double-check the signs of your data, and make sure the ``frame_id`` values are correct.\n\n2. **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*. \n\n3. **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:\n\n * Measure **+**:math:`9.81` meters per second squared for the :math:`Z` axis. \n * 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. \n * 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.\n\nPoseWithCovarianceStamped\n=========================\n\nSee the section on odometry.\n\nTwistWithCovarianceStamped\n==========================\n\nSee the section on odometry.\n\nCommon errors\n*************\n\n* Input data doesn't adhere to `REP-103 <http://www.ros.org/reps/rep-0103.html>`_. Make sure that all values (especially orientation angles) increase and decrease in the correct directions.\n* 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``.\n* Inflated covariances. The preferred method for ignoring variables in measurements is through the ``odomN_config`` parameter. \n* 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.\n\n"
  },
  {
    "path": "src/robot_localization/doc/state_estimation_nodes.rst",
    "content": "State Estimation Nodes\n######################\n\nekf_localization_node\n*********************\n``ekf_localization_node`` is an implementation of an `extended Kalman filter <http://en.wikipedia.org/wiki/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.\n\nukf_localization_node\n*********************\n``ukf_localization_node`` is an implementation of an `unscented Kalman filter <http://en.wikipedia.org/wiki/Kalman_filter#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``.\n\nParameters\n**********\n\n``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.\n\nThe 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.\n\nParameters Common to *ekf_localization_node* and *ukf_localization_node*\n========================================================================\n\nStandard Parameters\n-------------------\n\n~frequency\n^^^^^^^^^^\nThe real-valued frequency, in Hz, at which the filter produces a state estimate.\n\n.. note:: The filter will not begin computation until it receives at least one message from one of the inputs.\n\n~sensor_timeout\n^^^^^^^^^^^^^^^\nThe 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.\n\n~two_d_mode\n^^^^^^^^^^^\nIf 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.\n\n~[frame]\n^^^^^^^^^\nSpecific parameters:\n\n* ``~map_frame``\n* ``~odom_frame``\n* ``~base_link_frame``\n* ``~world_frame``\n\nThese parameters define the operating \"mode\" for ``robot_localization``. `REP-105 <http://www.ros.org/reps/rep-0105.html>`_ 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:\n\n1. Set the ``map_frame``, ``odom_frame``, and ``base_link_frame`` parameters to the appropriate frame names for your system.\n\n .. 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``.\n\n2. 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.\n3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates from landmark observations) then:\n\n i. Set your ``world_frame`` to your ``map_frame`` value\n 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.\n\nThe 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``.\n\n~transform_time_offset\n^^^^^^^^^^^^^^^^^^^^^^\nSome 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``.\n\n~transform_timeout\n^^^^^^^^^^^^^^^^^^\nThe ``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.\n\n~[sensor]\n^^^^^^^^^\nFor 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:\n\n.. code-block:: xml\n\n   <param name=\"imu0\" value=\"robot/imu/data\"/>\n   <param name=\"odom0\" value=\"wheel_encoder/odometry\"/>\n   <param name=\"odom1\" value=\"visual_odometry/odometry\"/>\n\nThe 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.\n\n~[sensor]_config\n^^^^^^^^^^^^^^^^\n\nSpecific parameters:\n\n* ``~odomN_config``\n* ``~twistN_config``\n* ``~imuN_config``\n* ``~poseN_config``\n\nFor 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:\n\n.. code-block:: xml\n\n <rosparam param=\"odom0_config\">[true,  true,  false,\n                                 false, false, true,\n                                 true,  false, false,\n                                 false, false, true,\n                                 false, false, false]</rosparam>\n\n\nThe 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}`.\n\n.. 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 <configuring_robot_localization>` for more information.\n\n~[sensor]_queue_size\n^^^^^^^^^^^^^^^^^^^^\n\nSpecific parameters:\n\n* ``~odomN_queue_size``\n* ``~twistN_queue_size``\n* ``~imuN_queue_size``\n* ``~poseN_queue_size``\n\nUsers 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.\n\n~[sensor]_differential\n^^^^^^^^^^^^^^^^^^^^^^\n\nSpecific parameters:\n\n* ``~odomN_differential``\n* ``~imuN_differential``\n* ``~poseN_differential``\n\nFor 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.\n\nUsers 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.\n\n.. 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.*\n\n~[sensor]_relative\n^^^^^^^^^^^^^^^^^^\n\nSpecific parameters:\n\n* ``~odomN_relative``\n* ``~imuN_relative``\n* ``~poseN_relative``\n\nIf 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.\n\n~imuN_remove_gravitational_acceleration\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nIf fusing accelerometer data from IMUs, this parameter determines whether or not acceleration due to gravity is removed from the acceleration measurement before fusing it.\n\n.. 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.\n\n~gravitational_acceleration\n^^^^^^^^^^^^^^^^^^^^^^^^^^^\nIf ``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).\n\n~initial_state\n^^^^^^^^^^^^^^\nStarts 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:\n\n.. code-block:: xml\n\n <rosparam param=\"initial_state\">[5.0,  4.0,  3.0,\n                                  0.0,  0.0,  1.57,\n                                  0.1,  0.2,  0.3,\n                                  0.0,  0.0,  0.0,\n                                  0.0,  0.0,  0.0]</rosparam>\n\n~publish_tf\n^^^^^^^^^^^\nIf *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*.\n\n~publish_acceleration\n^^^^^^^^^^^^^^^^^^^^^\nIf *true*, the state estimation node will publish the linear acceleration state. Defaults to *false*.\n\n~print_diagnostics\n^^^^^^^^^^^^^^^^^^\nIf true, the state estimation node will publish diagnostic messages to the ``/diagnostics`` topic. This is useful for debugging your configuration and sensor data.\n\nAdvanced Parameters\n-------------------\n\n~use_control\n^^^^^^^^^^^^\nIf *true*, the state estimation node will listen to the `cmd_vel` topic for a `geometry_msgs/Twist <http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html>`_ 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*.\n\n.. note:: The presence and inclusion of linear acceleration data from an IMU will currently \"override\" the predicted linear acceleration value.\n\n~stamped_control\n^^^^^^^^^^^^^^^^\nIf *true* and ``use_control`` is also *true*, looks for a `geometry_msgs/TwistStamped <http://docs.ros.org/api/geometry_msgs/html/msg/TwistStamped.html>`_ message instead of a `geometry_msgs/Twist <http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html>`_ message.\n\n~control_timeout\n^^^^^^^^^^^^^^^^\nIf ``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.\n\n~control_config\n^^^^^^^^^^^^^^^\nControls 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*.\n\n.. code-block:: xml\n\n <rosparam param=\"control_config\">[true,  false, false,\n                                   false, false, true]</rosparam>\n\n~acceleration_limits\n^^^^^^^^^^^^^^^^^^^^\nHow rapidly your robot can accelerate for each dimension. Matches the parameter order in ``control_config``. Only used if ``use_control`` is set to *true*.\n\n.. code-block:: xml\n\n <rosparam param=\"acceleration_limits\">[1.3, 0.0, 0.0,\n                                        0.0, 0.0, 3.2]</rosparam>\n\n~deceleration_limits\n^^^^^^^^^^^^^^^^^^^^\nHow rapidly your robot can decelerate for each dimension. Matches the parameter order in ``control_config``. Only used if ``use_control`` is set to *true*.\n\n~acceleration_gains\n^^^^^^^^^^^^^^^^^^^\nIf 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*.\n\n.. code-block:: xml\n\n <rosparam param=\"acceleration_limits\">[0.8, 0.0, 0.0,\n                                        0.0, 0.0, 0.9]</rosparam>\n\n~deceleration_gains\n^^^^^^^^^^^^^^^^^^^\nIf 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*.\n\n~smooth_lagged_data\n^^^^^^^^^^^^^^^^^^^\nIf 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.\n\n~history_length\n^^^^^^^^^^^^^^^\nIf ``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.\n\n~[sensor]_nodelay\n^^^^^^^^^^^^^^^^^\n\nSpecific parameters:\n\n* ``~odomN_nodelay``\n* ``~twistN_nodelay``\n* ``~imuN_nodelay``\n* ``~poseN_nodelay``\n\nIf *true*, sets the `tcpNoDelay` `transport hint <http://docs.ros.org/api/roscpp/html/classros_1_1TransportHints.html#a03191a9987162fca0ae2c81fa79fcde9>`_. There is some evidence that Nagle's algorithm intereferes with the timely reception of large message types, such as the `nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_ message. Setting this to *true* for an input disables Nagle's algorithm for that subscriber. Defaults to *false*.\n\n~[sensor]_threshold\n^^^^^^^^^^^^^^^^^^^\nSpecific parameters:\n\n* ``~odomN_pose_rejection_threshold``\n* ``odomN_twist_rejection_threshold``\n* ``poseN_rejection_threshold``\n* ``twistN_rejection_threshold``\n* ``imuN_pose_rejection_threshold``\n* ``imuN_angular_velocity_rejection_threshold``\n* ``imuN_linear_acceleration_rejection_threshold``\n\nIf your data is subject to outliers, use these threshold settings, expressed as `Mahalanobis distances <http://en.wikipedia.org/wiki/Mahalanobis_distance>`_, to control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to ``numeric_limits<double>::max()`` if unspecified.\n\n~debug\n^^^^^^\nBoolean 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*.\n\n~debug_out_file\n^^^^^^^^^^^^^^^^\nIf ``debug`` is *true*, the file to which debug output is written.\n\n~process_noise_covariance\n^^^^^^^^^^^^^^^^^^^^^^^^^\nThe 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.\n\n~dynamic_process_noise_covariance\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nIf *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*.\n\n~initial_estimate_covariance\n^^^^^^^^^^^^^^^^^^^^^^^^^^^^\nThe 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.\n\n~reset_on_time_jump\n^^^^^^^^^^^^^^^^^^^\nIf 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.\n\nNode-specific Parameters\n------------------------\nThe 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.\n\nukf_localization_node\n^^^^^^^^^^^^^^^^^^^^^\n\nThe parameters for ``ukf_localization_node`` follow the nomenclature of the `original paper <http://ieeexplore.ieee.org/xpls/abs_all.jsp?arnumber=882463&tag=1>`_ and `wiki article <http://en.wikipedia.org/wiki/Kalman_filter#Unscented_Kalman_filter>`_.\n\n* **~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).\n\n* **~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).\n\n* **~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.\n\nPublished Topics\n================\n\n* ``odometry/filtered`` (`nav_msgs/Odometry <http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html>`_)\n* ``accel/filtered`` (`geometry_msgs/AccelWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/AccelWithCovarianceStamped.html>`_) (if enabled)\n\nPublished Transforms\n====================\n\n* 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.\n\n* 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.\n\n .. 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.\n\nServices\n========\n\n* ``set_pose`` - By issuing a `geometry_msgs/PoseWithCovarianceStamped <http://docs.ros.org/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html>`_ 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 <http://docs.ros.org/api/robot_localization/html/srv/SetPose.html>`_.rejection\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/ekf.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_EKF_H\n#define ROBOT_LOCALIZATION_EKF_H\n\n#include \"robot_localization/filter_base.h\"\n\n#include <fstream>\n#include <vector>\n#include <set>\n#include <queue>\n\nnamespace RobotLocalization\n{\n\n//! @brief Extended Kalman filter class\n//!\n//! Implementation of an extended Kalman filter (EKF). This\n//! class derives from FilterBase and overrides the predict()\n//! and correct() methods in keeping with the discrete time\n//! EKF algorithm.\n//!\nclass Ekf: public FilterBase\n{\n  public:\n    //! @brief Constructor for the Ekf class\n    //!\n    //! @param[in] args - Generic argument container (not used here, but\n    //! needed so that the ROS filters can pass arbitrary arguments to\n    //! templated filter types).\n    //!\n    explicit Ekf(std::vector<double> args = std::vector<double>());\n\n    //! @brief Destructor for the Ekf class\n    //!\n    ~Ekf();\n\n    //! @brief Carries out the correct step in the predict/update cycle.\n    //!\n    //! @param[in] measurement - The measurement to fuse with our estimate\n    //!\n    void correct(const Measurement &measurement);\n\n    //! @brief Carries out the predict step in the predict/update cycle.\n    //!\n    //! Projects the state and error matrices forward using a model of\n    //! the vehicle's motion.\n    //!\n    //! @param[in] referenceTime - The time at which the prediction is being made\n    //! @param[in] delta - The time step over which to predict.\n    //!\n    void predict(const double referenceTime, const double delta);\n};\n\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_EKF_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/filter_base.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_FILTER_BASE_H\n#define ROBOT_LOCALIZATION_FILTER_BASE_H\n\n#include \"robot_localization/filter_utilities.h\"\n#include \"robot_localization/filter_common.h\"\n\n#include <Eigen/Dense>\n\n#include <algorithm>\n#include <limits>\n#include <map>\n#include <ostream>\n#include <queue>\n#include <set>\n#include <string>\n#include <vector>\n\n#include <boost/shared_ptr.hpp>\n\nnamespace RobotLocalization\n{\n\n//! @brief Structure used for storing and comparing measurements\n//! (for priority queues)\n//!\n//! Measurement units are assumed to be in meters and radians.\n//! Times are real-valued and measured in seconds.\n//!\nstruct Measurement\n{\n  // The topic name for this measurement. Needed\n  // for capturing previous state values for new\n  // measurements.\n  std::string topicName_;\n\n  // The measurement and its associated covariance\n  Eigen::VectorXd measurement_;\n  Eigen::MatrixXd covariance_;\n\n  // This defines which variables within this measurement\n  // actually get passed into the filter. std::vector<bool>\n  // is generally frowned upon, so we use ints.\n  std::vector<int> updateVector_;\n\n  // The real-valued time, in seconds, since some epoch\n  // (presumably the start of execution, but any will do)\n  double time_;\n\n  // The Mahalanobis distance threshold in number of sigmas\n  double mahalanobisThresh_;\n\n  // The most recent control vector (needed for lagged data)\n  Eigen::VectorXd latestControl_;\n\n  // The time stamp of the most recent control term (needed for lagged data)\n  double latestControlTime_;\n\n  // We want earlier times to have greater priority\n  bool operator()(const boost::shared_ptr<Measurement> &a, const boost::shared_ptr<Measurement> &b)\n  {\n    return (*this)(*(a.get()), *(b.get()));\n  }\n\n  bool operator()(const Measurement &a, const Measurement &b)\n  {\n    return a.time_ > b.time_;\n  }\n\n  Measurement() :\n    topicName_(\"\"),\n    latestControl_(),\n    latestControlTime_(0.0),\n    time_(0.0),\n    mahalanobisThresh_(std::numeric_limits<double>::max())\n  {\n  }\n};\ntypedef boost::shared_ptr<Measurement> MeasurementPtr;\n\n//! @brief Structure used for storing and comparing filter states\n//!\n//! This structure is useful when higher-level classes need to remember filter history.\n//! Measurement units are assumed to be in meters and radians.\n//! Times are real-valued and measured in seconds.\n//!\nstruct FilterState\n{\n  // The filter state vector\n  Eigen::VectorXd state_;\n\n  // The filter error covariance matrix\n  Eigen::MatrixXd estimateErrorCovariance_;\n\n  // The most recent control vector\n  Eigen::VectorXd latestControl_;\n\n  // The time stamp of the most recent measurement for the filter\n  double lastMeasurementTime_;\n\n  // The time stamp of the most recent control term\n  double latestControlTime_;\n\n  // We want the queue to be sorted from latest to earliest timestamps.\n  bool operator()(const FilterState &a, const FilterState &b)\n  {\n    return a.lastMeasurementTime_ < b.lastMeasurementTime_;\n  }\n\n  FilterState() :\n    state_(),\n    estimateErrorCovariance_(),\n    latestControl_(),\n    lastMeasurementTime_(0.0),\n    latestControlTime_(0.0)\n  {}\n};\ntypedef boost::shared_ptr<FilterState> FilterStatePtr;\n\nclass FilterBase\n{\n  public:\n    //! @brief Constructor for the FilterBase class\n    //!\n    FilterBase();\n\n    //! @brief Destructor for the FilterBase class\n    //!\n    virtual ~FilterBase();\n\n    //! @brief Resets filter to its unintialized state\n    //!\n    void reset();\n\n    //! @brief Computes a dynamic process noise covariance matrix using the parameterized state\n    //!\n    //! This allows us to, e.g., not increase the pose covariance values when the vehicle is not moving\n    //!\n    //! @param[in] state - The STATE_SIZE state vector that is used to generate the dynamic process noise covariance\n    //!\n    void computeDynamicProcessNoiseCovariance(const Eigen::VectorXd &state, const double delta);\n\n    //! @brief Carries out the correct step in the predict/update cycle. This method\n    //! must be implemented by subclasses.\n    //!\n    //! @param[in] measurement - The measurement to fuse with the state estimate\n    //!\n    virtual void correct(const Measurement &measurement) = 0;\n\n    //! @brief Returns the control vector currently being used\n    //!\n    //! @return The control vector\n    //!\n    const Eigen::VectorXd& getControl();\n\n    //! @brief Returns the time at which the control term was issued\n    //!\n    //! @return The time the control vector was issued\n    //!\n    double getControlTime();\n\n    //! @brief Gets the value of the debug_ variable.\n    //!\n    //! @return True if in debug mode, false otherwise\n    //!\n    bool getDebug();\n\n    //! @brief Gets the estimate error covariance\n    //!\n    //! @return A copy of the estimate error covariance matrix\n    //!\n    const Eigen::MatrixXd& getEstimateErrorCovariance();\n\n    //! @brief Gets the filter's initialized status\n    //!\n    //! @return True if we've received our first measurement, false otherwise\n    //!\n    bool getInitializedStatus();\n\n    //! @brief Gets the most recent measurement time\n    //!\n    //! @return The time at which we last received a measurement\n    //!\n    double getLastMeasurementTime();\n\n    //! @brief Gets the filter's predicted state, i.e., the\n    //! state estimate before correct() is called.\n    //!\n    //! @return A constant reference to the predicted state\n    //!\n    const Eigen::VectorXd& getPredictedState();\n\n    //! @brief Gets the filter's process noise covariance\n    //!\n    //! @return A constant reference to the process noise covariance\n    //!\n    const Eigen::MatrixXd& getProcessNoiseCovariance();\n\n    //! @brief Gets the sensor timeout value (in seconds)\n    //!\n    //! @return The sensor timeout value\n    //!\n    double getSensorTimeout();\n\n    //! @brief Gets the filter state\n    //!\n    //! @return A constant reference to the current state\n    //!\n    const Eigen::VectorXd& getState();\n\n    //! @brief Carries out the predict step in the predict/update cycle.\n    //! Projects the state and error matrices forward using a model of\n    //! the vehicle's motion. This method must be implemented by subclasses.\n    //!\n    //! @param[in] referenceTime - The time at which the prediction is being made\n    //! @param[in] delta - The time step over which to predict.\n    //!\n    virtual void predict(const double referenceTime, const double delta) = 0;\n\n    //! @brief Does some final preprocessing, carries out the predict/update cycle\n    //!\n    //! @param[in] measurement - The measurement object to fuse into the filter\n    //!\n    virtual void processMeasurement(const Measurement &measurement);\n\n    //! @brief Sets the most recent control term\n    //!\n    //! @param[in] control - The control term to be applied\n    //! @param[in] controlTime - The time at which the control in question was received\n    //!\n    void setControl(const Eigen::VectorXd &control, const double controlTime);\n\n    //! @brief Sets the control update vector and acceleration limits\n    //!\n    //! @param[in] updateVector - The values the control term affects\n    //! @param[in] controlTimeout - Timeout value, in seconds, after which a control is considered stale\n    //! @param[in] accelerationLimits - The acceleration limits for the control variables\n    //! @param[in] accelerationGains - Gains applied to the control term-derived acceleration\n    //! @param[in] decelerationLimits - The deceleration limits for the control variables\n    //! @param[in] decelerationGains - Gains applied to the control term-derived deceleration\n    //!\n    void setControlParams(const std::vector<int> &updateVector, const double controlTimeout,\n      const std::vector<double> &accelerationLimits, const std::vector<double> &accelerationGains,\n      const std::vector<double> &decelerationLimits, const std::vector<double> &decelerationGains);\n\n    //! @brief Sets the filter into debug mode\n    //!\n    //! NOTE: this will generates a lot of debug output to the provided stream.\n    //! The value must be a pointer to a valid ostream object.\n    //!\n    //! @param[in] debug - Whether or not to place the filter in debug mode\n    //! @param[in] outStream - If debug is true, then this must have a valid pointer.\n    //! If the pointer is invalid, the filter will not enter debug mode. If debug is\n    //! false, outStream is ignored.\n    //!\n    void setDebug(const bool debug, std::ostream *outStream = NULL);\n\n    //! @brief Enables dynamic process noise covariance calculation\n    //!\n    //! @param[in] dynamicProcessNoiseCovariance - Whether or not to compute dynamic process noise covariance matrices\n    //!\n    void setUseDynamicProcessNoiseCovariance(const bool dynamicProcessNoiseCovariance);\n\n    //! @brief Manually sets the filter's estimate error covariance\n    //!\n    //! @param[in] estimateErrorCovariance - The state to set as the filter's current state\n    //!\n    void setEstimateErrorCovariance(const Eigen::MatrixXd &estimateErrorCovariance);\n\n    //! @brief Sets the filter's last measurement time.\n    //!\n    //! @param[in] lastMeasurementTime - The last measurement time of the filter\n    //!\n    void setLastMeasurementTime(const double lastMeasurementTime);\n\n    //! @brief Sets the process noise covariance for the filter.\n    //!\n    //! This enables external initialization, which is important, as this\n    //! matrix can be difficult to tune for a given implementation.\n    //!\n    //! @param[in] processNoiseCovariance - The STATE_SIZExSTATE_SIZE process noise covariance matrix\n    //! to use for the filter\n    //!\n    void setProcessNoiseCovariance(const Eigen::MatrixXd &processNoiseCovariance);\n\n    //! @brief Sets the sensor timeout\n    //!\n    //! @param[in] sensorTimeout - The time, in seconds, for a sensor to be\n    //! considered having timed out\n    //!\n    void setSensorTimeout(const double sensorTimeout);\n\n    //! @brief Manually sets the filter's state\n    //!\n    //! @param[in] state - The state to set as the filter's current state\n    //!\n    void setState(const Eigen::VectorXd &state);\n\n    //! @brief Ensures a given time delta is valid (helps with bag file playback issues)\n    //!\n    //! @param[in] delta - The time delta, in seconds, to validate\n    //!\n    void validateDelta(double &delta);\n\n  protected:\n    //! @brief Method for settings bounds on acceleration values derived from controls\n    //! @param[in] state - The current state variable (e.g., linear X velocity)\n    //! @param[in] control - The current control commanded velocity corresponding to the state variable\n    //! @param[in] accelerationLimit - Limit for acceleration (regardless of driving direction)\n    //! @param[in] accelerationGain - Gain applied to acceleration control error\n    //! @param[in] decelerationLimit - Limit for deceleration (moving towards zero, regardless of driving direction)\n    //! @param[in] decelerationGain - Gain applied to deceleration control error\n    //! @return a usable acceleration estimate for the control vector\n    //!\n    inline double computeControlAcceleration(const double state, const double control, const double accelerationLimit,\n      const double accelerationGain, const double decelerationLimit, const double decelerationGain)\n    {\n      FB_DEBUG(\"---------- FilterBase::computeControlAcceleration ----------\\n\");\n\n      const double error = control - state;\n      const bool sameSign = (::fabs(error) <= ::fabs(control) + 0.01);\n      const double setPoint = (sameSign ? control : 0.0);\n      const bool decelerating = ::fabs(setPoint) < ::fabs(state);\n      double limit = accelerationLimit;\n      double gain = accelerationGain;\n\n      if (decelerating)\n      {\n        limit = decelerationLimit;\n        gain = decelerationGain;\n      }\n\n      const double finalAccel = std::min(std::max(gain * error, -limit), limit);\n\n      FB_DEBUG(\"Control value: \" << control << \"\\n\" <<\n               \"State value: \" << state << \"\\n\" <<\n               \"Error: \" << error << \"\\n\" <<\n               \"Same sign: \" << (sameSign ? \"true\" : \"false\") << \"\\n\" <<\n               \"Set point: \" << setPoint << \"\\n\" <<\n               \"Decelerating: \" << (decelerating ? \"true\" : \"false\") << \"\\n\" <<\n               \"Limit: \" << limit << \"\\n\" <<\n               \"Gain: \" << gain << \"\\n\" <<\n               \"Final is \" << finalAccel << \"\\n\");\n\n      return finalAccel;\n    }\n\n    //! @brief Keeps the state Euler angles in the range [-pi, pi]\n    //!\n    virtual void wrapStateAngles();\n\n    //! @brief Tests if innovation is within N-sigmas of covariance. Returns true if passed the test.\n    //! @param[in] innovation - The difference between the measurement and the state\n    //! @param[in] invCovariance - The innovation error\n    //! @param[in] nsigmas - Number of standard deviations that are considered acceptable\n    //!\n    virtual bool checkMahalanobisThreshold(const Eigen::VectorXd &innovation,\n                                           const Eigen::MatrixXd &invCovariance,\n                                           const double nsigmas);\n\n    //! @brief Converts the control term to an acceleration to be applied in the prediction step\n    //! @param[in] referenceTime - The time of the update (measurement used in the prediction step)\n    //! @param[in] predictionDelta - The amount of time over which we are carrying out our prediction\n    //!\n    void prepareControl(const double referenceTime, const double predictionDelta);\n\n    //! @brief Gains applied to acceleration derived from control term\n    //!\n    std::vector<double> accelerationGains_;\n\n    //! @brief Caps the acceleration we apply from control input\n    //!\n    std::vector<double> accelerationLimits_;\n\n    //! @brief Variable that gets updated every time we process a measurement and we have a valid control\n    //!\n    Eigen::VectorXd controlAcceleration_;\n\n    //! @brief Gains applied to deceleration derived from control term\n    //!\n    std::vector<double> decelerationGains_;\n\n    //! @brief Caps the deceleration we apply from control input\n    //!\n    std::vector<double> decelerationLimits_;\n\n    //! @brief Latest control term\n    //!\n    Eigen::VectorXd latestControl_;\n\n    //! @brief Which control variables are being used (e.g., not every vehicle is controllable in Y or Z)\n    //!\n    std::vector<int> controlUpdateVector_;\n\n    //! @brief Timeout value, in seconds, after which a control is considered stale\n    //!\n    double controlTimeout_;\n\n    //! @brief Covariance matrices can be incredibly unstable. We can\n    //! add a small value to it at each iteration to help maintain its\n    //! positive-definite property.\n    //!\n    Eigen::MatrixXd covarianceEpsilon_;\n\n    //! @brief Used for outputting debug messages\n    //!\n    std::ostream *debugStream_;\n\n    //! @brief Gets updated when useDynamicProcessNoise_ is true\n    //!\n    Eigen::MatrixXd dynamicProcessNoiseCovariance_;\n\n    //! @brief This matrix stores the total error in our position\n    //! estimate (the state_ variable).\n    //!\n    Eigen::MatrixXd estimateErrorCovariance_;\n\n    //! @brief We need the identity for a few operations. Better to store it.\n    //!\n    Eigen::MatrixXd identity_;\n\n    //! @brief Whether or not we've received any measurements\n    //!\n    bool initialized_;\n\n    //! @brief Tracks the time the filter was last updated using a measurement.\n    //!\n    //! This value is used to monitor sensor readings with respect to the sensorTimeout_.\n    //! We also use it to compute the time delta values for our prediction step.\n    //!\n    double lastMeasurementTime_;\n\n    //! @brief The time of reception of the most recent control term\n    //!\n    double latestControlTime_;\n\n    //! @brief Holds the last predicted state of the filter\n    //!\n    Eigen::VectorXd predictedState_;\n\n    //! @brief As we move through the world, we follow a predict/update\n    //! cycle. If one were to imagine a scenario where all we did was make\n    //! predictions without correcting, the error in our position estimate\n    //! would grow without bound. This error is stored in the\n    //! stateEstimateCovariance_ matrix. However, this matrix doesn't answer\n    //! the question of *how much* our error should grow for each time step.\n    //! That's where the processNoiseCovariance matrix comes in. When we\n    //! make a prediction using the transfer function, we add this matrix\n    //! (times deltaT) to the state estimate covariance matrix.\n    //!\n    Eigen::MatrixXd processNoiseCovariance_;\n\n    //! @brief The updates to the filter - both predict and correct - are driven\n    //! by measurements. If we get a gap in measurements for some reason, we want\n    //! the filter to continue estimating. When this gap occurs, as specified by\n    //! this timeout, we will continue to call predict() at the filter's frequency.\n    //!\n    double sensorTimeout_;\n\n    //! @brief This is the robot's state vector, which is what we are trying to\n    //! filter. The values in this vector are what get reported by the node.\n    //!\n    Eigen::VectorXd state_;\n\n    //! @brief The Kalman filter transfer function\n    //!\n    //! Kalman filters and extended Kalman filters project the current\n    //! state forward in time. This is the \"predict\" part of the predict/correct\n    //! cycle. A Kalman filter has a (typically constant) matrix A that defines\n    //! how to turn the current state, x, into the predicted next state. For an\n    //! EKF, this matrix becomes a function f(x). However, this function can still\n    //! be expressed as a matrix to make the math a little cleaner, which is what\n    //! we do here. Technically, each row in the matrix is actually a function.\n    //! Some rows will contain many trigonometric functions, which are of course\n    //! non-linear. In any case, you can think of this as the 'A' matrix in the\n    //! Kalman filter formulation.\n    //!\n    Eigen::MatrixXd transferFunction_;\n\n    //! @brief The Kalman filter transfer function Jacobian\n    //!\n    //! The transfer function is allowed to be non-linear in an EKF, but\n    //! for propagating (predicting) the covariance matrix, we need to linearize\n    //! it about the current mean (i.e., state). This is done via a Jacobian,\n    //! which calculates partial derivatives of each row of the transfer function\n    //! matrix with respect to each state variable.\n    //!\n    Eigen::MatrixXd transferFunctionJacobian_;\n\n    //! @brief Whether or not we apply the control term\n    //!\n    bool useControl_;\n\n    //! @brief If true, uses the robot's vehicle state and the static process noise covariance matrix to generate a\n    //! dynamic process noise covariance matrix\n    //!\n    bool useDynamicProcessNoiseCovariance_;\n\n  private:\n    //! @brief Whether or not the filter is in debug mode\n    //!\n    bool debug_;\n};\n\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_FILTER_BASE_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/filter_common.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_FILTER_COMMON_H\n#define ROBOT_LOCALIZATION_FILTER_COMMON_H\n\nnamespace RobotLocalization\n{\n\n//! @brief Enumeration that defines the state vector\n//!\nenum StateMembers\n{\n  StateMemberX = 0,\n  StateMemberY,\n  StateMemberZ,\n  StateMemberRoll,\n  StateMemberPitch,\n  StateMemberYaw,\n  StateMemberVx,\n  StateMemberVy,\n  StateMemberVz,\n  StateMemberVroll,\n  StateMemberVpitch,\n  StateMemberVyaw,\n  StateMemberAx,\n  StateMemberAy,\n  StateMemberAz\n};\n\n//! @brief Enumeration that defines the control vector\n//!\nenum ControlMembers\n{\n  ControlMemberVx,\n  ControlMemberVy,\n  ControlMemberVz,\n  ControlMemberVroll,\n  ControlMemberVpitch,\n  ControlMemberVyaw\n};\n\n//! @brief Global constants that define our state\n//! vector size and offsets to groups of values\n//! within that state.\nconst int STATE_SIZE = 15;\nconst int POSITION_OFFSET = StateMemberX;\nconst int ORIENTATION_OFFSET = StateMemberRoll;\nconst int POSITION_V_OFFSET = StateMemberVx;\nconst int ORIENTATION_V_OFFSET = StateMemberVroll;\nconst int POSITION_A_OFFSET = StateMemberAx;\n\n//! @brief Pose and twist messages each\n//! contain six variables\nconst int POSE_SIZE = 6;\nconst int TWIST_SIZE = 6;\nconst int POSITION_SIZE = 3;\nconst int ORIENTATION_SIZE = 3;\nconst int ACCELERATION_SIZE = 3;\n\n//! @brief Common variables\nconst double PI = 3.141592653589793;\nconst double TAU = 6.283185307179587;\n\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_FILTER_COMMON_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/filter_utilities.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_FILTER_UTILITIES_H\n#define ROBOT_LOCALIZATION_FILTER_UTILITIES_H\n\n#include <Eigen/Dense>\n\n#include <iomanip>\n#include <iostream>\n#include <string>\n#include <vector>\n\n#define FB_DEBUG(msg) if (getDebug()) { *debugStream_ << msg; }\n\n// Handy methods for debug output\nstd::ostream& operator<<(std::ostream& os, const Eigen::MatrixXd &mat);\nstd::ostream& operator<<(std::ostream& os, const Eigen::VectorXd &vec);\nstd::ostream& operator<<(std::ostream& os, const std::vector<size_t> &vec);\nstd::ostream& operator<<(std::ostream& os, const std::vector<int> &vec);\n\nnamespace RobotLocalization\n{\nnamespace FilterUtilities\n{\n\n  //! @brief Utility method keeping RPY angles in the range [-pi, pi]\n  //! @param[in] rotation - The rotation to bind\n  //! @return the bounded value\n  //!\n  double clampRotation(double rotation);\n\n  //! @brief Utility method for appending tf2 prefixes cleanly\n  //! @param[in] tfPrefix - the tf2 prefix to append\n  //! @param[in, out] frameId - the resulting frame_id value\n  //!\n  void appendPrefix(std::string tfPrefix, std::string &frameId);\n\n}  // namespace FilterUtilities\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_FILTER_UTILITIES_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/navsat_conversions.h",
    "content": "/*\n* Copyright (C) 2010 Austin Robot Technology, and others\n* All rights reserved.\n*\n* Redistribution and use in source and binary forms, with or without\n* modification, are permitted provided that the following conditions\n* are met:\n*\n* 1. Redistributions of source code must retain the above copyright\n* notice, this list of conditions and the following disclaimer.\n* 2. Redistributions in binary form must reproduce the above\n* copyright notice, this list of conditions and the following\n* disclaimer in the documentation and/or other materials provided\n* with the distribution.\n* 3. Neither the names of the University of Texas at Austin, nor\n* Austin Robot Technology, nor the names of other contributors may\n* be used to endorse or promote products derived from this\n* software without specific prior written permission.\n*\n* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n* \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n* POSSIBILITY OF SUCH DAMAGE.\n*\n* This file contains code from multiple files in the original\n* source. The originals can be found here:\n*\n* https://github.com/austin-robot/utexas-art-ros-pkg/blob/afd147a1eb944fc3dbd138574c39699813f797bf/stacks/art_vehicle/art_common/include/art/UTM.h\n* https://github.com/austin-robot/utexas-art-ros-pkg/blob/afd147a1eb944fc3dbd138574c39699813f797bf/stacks/art_vehicle/art_common/include/art/conversions.h\n*/\n\n#ifndef ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H\n#define ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H\n\n/**  @file\n\n     @brief Universal Transverse Mercator transforms.\n     Functions to convert (spherical) latitude and longitude to and\n     from (Euclidean) UTM coordinates.\n     @author Chuck Gantz- chuck.gantz@globalstar.com\n */\n\n#include <cmath>\n#include <string>\n\n#include <stdio.h>\n#include <stdlib.h>\n\nnamespace RobotLocalization\n{\nnamespace NavsatConversions\n{\n\nconst double RADIANS_PER_DEGREE = M_PI/180.0;\nconst double DEGREES_PER_RADIAN = 180.0/M_PI;\n\n// Grid granularity for rounding UTM coordinates to generate MapXY.\nconst double grid_size = 100000.0;    // 100 km grid\n\n// WGS84 Parameters\n#define WGS84_A   6378137.0   // major axis\n#define WGS84_B   6356752.31424518  // minor axis\n#define WGS84_F   0.0033528107    // ellipsoid flattening\n#define WGS84_E   0.0818191908    // first eccentricity\n#define WGS84_EP  0.0820944379    // second eccentricity\n\n// UTM Parameters\n#define UTM_K0    0.9996               // scale factor\n#define UTM_FE    500000.0             // false easting\n#define UTM_FN_N  0.0                  // false northing, northern hemisphere\n#define UTM_FN_S  10000000.0           // false northing, southern hemisphere\n#define UTM_E2    (WGS84_E*WGS84_E)    // e^2\n#define UTM_E4    (UTM_E2*UTM_E2)      // e^4\n#define UTM_E6    (UTM_E4*UTM_E2)      // e^6\n#define UTM_EP2   (UTM_E2/(1-UTM_E2))  // e'^2\n\n/**\n * Utility function to convert geodetic to UTM position\n *\n * Units in are floating point degrees (sign for east/west)\n *\n * Units out are meters\n *\n * @todo deprecate this interface in favor of LLtoUTM()\n */\nstatic inline void UTM(double lat, double lon, double *x, double *y)\n{\n  // constants\n  static const double m0 = (1 - UTM_E2/4 - 3*UTM_E4/64 - 5*UTM_E6/256);\n  static const double m1 = -(3*UTM_E2/8 + 3*UTM_E4/32 + 45*UTM_E6/1024);\n  static const double m2 = (15*UTM_E4/256 + 45*UTM_E6/1024);\n  static const double m3 = -(35*UTM_E6/3072);\n\n  // compute the central meridian\n  int cm = ((lon >= 0.0)\n    ? (static_cast<int>(lon) - (static_cast<int>(lon)) % 6 + 3)\n    : (static_cast<int>(lon) - (static_cast<int>(lon)) % 6 - 3));\n\n  // convert degrees into radians\n  double rlat = lat * RADIANS_PER_DEGREE;\n  double rlon = lon * RADIANS_PER_DEGREE;\n  double rlon0 = cm * RADIANS_PER_DEGREE;\n\n  // compute trigonometric functions\n  double slat = sin(rlat);\n  double clat = cos(rlat);\n  double tlat = tan(rlat);\n\n  // decide the false northing at origin\n  double fn = (lat > 0) ? UTM_FN_N : UTM_FN_S;\n\n  double T = tlat * tlat;\n  double C = UTM_EP2 * clat * clat;\n  double A = (rlon - rlon0) * clat;\n  double M = WGS84_A * (m0*rlat + m1*sin(2*rlat)\n      + m2*sin(4*rlat) + m3*sin(6*rlat));\n  double V = WGS84_A / sqrt(1 - UTM_E2*slat*slat);\n\n  // compute the easting-northing coordinates\n  *x = UTM_FE + UTM_K0 * V * (A + (1-T+C)*pow(A, 3)/6\n            + (5-18*T+T*T+72*C-58*UTM_EP2)*pow(A, 5)/120);\n  *y = fn + UTM_K0 * (M + V * tlat * (A*A/2\n              + (5-T+9*C+4*C*C)*pow(A, 4)/24\n              + ((61-58*T+T*T+600*C-330*UTM_EP2)\n           * pow(A, 6)/720)));\n\n  return;\n}\n\n\n/**\n * Determine the correct UTM letter designator for the\n * given latitude\n *\n * @returns 'Z' if latitude is outside the UTM limits of 84N to 80S\n *\n * Written by Chuck Gantz- chuck.gantz@globalstar.com\n */\nstatic inline char UTMLetterDesignator(double Lat)\n{\n  char LetterDesignator;\n\n  if     ((84 >= Lat) && (Lat >= 72))  LetterDesignator = 'X';\n  else if ((72 > Lat) && (Lat >= 64))  LetterDesignator = 'W';\n  else if ((64 > Lat) && (Lat >= 56))  LetterDesignator = 'V';\n  else if ((56 > Lat) && (Lat >= 48))  LetterDesignator = 'U';\n  else if ((48 > Lat) && (Lat >= 40))  LetterDesignator = 'T';\n  else if ((40 > Lat) && (Lat >= 32))  LetterDesignator = 'S';\n  else if ((32 > Lat) && (Lat >= 24))  LetterDesignator = 'R';\n  else if ((24 > Lat) && (Lat >= 16))  LetterDesignator = 'Q';\n  else if ((16 > Lat) && (Lat >= 8))   LetterDesignator = 'P';\n  else if (( 8 > Lat) && (Lat >= 0))   LetterDesignator = 'N';\n  else if (( 0 > Lat) && (Lat >= -8))  LetterDesignator = 'M';\n  else if ((-8 > Lat) && (Lat >= -16)) LetterDesignator = 'L';\n  else if ((-16 > Lat) && (Lat >= -24)) LetterDesignator = 'K';\n  else if ((-24 > Lat) && (Lat >= -32)) LetterDesignator = 'J';\n  else if ((-32 > Lat) && (Lat >= -40)) LetterDesignator = 'H';\n  else if ((-40 > Lat) && (Lat >= -48)) LetterDesignator = 'G';\n  else if ((-48 > Lat) && (Lat >= -56)) LetterDesignator = 'F';\n  else if ((-56 > Lat) && (Lat >= -64)) LetterDesignator = 'E';\n  else if ((-64 > Lat) && (Lat >= -72)) LetterDesignator = 'D';\n  else if ((-72 > Lat) && (Lat >= -80)) LetterDesignator = 'C';\n        // 'Z' is an error flag, the Latitude is outside the UTM limits\n  else LetterDesignator = 'Z';\n  return LetterDesignator;\n}\n\n/**\n * Convert lat/long to UTM coords.  Equations from USGS Bulletin 1532\n *\n * East Longitudes are positive, West longitudes are negative.\n * North latitudes are positive, South latitudes are negative\n * Lat and Long are in fractional degrees\n *\n * Written by Chuck Gantz- chuck.gantz@globalstar.com\n */\nstatic inline void LLtoUTM(const double Lat, const double Long,\n                           double &UTMNorthing, double &UTMEasting,\n                           std::string &UTMZone)\n{\n  double a = WGS84_A;\n  double eccSquared = UTM_E2;\n  double k0 = UTM_K0;\n\n  double LongOrigin;\n  double eccPrimeSquared;\n  double N, T, C, A, M;\n\n  // Make sure the longitude is between -180.00 .. 179.9\n  double LongTemp = (Long+180)-static_cast<int>((Long+180)/360)*360-180;\n\n  double LatRad = Lat*RADIANS_PER_DEGREE;\n  double LongRad = LongTemp*RADIANS_PER_DEGREE;\n  double LongOriginRad;\n  int    ZoneNumber;\n\n  ZoneNumber = static_cast<int>((LongTemp + 180)/6) + 1;\n\n  if ( Lat >= 56.0 && Lat < 64.0 && LongTemp >= 3.0 && LongTemp < 12.0 )\n    ZoneNumber = 32;\n\n        // Special zones for Svalbard\n  if ( Lat >= 72.0 && Lat < 84.0 )\n  {\n    if (      LongTemp >= 0.0  && LongTemp <  9.0 ) ZoneNumber = 31;\n    else if ( LongTemp >= 9.0  && LongTemp < 21.0 ) ZoneNumber = 33;\n    else if ( LongTemp >= 21.0 && LongTemp < 33.0 ) ZoneNumber = 35;\n    else if ( LongTemp >= 33.0 && LongTemp < 42.0 ) ZoneNumber = 37;\n  }\n        // +3 puts origin in middle of zone\n  LongOrigin = (ZoneNumber - 1)*6 - 180 + 3;\n  LongOriginRad = LongOrigin * RADIANS_PER_DEGREE;\n\n  // Compute the UTM Zone from the latitude and longitude\n  char zone_buf[] = {0, 0, 0, 0};\n  snprintf(zone_buf, sizeof(zone_buf), \"%d%c\", ZoneNumber, UTMLetterDesignator(Lat));\n  UTMZone = std::string(zone_buf);\n\n  eccPrimeSquared = (eccSquared)/(1-eccSquared);\n\n  N = a/sqrt(1-eccSquared*sin(LatRad)*sin(LatRad));\n  T = tan(LatRad)*tan(LatRad);\n  C = eccPrimeSquared*cos(LatRad)*cos(LatRad);\n  A = cos(LatRad)*(LongRad-LongOriginRad);\n\n  M = a*((1 - eccSquared/4 - 3*eccSquared*eccSquared/64\n                - 5*eccSquared*eccSquared*eccSquared/256) * LatRad\n               - (3*eccSquared/8 + 3*eccSquared*eccSquared/32\n                  + 45*eccSquared*eccSquared*eccSquared/1024)*sin(2*LatRad)\n               + (15*eccSquared*eccSquared/256\n                  + 45*eccSquared*eccSquared*eccSquared/1024)*sin(4*LatRad)\n               - (35*eccSquared*eccSquared*eccSquared/3072)*sin(6*LatRad));\n\n  UTMEasting = static_cast<double>\n          (k0*N*(A+(1-T+C)*A*A*A/6\n                 + (5-18*T+T*T+72*C-58*eccPrimeSquared)*A*A*A*A*A/120)\n           + 500000.0);\n\n  UTMNorthing = static_cast<double>\n          (k0*(M+N*tan(LatRad)\n               *(A*A/2+(5-T+9*C+4*C*C)*A*A*A*A/24\n                 + (61-58*T+T*T+600*C-330*eccPrimeSquared)*A*A*A*A*A*A/720)));\n\n  if (Lat < 0)\n          {\n            // 10000000 meter offset for southern hemisphere\n            UTMNorthing += 10000000.0;\n          }\n}\n\n/**\n * Converts UTM coords to lat/long.  Equations from USGS Bulletin 1532\n *\n * East Longitudes are positive, West longitudes are negative.\n * North latitudes are positive, South latitudes are negative\n * Lat and Long are in fractional degrees.\n *\n * Written by Chuck Gantz- chuck.gantz@globalstar.com\n */\nstatic inline void UTMtoLL(const double UTMNorthing, const double UTMEasting,\n                           const std::string &UTMZone, double& Lat,  double& Long )\n{\n  double k0 = UTM_K0;\n  double a = WGS84_A;\n  double eccSquared = UTM_E2;\n  double eccPrimeSquared;\n  double e1 = (1-sqrt(1-eccSquared))/(1+sqrt(1-eccSquared));\n  double N1, T1, C1, R1, D, M;\n  double LongOrigin;\n  double mu, phi1Rad;\n  double x, y;\n  int ZoneNumber;\n  char* ZoneLetter;\n\n  x = UTMEasting - 500000.0;  // remove 500,000 meter offset for longitude\n  y = UTMNorthing;\n\n  ZoneNumber = strtoul(UTMZone.c_str(), &ZoneLetter, 10);\n  if ((*ZoneLetter - 'N') < 0)\n          {\n            // remove 10,000,000 meter offset used for southern hemisphere\n            y -= 10000000.0;\n          }\n\n  // +3 puts origin in middle of zone\n  LongOrigin = (ZoneNumber - 1)*6 - 180 + 3;\n  eccPrimeSquared = (eccSquared)/(1-eccSquared);\n\n  M = y / k0;\n  mu = M/(a*(1-eccSquared/4-3*eccSquared*eccSquared/64\n                   -5*eccSquared*eccSquared*eccSquared/256));\n\n  phi1Rad = mu + ((3*e1/2-27*e1*e1*e1/32)*sin(2*mu)\n                        + (21*e1*e1/16-55*e1*e1*e1*e1/32)*sin(4*mu)\n                        + (151*e1*e1*e1/96)*sin(6*mu));\n\n  N1 = a/sqrt(1-eccSquared*sin(phi1Rad)*sin(phi1Rad));\n  T1 = tan(phi1Rad)*tan(phi1Rad);\n  C1 = eccPrimeSquared*cos(phi1Rad)*cos(phi1Rad);\n  R1 = a*(1-eccSquared)/pow(1-eccSquared*sin(phi1Rad)*sin(phi1Rad), 1.5);\n  D = x/(N1*k0);\n\n  Lat = phi1Rad - ((N1*tan(phi1Rad)/R1)\n                         *(D*D/2\n                           -(5+3*T1+10*C1-4*C1*C1-9*eccPrimeSquared)*D*D*D*D/24\n                           +(61+90*T1+298*C1+45*T1*T1-252*eccPrimeSquared\n                             -3*C1*C1)*D*D*D*D*D*D/720));\n\n  Lat = Lat * DEGREES_PER_RADIAN;\n\n  Long = ((D-(1+2*T1+C1)*D*D*D/6\n                 +(5-2*C1+28*T1-3*C1*C1+8*eccPrimeSquared+24*T1*T1)\n                 *D*D*D*D*D/120)\n                / cos(phi1Rad));\n  Long = LongOrigin + Long * DEGREES_PER_RADIAN;\n}\n\n}  // namespace NavsatConversions\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_NAVSAT_CONVERSIONS_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/navsat_transform.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H\n#define ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H\n\n#include <robot_localization/SetDatum.h>\n\n#include <ros/ros.h>\n\n#include <nav_msgs/Odometry.h>\n#include <sensor_msgs/Imu.h>\n#include <sensor_msgs/NavSatFix.h>\n\n#include <tf2/LinearMath/Transform.h>\n#include <tf2_ros/static_transform_broadcaster.h>\n#include <tf2_ros/buffer.h>\n#include <tf2_ros/transform_listener.h>\n\n#include <Eigen/Dense>\n\n#include <string>\n\nnamespace RobotLocalization\n{\n\nclass NavSatTransform\n{\n  public:\n    //! @brief Constructor\n    //!\n    NavSatTransform();\n\n    //! @brief Destructor\n    //!\n    ~NavSatTransform();\n\n    //! @brief Main run loop\n    //!\n    void run();\n\n  private:\n    //! @brief Computes the transform from the UTM frame to the odom frame\n    //!\n    void computeTransform();\n\n    //! @brief Callback for the datum service\n    //!\n    bool datumCallback(robot_localization::SetDatum::Request& request, robot_localization::SetDatum::Response&);\n\n    //! @brief Given the pose of the navsat sensor in the UTM frame, removes the offset from the vehicle's centroid\n    //! and returns the UTM-frame pose of said centroid.\n    //!\n    void getRobotOriginUtmPose(const tf2::Transform &gps_utm_pose,\n                               tf2::Transform &robot_utm_pose,\n                               const ros::Time &transform_time);\n\n    //! @brief Given the pose of the navsat sensor in the world frame, removes the offset from the vehicle's centroid\n    //! and returns the world-frame pose of said centroid.\n    //!\n    void getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose,\n                                 tf2::Transform &robot_odom_pose,\n                                 const ros::Time &transform_time);\n\n    //! @brief Callback for the GPS fix data\n    //! @param[in] msg The NavSatFix message to process\n    //!\n    void gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg);\n\n    //! @brief Callback for the IMU data\n    //! @param[in] msg The IMU message to process\n    //!\n    void imuCallback(const sensor_msgs::ImuConstPtr& msg);\n\n    //! @brief Callback for the odom data\n    //! @param[in] msg The odometry message to process\n    //!\n    void odomCallback(const nav_msgs::OdometryConstPtr& msg);\n\n    //! @brief Converts the odometry data back to GPS and broadcasts it\n    //! @param[out] filtered_gps The NavSatFix message to prepare\n    //!\n    bool prepareFilteredGps(sensor_msgs::NavSatFix &filtered_gps);\n\n    //! @brief Prepares the GPS odometry message before sending\n    //! @param[out] gps_odom The odometry message to prepare\n    //!\n    bool prepareGpsOdometry(nav_msgs::Odometry &gps_odom);\n\n    //! @brief Used for setting the GPS data that will be used to compute the transform\n    //! @param[in] msg The NavSatFix message to use in the transform\n    //!\n    void setTransformGps(const sensor_msgs::NavSatFixConstPtr& msg);\n\n    //! @brief Used for setting the odometry data that will be used to compute the transform\n    //! @param[in] msg The odometry message to use in the transform\n    //!\n    void setTransformOdometry(const nav_msgs::OdometryConstPtr& msg);\n\n    //! @brief Frame ID of the robot's body frame\n    //!\n    //! This is needed for obtaining transforms from the robot's body frame to the frames of sensors (IMU and GPS)\n    //!\n    std::string base_link_frame_id_;\n\n    //! @brief Whether or not we broadcast the UTM transform\n    //!\n    bool broadcast_utm_transform_;\n\n    //! @brief Whether to broadcast the UTM transform as parent frame, default as child\n    //!\n    bool broadcast_utm_transform_as_parent_frame_;\n\n    //! @brief The frame_id of the GPS message (specifies mounting location)\n    //!\n    std::string gps_frame_id_;\n\n    //! @brief Timestamp of the latest good GPS message\n    //!\n    //! We assign this value to the timestamp of the odometry message that we output\n    //!\n    ros::Time gps_update_time_;\n\n    //! @brief Whether or not we have new GPS data\n    //!\n    //! We only want to compute and broadcast our transformed GPS data if it's new. This variable keeps track of that.\n    //!\n    bool gps_updated_;\n\n    //! @brief Whether or not the GPS fix is usable\n    //!\n    bool has_transform_gps_;\n\n    //! @brief Signifies that we have received a usable IMU message\n    //!\n    bool has_transform_imu_;\n\n    //! @brief Signifies that we have received a usable odometry message\n    //!\n    bool has_transform_odom_;\n\n    //! @brief Covariance for most recent odometry data\n    //!\n    Eigen::MatrixXd latest_odom_covariance_;\n\n    //! @brief Covariance for most recent GPS/UTM data\n    //!\n    Eigen::MatrixXd latest_utm_covariance_;\n\n    //! @brief Latest GPS data, stored as UTM coords\n    //!\n    tf2::Transform latest_utm_pose_;\n\n    //! @brief Latest odometry pose data\n    //!\n    tf2::Transform latest_world_pose_;\n\n    //! @brief Parameter that specifies the magnetic declination for the robot's environment.\n    //!\n    double magnetic_declination_;\n\n    //! @brief Timestamp of the latest good odometry message\n    //!\n    //! We assign this value to the timestamp of the odometry message that we output\n    //!\n    ros::Time odom_update_time_;\n\n    //! @brief Whether or not we have new odometry data\n    //!\n    //! If we're creating filtered GPS messages, then we only want to broadcast them when new odometry data arrives.\n    //!\n    bool odom_updated_;\n\n    //! @brief Whether or not we publish filtered GPS messages\n    //!\n    bool publish_gps_;\n\n    //! @brief Transform buffer for managing coordinate transforms\n    //!\n    tf2_ros::Buffer tf_buffer_;\n\n    //! @brief Transform listener for receiving transforms\n    //!\n    tf2_ros::TransformListener tf_listener_;\n\n    //! @brief Whether or not we've computed a good heading\n    //!\n    bool transform_good_;\n\n    //! @brief Latest IMU orientation\n    //!\n    tf2::Quaternion transform_orientation_;\n\n    //! @brief Holds the UTM pose that is used to compute the transform\n    //!\n    tf2::Transform transform_utm_pose_;\n\n    //! @brief Latest IMU orientation\n    //!\n    tf2::Transform transform_world_pose_;\n\n    //! @brief Whether we get our datum from the first GPS message or from the set_datum\n    //! service/parameter\n    //!\n    bool use_manual_datum_;\n\n    //! @brief Whether we get the transform's yaw from the odometry or IMU source\n    //!\n    bool use_odometry_yaw_;\n\n    //! @brief Used for publishing the static world_frame->utm transform\n    //!\n    tf2_ros::StaticTransformBroadcaster utm_broadcaster_;\n\n    //! @brief Stores the yaw we need to compute the transform\n    //!\n    double utm_odom_tf_yaw_;\n\n    //! @brief Holds the UTM->odom transform\n    //!\n    tf2::Transform utm_world_transform_;\n\n    //! @brief Holds the odom->UTM transform for filtered GPS broadcast\n    //!\n    tf2::Transform utm_world_trans_inverse_;\n\n    //! @brief UTM zone as determined after transforming GPS message\n    //!\n    std::string utm_zone_;\n\n    //! @brief Frame ID of the GPS odometry output\n    //!\n    //! This will just match whatever your odometry message has\n    //!\n    std::string world_frame_id_;\n\n    //! @brief IMU's yaw offset\n    //!\n    //! Your IMU should read 0 when facing *magnetic* north. If it doesn't, this (parameterized) value gives the offset\n    //! (NOTE: if you have a magenetic declination, use the parameter setting for that).\n    //!\n    double yaw_offset_;\n\n    //! @brief Parameter that specifies the how long we wait for a transform to become available.\n    //!\n    ros::Duration transform_timeout_;\n\n    //! @brief Whether or not to report 0 altitude\n    //!\n    //! If this parameter is true, we always report 0 for the altitude of the converted GPS odometry message.\n    //!\n    bool zero_altitude_;\n};\n\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_NAVSAT_TRANSFORM_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/robot_localization_estimator.h",
    "content": "/*\n * Copyright (c) 2016, TNO IVS Helmond.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H\n#define ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H\n\n#include <iostream>\n#include <vector>\n#include <boost/circular_buffer.hpp>\n#include <Eigen/Dense>\n\n#include \"robot_localization/filter_base.h\"\n#include \"robot_localization/filter_utilities.h\"\n#include \"robot_localization/filter_common.h\"\n\nnamespace RobotLocalization\n{\n\nstruct Twist\n{\n  Eigen::Vector3d linear;\n  Eigen::Vector3d angular;\n};\n\n//! @brief Robot Localization Estimator State\n//!\n//! The Estimator State data structure bundles the state information of the estimator.\n//!\nstruct EstimatorState\n{\n  EstimatorState():\n    time_stamp(0.0),\n    state(STATE_SIZE),\n    covariance(STATE_SIZE, STATE_SIZE)\n  {\n    state.setZero();\n    covariance.setZero();\n  }\n\n  //! @brief Time at which this state is/was achieved\n  double time_stamp;\n\n  //! @brief System state at time = time_stamp\n  Eigen::VectorXd state;\n\n  //! @brief System state covariance at time = time_stamp\n  Eigen::MatrixXd covariance;\n\n  friend std::ostream& operator<<(std::ostream &os, const EstimatorState& state)\n  {\n    return os << \"state:\\n - time_stamp: \" << state.time_stamp <<\n                 \"\\n - state: \\n\" << state.state <<\n                 \" - covariance: \\n\" << state.covariance;\n  }\n};\n\nnamespace EstimatorResults\n{\nenum EstimatorResult\n{\n  ExtrapolationIntoFuture = 0,\n  Interpolation,\n  ExtrapolationIntoPast,\n  Exact,\n  EmptyBuffer,\n  Failed\n};\n}  // namespace EstimatorResults\ntypedef EstimatorResults::EstimatorResult EstimatorResult;\n\nnamespace FilterTypes\n{\nenum FilterType\n{\n  EKF = 0,\n  UKF,\n  NotDefined\n};\n}  // namespace FilterTypes\ntypedef FilterTypes::FilterType FilterType;\n\n//! @brief Robot Localization Listener class\n//!\n//! The Robot Localization Estimator class buffers states of and inputs to a system and can interpolate and extrapolate\n//! based on a given system model.\n//!\nclass RobotLocalizationEstimator\n{\npublic:\n  //! @brief Constructor for the RobotLocalizationListener class\n  //!\n  //! @param[in] args - Generic argument container (not used here, but needed so that the ROS filters can pass arbitrary\n  //! arguments to templated filter types).\n  //!\n  explicit RobotLocalizationEstimator(unsigned int buffer_capacity,\n                                      FilterType filter_type,\n                                      const Eigen::MatrixXd& process_noise_covariance,\n                                      const std::vector<double>& filter_args = std::vector<double>());\n\n  //! @brief Destructor for the RobotLocalizationListener class\n  //!\n  virtual ~RobotLocalizationEstimator();\n\n  //! @brief Sets the current internal state of the listener.\n  //!\n  //! @param[in] state - The new state vector to set the internal state to\n  //!\n  void setState(const EstimatorState& state);\n\n  //! @brief Returns the state at a given time\n  //!\n  //! Projects the current state and error matrices forward using a model of the robot's motion.\n  //!\n  //! @param[in] time - The time to which the prediction is being made\n  //! @param[out] state - The returned state at the given time\n  //!\n  //! @return GetStateResult enum\n  //!\n  EstimatorResult getState(const double time, EstimatorState &state) const;\n\n  //! @brief Clears the internal state buffer\n  //!\n  void clearBuffer();\n\n  //! @brief Sets the buffer capacity\n  //!\n  //! @param[in] capacity - The new buffer capacity\n  //!\n  void setBufferCapacity(const int capacity);\n\n  //! @brief Returns the buffer capacity\n  //!\n  //! Returns the number of EstimatorState objects that can be pushed to the buffer before old ones are dropped. (The\n  //! capacity of the buffer).\n  //!\n  //! @return buffer capacity\n  //!\n  unsigned int getBufferCapacity() const;\n\n  //! @brief Returns the current buffer size\n  //!\n  //! Returns the number of EstimatorState objects currently in the buffer.\n  //!\n  //! @return current buffer size\n  //!\n  unsigned int getSize() const;\n\nprivate:\n  friend std::ostream& operator<<(std::ostream &os, const RobotLocalizationEstimator& rle)\n  {\n    for ( boost::circular_buffer<EstimatorState>::const_iterator it = rle.state_buffer_.begin();\n          it != rle.state_buffer_.end(); ++it )\n    {\n      os << *it << \"\\n\";\n    }\n    return os;\n  }\n\n  //! @brief Extrapolates the given state to a requested time stamp\n  //!\n  //! @param[in] boundary_state - state from which to extrapolate\n  //! @param[in] requested_time - time stamp to extrapolate to\n  //! @param[out] state_at_req_time - predicted state at requested time\n  //!\n  void extrapolate(const EstimatorState& boundary_state,\n                   const double requested_time,\n                   EstimatorState& state_at_req_time) const;\n\n  //! @brief Interpolates the given state to a requested time stamp\n  //!\n  //! @param[in] given_state_1 - last state update before requested time\n  //! @param[in] given_state_2 - next state update after requested time\n  //! @param[in] requested_time - time stamp to extrapolate to\n  //! @param[out] state_at_req_time - predicted state at requested time\n  //!\n  void interpolate(const EstimatorState& given_state_1, const EstimatorState& given_state_2,\n                   const double requested_time, EstimatorState& state_at_req_time) const;\n\n  //!\n  //! @brief The buffer holding the system states that have come in. Interpolation and extrapolation is done starting\n  //! from these states.\n  //!\n  boost::circular_buffer<EstimatorState> state_buffer_;\n\n  //!\n  //! @brief A pointer to the filter instance that is used for extrapolation\n  //!\n  FilterBase* filter_;\n};\n\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_ROBOT_LOCALIZATION_ESTIMATOR_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/ros_filter.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_ROS_FILTER_H\n#define ROBOT_LOCALIZATION_ROS_FILTER_H\n\n#include \"robot_localization/ros_filter_utilities.h\"\n#include \"robot_localization/filter_common.h\"\n#include \"robot_localization/filter_base.h\"\n\n#include <robot_localization/SetPose.h>\n\n#include <ros/ros.h>\n#include <std_msgs/String.h>\n#include <std_srvs/Empty.h>\n#include <nav_msgs/Odometry.h>\n#include <sensor_msgs/Imu.h>\n#include <geometry_msgs/Twist.h>\n#include <geometry_msgs/TwistStamped.h>\n#include <geometry_msgs/TwistWithCovarianceStamped.h>\n#include <geometry_msgs/PoseWithCovarianceStamped.h>\n#include <geometry_msgs/AccelWithCovarianceStamped.h>\n#include <tf2_ros/transform_listener.h>\n#include <tf2_ros/transform_broadcaster.h>\n#include <tf2_ros/message_filter.h>\n#include <tf2/LinearMath/Transform.h>\n#include <message_filters/subscriber.h>\n#include <diagnostic_updater/diagnostic_updater.h>\n#include <diagnostic_updater/publisher.h>\n#include <diagnostic_msgs/DiagnosticStatus.h>\n\n#include <XmlRpcException.h>\n\n#include <Eigen/Dense>\n\n#include <fstream>\n#include <map>\n#include <numeric>\n#include <queue>\n#include <string>\n#include <vector>\n#include <deque>\n\nnamespace RobotLocalization\n{\n\nstruct CallbackData\n{\n  CallbackData(const std::string &topicName,\n               const std::vector<int> &updateVector,\n               const int updateSum,\n               const bool differential,\n               const bool relative,\n               const double rejectionThreshold) :\n    topicName_(topicName),\n    updateVector_(updateVector),\n    updateSum_(updateSum),\n    differential_(differential),\n    relative_(relative),\n    rejectionThreshold_(rejectionThreshold)\n  {\n  }\n\n  std::string topicName_;\n  std::vector<int> updateVector_;\n  int updateSum_;\n  bool differential_;\n  bool relative_;\n  double rejectionThreshold_;\n};\n\ntypedef std::priority_queue<MeasurementPtr, std::vector<MeasurementPtr>, Measurement> MeasurementQueue;\ntypedef std::deque<MeasurementPtr> MeasurementHistoryDeque;\ntypedef std::deque<FilterStatePtr> FilterStateHistoryDeque;\n\ntemplate<class T> class RosFilter\n{\n  public:\n    //! @brief Constructor\n    //!\n    //! The RosFilter constructor makes sure that anyone using\n    //! this template is doing so with the correct object type\n    //!\n    explicit RosFilter(std::vector<double> args = std::vector<double>());\n\n    //! @brief Destructor\n    //!\n    //! Clears out the message filters and topic subscribers.\n    //!\n    ~RosFilter();\n\n    //! @brief Resets the filter to its initial state\n    //!\n    void reset();\n\n    //! @brief Callback method for receiving all acceleration (IMU) messages\n    //! @param[in] msg - The ROS IMU message to take in.\n    //! @param[in] callbackData - Relevant static callback data\n    //! @param[in] targetFrame - The target frame_id into which to transform the data\n    //!\n    void accelerationCallback(const sensor_msgs::Imu::ConstPtr &msg,\n                              const CallbackData &callbackData,\n                              const std::string &targetFrame);\n\n    //! @brief Callback method for receiving non-stamped control input\n    //! @param[in] msg - The ROS twist message to take in\n    //!\n    void controlCallback(const geometry_msgs::Twist::ConstPtr &msg);\n\n    //! @brief Callback method for receiving stamped control input\n    //! @param[in] msg - The ROS stamped twist message to take in\n    //!\n    void controlCallback(const geometry_msgs::TwistStamped::ConstPtr &msg);\n\n    //! @brief Adds a measurement to the queue of measurements to be processed\n    //!\n    //! @param[in] topicName - The name of the measurement source (only used for debugging)\n    //! @param[in] measurement - The measurement to enqueue\n    //! @param[in] measurementCovariance - The covariance of the measurement\n    //! @param[in] updateVector - The boolean vector that specifies which variables to update from this measurement\n    //! @param[in] mahalanobisThresh - Threshold, expressed as a Mahalanobis distance, for outlier rejection\n    //! @param[in] time - The time of arrival (in seconds)\n    //!\n    void enqueueMeasurement(const std::string &topicName,\n                            const Eigen::VectorXd &measurement,\n                            const Eigen::MatrixXd &measurementCovariance,\n                            const std::vector<int> &updateVector,\n                            const double mahalanobisThresh,\n                            const ros::Time &time);\n\n    //! @brief Method for zeroing out 3D variables within measurements\n    //! @param[out] measurement - The measurement whose 3D variables will be zeroed out\n    //! @param[out] measurementCovariance - The covariance of the measurement\n    //! @param[out] updateVector - The boolean update vector of the measurement\n    //!\n    //! If we're in 2D mode, then for every measurement from every sensor, we call this.\n    //! It sets the 3D variables to 0, gives those variables tiny variances, and sets\n    //! their updateVector values to 1.\n    //!\n    void forceTwoD(Eigen::VectorXd &measurement,\n                   Eigen::MatrixXd &measurementCovariance,\n                   std::vector<int> &updateVector);\n\n    //! @brief Retrieves the EKF's output for broadcasting\n    //! @param[out] message - The standard ROS odometry message to be filled\n    //! @return true if the filter is initialized, false otherwise\n    //!\n    bool getFilteredOdometryMessage(nav_msgs::Odometry &message);\n\n    //! @brief Retrieves the EKF's acceleration output for broadcasting\n    //! @param[out] message - The standard ROS acceleration message to be filled\n    //! @return true if the filter is initialized, false otherwise\n    //!\n    bool getFilteredAccelMessage(geometry_msgs::AccelWithCovarianceStamped &message);\n\n    //! @brief Callback method for receiving all IMU messages\n    //! @param[in] msg - The ROS IMU message to take in.\n    //! @param[in] topicName - The topic name for the IMU message (only used for debug output)\n    //! @param[in] poseCallbackData - Relevant static callback data for orientation variables\n    //! @param[in] twistCallbackData - Relevant static callback data for angular velocity variables\n    //! @param[in] accelCallbackData - Relevant static callback data for linear acceleration variables\n    //!\n    //! This method separates out the orientation, angular velocity, and linear acceleration data and\n    //! passed each on to its respective callback.\n    //!\n    void imuCallback(const sensor_msgs::Imu::ConstPtr &msg, const std::string &topicName,\n      const CallbackData &poseCallbackData, const CallbackData &twistCallbackData,\n      const CallbackData &accelCallbackData);\n\n    //! @brief Processes all measurements in the measurement queue, in temporal order\n    //!\n    //! @param[in] currentTime - The time at which to carry out integration (the current time)\n    //!\n    void integrateMeasurements(const ros::Time &currentTime);\n\n    //! @brief Loads all parameters from file\n    //!\n    void loadParams();\n\n    //! @brief Callback method for receiving all odometry messages\n    //! @param[in] msg - The ROS odometry message to take in.\n    //! @param[in] topicName - The topic name for the odometry message (only used for debug output)\n    //! @param[in] poseCallbackData - Relevant static callback data for pose variables\n    //! @param[in] twistCallbackData - Relevant static callback data for twist variables\n    //!\n    //! This method simply separates out the pose and twist data into two new messages, and passes them into their\n    //! respective callbacks\n    //!\n    void odometryCallback(const nav_msgs::Odometry::ConstPtr &msg, const std::string &topicName,\n      const CallbackData &poseCallbackData, const CallbackData &twistCallbackData);\n\n    //! @brief Callback method for receiving all pose messages\n    //! @param[in] msg - The ROS stamped pose with covariance message to take in\n    //! @param[in] callbackData - Relevant static callback data\n    //! @param[in] targetFrame - The target frame_id into which to transform the data\n    //! @param[in] imuData - Whether this data comes from an IMU\n    //!\n    void poseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg,\n                      const CallbackData &callbackData,\n                      const std::string &targetFrame,\n                      const bool imuData);\n\n    //! @brief Main run method\n    //!\n    void run();\n\n    //! @brief Callback method for manually setting/resetting the internal pose estimate\n    //! @param[in] msg - The ROS stamped pose with covariance message to take in\n    //!\n    void setPoseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg);\n\n    //! @brief Service callback for manually setting/resetting the internal pose estimate\n    //!\n    //! @param[in] request - Custom service request with pose information\n    //! @return true if successful, false if not\n    bool setPoseSrvCallback(robot_localization::SetPose::Request& request,\n                            robot_localization::SetPose::Response&);\n\n    //! @brief Service callback for manually enable the filter\n    //! @param[in] request - N/A\n    //! @param[out] response - N/A\n    //! @return boolean true if successful, false if not\n    bool enableFilterSrvCallback(std_srvs::Empty::Request&,\n                                 std_srvs::Empty::Response&);\n\n    //! @brief Callback method for receiving all twist messages\n    //! @param[in] msg - The ROS stamped twist with covariance message to take in.\n    //! @param[in] callbackData - Relevant static callback data\n    //! @param[in] targetFrame - The target frame_id into which to transform the data\n    //!\n    void twistCallback(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg,\n                       const CallbackData &callbackData,\n                       const std::string &targetFrame);\n\n    //! @brief Validates filter outputs for NaNs and Infinite values\n    //! @param[out] message - The standard ROS odometry message to be validated\n    //! @return true if the filter output is valid, false otherwise\n    //!\n    bool validateFilterOutput(const nav_msgs::Odometry &message);\n\n  protected:\n    //! @brief Finds the latest filter state before the given timestamp and makes it the current state again.\n    //!\n    //! This method also inserts all measurements between the older filter timestamp and now into the measurements\n    //! queue.\n    //!\n    //! @param[in] time - The time to which the filter state should revert\n    //! @return True if restoring the filter succeeded. False if not.\n    //!\n    bool revertTo(const double time);\n\n    //! @brief Saves the current filter state in the queue of previous filter states\n    //!\n    //! These measurements will be used in backwards smoothing in the event that older measurements come in.\n    //! @param[in] filter - The filter base object whose state we want to save\n    //!\n    void saveFilterState(FilterBase &filter);\n\n    //! @brief Removes measurements and filter states older than the given cutoff time.\n    //! @param[in] cutoffTime - Measurements and states older than this time will be dropped.\n    //!\n    void clearExpiredHistory(const double cutoffTime);\n\n    //! @brief Adds a diagnostic message to the accumulating map and updates the error level\n    //! @param[in] errLevel - The error level of the diagnostic\n    //! @param[in] topicAndClass - The sensor topic (if relevant) and class of diagnostic\n    //! @param[in] message - Details of the diagnostic\n    //! @param[in] staticDiag - Whether or not this diagnostic information is static\n    //!\n    void addDiagnostic(const int errLevel,\n                       const std::string &topicAndClass,\n                       const std::string &message,\n                       const bool staticDiag);\n\n    //! @brief Aggregates all diagnostics so they can be published\n    //! @param[in] wrapper - The diagnostic status wrapper to update\n    //!\n    void aggregateDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &wrapper);\n\n    //! @brief Utility method for copying covariances from ROS covariance arrays\n    //! to Eigen matrices\n    //!\n    //! This method copies the covariances and also does some data validation, which is\n    //! why it requires more parameters than just the covariance containers.\n    //! @param[in] arr - The source array for the covariance data\n    //! @param[in] covariance - The destination matrix for the covariance data\n    //! @param[in] topicName - The name of the source data topic (for debug purposes)\n    //! @param[in] updateVector - The update vector for the source topic\n    //! @param[in] offset - The \"starting\" location within the array/update vector\n    //! @param[in] dimension - The number of values to copy, starting at the offset\n    //!\n    void copyCovariance(const double *arr,\n                        Eigen::MatrixXd &covariance,\n                        const std::string &topicName,\n                        const std::vector<int> &updateVector,\n                        const size_t offset,\n                        const size_t dimension);\n\n    //! @brief Utility method for copying covariances from Eigen matrices to ROS\n    //! covariance arrays\n    //!\n    //! @param[in] covariance - The source matrix for the covariance data\n    //! @param[in] arr - The destination array\n    //! @param[in] dimension - The number of values to copy\n    //!\n    void copyCovariance(const Eigen::MatrixXd &covariance,\n                        double *arr,\n                        const size_t dimension);\n\n    //! @brief Loads fusion settings from the config file\n    //! @param[in] topicName - The name of the topic for which to load settings\n    //! @return The boolean vector of update settings for each variable for this topic\n    //!\n    std::vector<int> loadUpdateConfig(const std::string &topicName);\n\n    //! @brief Prepares an IMU message's linear acceleration for integration into the filter\n    //! @param[in] msg - The IMU message to prepare\n    //! @param[in] topicName - The name of the topic over which this message was received\n    //! @param[in] targetFrame - The target tf frame\n    //! @param[in] updateVector - The update vector for the data source\n    //! @param[in] measurement - The twist data converted to a measurement\n    //! @param[in] measurementCovariance - The covariance of the converted measurement\n    //!\n    bool prepareAcceleration(const sensor_msgs::Imu::ConstPtr &msg,\n                             const std::string &topicName,\n                             const std::string &targetFrame,\n                             std::vector<int> &updateVector,\n                             Eigen::VectorXd &measurement,\n                             Eigen::MatrixXd &measurementCovariance);\n\n    //! @brief Prepares a pose message for integration into the filter\n    //! @param[in] msg - The pose message to prepare\n    //! @param[in] topicName - The name of the topic over which this message was received\n    //! @param[in] targetFrame - The target tf frame\n    //! @param[in] differential - Whether we're carrying out differential integration\n    //! @param[in] relative - Whether this measurement is processed relative to the first\n    //! @param[in] imuData - Whether this measurement is from an IMU\n    //! @param[in,out] updateVector - The update vector for the data source\n    //! @param[out] measurement - The pose data converted to a measurement\n    //! @param[out] measurementCovariance - The covariance of the converted measurement\n    //! @return true indicates that the measurement was successfully prepared, false otherwise\n    //!\n    bool preparePose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg,\n                     const std::string &topicName,\n                     const std::string &targetFrame,\n                     const bool differential,\n                     const bool relative,\n                     const bool imuData,\n                     std::vector<int> &updateVector,\n                     Eigen::VectorXd &measurement,\n                     Eigen::MatrixXd &measurementCovariance);\n\n    //! @brief Prepares a twist message for integration into the filter\n    //! @param[in] msg - The twist message to prepare\n    //! @param[in] topicName - The name of the topic over which this message was received\n    //! @param[in] targetFrame - The target tf frame\n    //! @param[in,out] updateVector - The update vector for the data source\n    //! @param[out] measurement - The twist data converted to a measurement\n    //! @param[out] measurementCovariance - The covariance of the converted measurement\n    //! @return true indicates that the measurement was successfully prepared, false otherwise\n    //!\n    bool prepareTwist(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg,\n                      const std::string &topicName,\n                      const std::string &targetFrame,\n                      std::vector<int> &updateVector,\n                      Eigen::VectorXd &measurement,\n                      Eigen::MatrixXd &measurementCovariance);\n\n    //! @brief tf frame name for the robot's body frame\n    //!\n    std::string baseLinkFrameId_;\n\n    //! @brief Subscribes to the control input topic\n    //!\n    ros::Subscriber controlSub_;\n\n    //! @brief This object accumulates static diagnostics, e.g., diagnostics relating\n    //! to the configuration parameters.\n    //!\n    //! The values are treated as static and always reported (i.e., this object is never cleared)\n    //!\n    std::map<std::string, std::string> staticDiagnostics_;\n\n    //! @brief This object accumulates dynamic diagnostics, e.g., diagnostics relating\n    //! to sensor data.\n    //!\n    //! The values are considered transient and are cleared at every iteration.\n    //!\n    std::map<std::string, std::string> dynamicDiagnostics_;\n\n    //! @brief Used for outputting debug messages\n    //!\n    std::ofstream debugStream_;\n\n    //! @brief The max (worst) dynamic diagnostic level.\n    //!\n    int dynamicDiagErrorLevel_;\n\n    //! @brief Used for updating the diagnostics\n    //!\n    diagnostic_updater::Updater diagnosticUpdater_;\n\n    //! @brief Our filter (EKF, UKF, etc.)\n    //!\n    T filter_;\n\n    //! @brief The frequency of the run loop\n    //!\n    double frequency_;\n\n    //! @brief The depth of the history we track for smoothing/delayed measurement processing\n    //!\n    //! This is the guaranteed minimum buffer size for which previous states and measurements are kept.\n    //!\n    double historyLength_;\n\n    //! @brief Whether to reset the filters when backwards jump in time is detected\n    //!\n    //! This is usually the case when logs are being used and a jump in the logi\n    //! is done or if a log files restarts from the beginning.\n    //!\n    bool resetOnTimeJump_;\n\n    //! @brief The most recent control input\n    //!\n    Eigen::VectorXd latestControl_;\n\n    //! @brief The time of the most recent control input\n    //!\n    ros::Time latestControlTime_;\n\n    //! @brief Parameter that specifies the how long we wait for a transform to become available.\n    //!\n    ros::Duration tfTimeout_;\n\n    //! @brief Vector to hold our subscribers until they go out of scope\n    //!\n    std::vector<ros::Subscriber> topicSubs_;\n\n    //! @brief Stores the first measurement from each topic for relative measurements\n    //!\n    //! When a given sensor is being integrated in relative mode, its first measurement\n    //! is effectively treated as an offset, and future measurements have this first\n    //! measurement removed before they are fused. This variable stores the initial\n    //! measurements. Note that this is different from using differential mode, as in\n    //! differential mode, pose data is converted to twist data, resulting in boundless\n    //! error growth for the variables being fused. With relative measurements, the\n    //! vehicle will start with a 0 heading and position, but the measurements are still\n    //! fused absolutely.\n    std::map<std::string, tf2::Transform> initialMeasurements_;\n\n    //! @brief Store the last time a message from each topic was received\n    //!\n    //! If we're getting messages rapidly, we may accidentally get\n    //! an older message arriving after a newer one. This variable keeps\n    //! track of the most recent message time for each subscribed message\n    //! topic. We also use it when listening to odometry messages to\n    //! determine if we should be using messages from that topic.\n    //!\n    std::map<std::string, ros::Time> lastMessageTimes_;\n\n    //! @brief Store the last time set pose message was received\n    //!\n    //! If we receive a setPose message to reset the filter, we can get in\n    //! strange situations wherein we process the pose reset, but then even\n    //! after another spin cycle or two, we can get a new message with a time\n    //! stamp that is *older* than the setPose message's time stamp. This means\n    //! we have to check the message's time stamp against the lastSetPoseTime_.\n    ros::Time lastSetPoseTime_;\n\n    //! @brief tf frame name for the robot's map (world-fixed) frame\n    //!\n    std::string mapFrameId_;\n\n    //! @brief We process measurements by queueing them up in\n    //! callbacks and processing them all at once within each\n    //! iteration\n    //!\n    MeasurementQueue measurementQueue_;\n\n    //! @brief Node handle\n    //!\n    ros::NodeHandle nh_;\n\n    //! @brief Local node handle (for params)\n    //!\n    ros::NodeHandle nhLocal_;\n\n    //! @brief tf frame name for the robot's odometry (world-fixed) frame\n    //!\n    std::string odomFrameId_;\n\n    //! @brief Stores the last measurement from a given topic for differential integration\n    //!\n    //! To carry out differential integration, we have to (1) transform\n    //! that into the target frame (probably the frame specified by\n    //! @p odomFrameId_), (2) \"subtract\"  the previous measurement from\n    //! the current measurement, and then (3) transform it again by the previous\n    //! state estimate. This holds the measurements used for step (2).\n    //!\n    std::map<std::string, tf2::Transform> previousMeasurements_;\n\n    //! @brief We also need the previous covariance matrix for differential data\n    //!\n    std::map<std::string, Eigen::MatrixXd> previousMeasurementCovariances_;\n\n    //! @brief By default, the filter predicts and corrects up to the time of the latest measurement. If this is set\n    //! to true, the filter does the same, but then also predicts up to the current time step.\n    //!\n    bool predictToCurrentTime_;\n\n    //! @brief Whether or not we print diagnostic messages to the /diagnostics topic\n    //!\n    bool printDiagnostics_;\n\n    //! @brief If including acceleration for each IMU input, whether or not we remove acceleration due to gravity\n    //!\n    std::map<std::string, bool> removeGravitationalAcc_;\n\n    //! @brief What is the acceleration in Z due to gravity (m/s^2)? Default is +9.80665.\n    //!\n    double gravitationalAcc_;\n\n    //! @brief Subscribes to the set_pose topic (usually published from rviz). Message\n    //! type is geometry_msgs/PoseWithCovarianceStamped.\n    //!\n    ros::Subscriber setPoseSub_;\n\n    //! @brief Service that allows another node to change the current state and recieve a confirmation. Uses\n    //! a custom SetPose service.\n    //!\n    ros::ServiceServer setPoseSrv_;\n\n    //! @brief Whether or not we use smoothing\n    //!\n    bool smoothLaggedData_;\n\n    //! @brief Service that allows another node to enable the filter. Uses a standard Empty service.\n    //!\n    ros::ServiceServer enableFilterSrv_;\n\n    //! @brief Contains the state vector variable names in string format\n    //!\n    std::vector<std::string> stateVariableNames_;\n\n    //! @brief The max (worst) static diagnostic level.\n    //!\n    int staticDiagErrorLevel_;\n\n    //! @brief Transform buffer for managing coordinate transforms\n    //!\n    tf2_ros::Buffer tfBuffer_;\n\n    //! @brief Transform listener for receiving transforms\n    //!\n    tf2_ros::TransformListener tfListener_;\n\n    //! @brief For future (or past) dating the world_frame->base_link_frame transform\n    //!\n    ros::Duration tfTimeOffset_;\n\n    //! @brief Whether or not we're in 2D mode\n    //!\n    //! If this is true, the filter binds all 3D variables (Z,\n    //! roll, pitch, and their respective velocities) to 0 for\n    //! every measurement.\n    //!\n    bool twoDMode_;\n\n    //! @brief Whether or not we use a control term\n    //!\n    bool useControl_;\n\n    //! @brief Start the Filter disabled at startup\n    //!\n    //! If this is true, the filter reads parameters and prepares publishers and subscribes\n    //! but does not integrate new messages into the state vector.\n    //! The filter can be enabled later using a service.\n    bool disabledAtStartup_;\n\n    //! @brief Whether the filter is enabled or not. See disabledAtStartup_.\n    bool enabled_;\n\n    //! @brief Message that contains our latest transform (i.e., state)\n    //!\n    //! We use the vehicle's latest state in a number of places, and often\n    //! use it as a transform, so this is the most convenient variable to\n    //! use as our global \"current state\" object\n    //!\n    geometry_msgs::TransformStamped worldBaseLinkTransMsg_;\n\n    //! @brief tf frame name that is the parent frame of the transform that this node will calculate and broadcast.\n    //!\n    std::string worldFrameId_;\n\n    //! @brief Whether we publish the transform from the world_frame to the base_link_frame\n    //!\n    bool publishTransform_;\n\n    //! @brief Whether we publish the acceleration\n    //!\n    bool publishAcceleration_;\n\n    //! @brief An implicitly time ordered queue of past filter states used for smoothing.\n    //\n    // front() refers to the filter state with the earliest timestamp.\n    // back() refers to the filter state with the latest timestamp.\n    FilterStateHistoryDeque filterStateHistory_;\n\n    //! @brief A deque of previous measurements which is implicitly ordered from earliest to latest measurement.\n    // when popped from the measurement priority queue.\n    // front() refers to the measurement with the earliest timestamp.\n    // back() refers to the measurement with the latest timestamp.\n    MeasurementHistoryDeque measurementHistory_;\n};\n\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_ROS_FILTER_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/ros_filter_types.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H\n#define ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H\n\n#include \"robot_localization/ros_filter.h\"\n#include \"robot_localization/ekf.h\"\n#include \"robot_localization/ukf.h\"\n\nnamespace RobotLocalization\n{\n\ntypedef RosFilter<Ekf> RosEkf;\ntypedef RosFilter<Ukf> RosUkf;\n\n}\n\n#endif  // ROBOT_LOCALIZATION_ROS_FILTER_TYPES_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/ros_filter_utilities.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H\n#define ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H\n\n#include <tf2/LinearMath/Quaternion.h>\n#include <tf2/LinearMath/Transform.h>\n#include <tf2_ros/buffer.h>\n\n#include <Eigen/Dense>\n\n#include <iomanip>\n#include <iostream>\n#include <string>\n#include <vector>\n\n#define RF_DEBUG(msg) if (filter_.getDebug()) { debugStream_ << msg; }\n\n// Handy methods for debug output\nstd::ostream& operator<<(std::ostream& os, const tf2::Vector3 &vec);\nstd::ostream& operator<<(std::ostream& os, const tf2::Quaternion &quat);\nstd::ostream& operator<<(std::ostream& os, const tf2::Transform &trans);\nstd::ostream& operator<<(std::ostream& os, const std::vector<double> &vec);\n\nnamespace RobotLocalization\n{\nnamespace RosFilterUtilities\n{\n\ndouble getYaw(const tf2::Quaternion quat);\n\n//! @brief Method for safely obtaining transforms.\n//! @param[in] buffer - tf buffer object to use for looking up the transform\n//! @param[in] targetFrame - The target frame of the desired transform\n//! @param[in] sourceFrame - The source frame of the desired transform\n//! @param[in] time - The time at which we want the transform\n//! @param[in] timeout - How long to block before falling back to last transform\n//! @param[out] targetFrameTrans - The resulting transform object\n//! @param[in] silent - Whether or not to print transform warnings\n//! @return Sets the value of @p targetFrameTrans and returns true if successful,\n//! false otherwise.\n//!\n//! This method attempts to obtain a transform from the @p sourceFrame to the @p\n//! targetFrame at the specific @p time. If no transform is available at that time,\n//! it attempts to simply obtain the latest transform. If that still fails, then the\n//! method checks to see if the transform is going from a given frame_id to itself.\n//! If any of these checks succeed, the method sets the value of @p targetFrameTrans\n//! and returns true, otherwise it returns false.\n//!\nbool lookupTransformSafe(const tf2_ros::Buffer &buffer,\n                         const std::string &targetFrame,\n                         const std::string &sourceFrame,\n                         const ros::Time &time,\n                         const ros::Duration &timeout,\n                         tf2::Transform &targetFrameTrans,\n                         const bool silent = false);\n\n//! @brief Method for safely obtaining transforms.\n//! @param[in] buffer - tf buffer object to use for looking up the transform\n//! @param[in] targetFrame - The target frame of the desired transform\n//! @param[in] sourceFrame - The source frame of the desired transform\n//! @param[in] time - The time at which we want the transform\n//! @param[out] targetFrameTrans - The resulting transform object\n//! @param[in] silent - Whether or not to print transform warnings\n//! @return Sets the value of @p targetFrameTrans and returns true if successful,\n//! false otherwise.\n//!\n//! This method attempts to obtain a transform from the @p sourceFrame to the @p\n//! targetFrame at the specific @p time. If no transform is available at that time,\n//! it attempts to simply obtain the latest transform. If that still fails, then the\n//! method checks to see if the transform is going from a given frame_id to itself.\n//! If any of these checks succeed, the method sets the value of @p targetFrameTrans\n//! and returns true, otherwise it returns false.\n//!\nbool lookupTransformSafe(const tf2_ros::Buffer &buffer,\n                         const std::string &targetFrame,\n                         const std::string &sourceFrame,\n                         const ros::Time &time,\n                         tf2::Transform &targetFrameTrans,\n                         const bool silent = false);\n\n//! @brief Utility method for converting quaternion to RPY\n//! @param[in] quat - The quaternion to convert\n//! @param[out] roll - The converted roll\n//! @param[out] pitch - The converted pitch\n//! @param[out] yaw - The converted yaw\n//!\nvoid quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw);\n\n//! @brief Converts our Eigen state vector into a TF transform/pose\n//! @param[in] state - The state to convert\n//! @param[out] stateTF - The converted state\n//!\nvoid stateToTF(const Eigen::VectorXd &state, tf2::Transform &stateTF);\n\n//! @brief Converts a TF transform/pose into our Eigen state vector\n//! @param[in] stateTF - The state to convert\n//! @param[out] state - The converted state\n//!\nvoid TFtoState(const tf2::Transform &stateTF, Eigen::VectorXd &state);\n\n}  // namespace RosFilterUtilities\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_ROS_FILTER_UTILITIES_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/ros_robot_localization_listener.h",
    "content": "/*\n * Copyright (c) 2016, TNO IVS Helmond.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H\n#define ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H\n\n#include \"robot_localization/robot_localization_estimator.h\"\n\n#include <string>\n\n#include <ros/ros.h>\n#include <message_filters/subscriber.h>\n#include <message_filters/time_synchronizer.h>\n#include <nav_msgs/Odometry.h>\n#include <geometry_msgs/AccelWithCovarianceStamped.h>\n#include <tf2_ros/transform_listener.h>\n\nnamespace RobotLocalization\n{\n\n//! @brief RosRobotLocalizationListener class\n//!\n//! This class wraps the RobotLocalizationEstimator. It listens to topics over which the (filtered) robot state is\n//! published (odom and accel) and pushes them into its instance of the RobotLocalizationEstimator. It exposes a\n//! getState method to offer the user the estimated state at a requested time. This class offers the option to run this\n//! listener without the need to run a separate node. If you do wish to run this functionality in a separate node,\n//! consider the robot localization listener node.\n//!\nclass RosRobotLocalizationListener\n{\npublic:\n  //! @brief Constructor\n  //!\n  //! The RosRobotLocalizationListener constructor initializes nodehandles, subscribers, a filter for synchronized\n  //! listening to the topics it subscribes to, and an instance of the RobotLocalizationEstimator.\n  //!\n  explicit RosRobotLocalizationListener();\n\n  //! @brief Destructor\n  //!\n  //! Empty destructor\n  //!\n  ~RosRobotLocalizationListener();\n\n  //! @brief Get a state from the localization estimator\n  //!\n  //! Requests the predicted state and covariance at a given time from the Robot Localization Estimator.\n  //!\n  //! @param[in] time - time of the requested state\n  //! @param[in] frame_id - frame id of which the state is requested.\n  //! @param[out] state - state at the requested time\n  //! @param[out] covariance - covariance at the requested time\n  //!\n  //! @return false if buffer is empty, true otherwise\n  //!\n  bool getState(const double time, const std::string& frame_id,\n                Eigen::VectorXd& state, Eigen::MatrixXd& covariance,\n                std::string world_frame_id = \"\") const;\n\n  //! @brief Get a state from the localization estimator\n  //!\n  //! Overload of getState method for using ros::Time.\n  //!\n  //! @param[in] ros_time - ros time of the requested state\n  //! @param[in] frame_id - frame id of which the state is requested.\n  //! @param[out] state - state at the requested time\n  //! @param[out] covariance - covariance at the requested time\n  //!\n  //! @return false if buffer is empty, true otherwise\n  //!\n  bool getState(const ros::Time& ros_time, const std::string& frame_id,\n                Eigen::VectorXd& state, Eigen::MatrixXd& covariance,\n                const std::string& world_frame_id = \"\") const;\n\n  //!\n  //! \\brief getBaseFrameId Returns the base frame id of the localization listener\n  //! \\return The base frame id\n  //!\n  const std::string& getBaseFrameId() const;\n\n  //!\n  //! \\brief getWorldFrameId Returns the world frame id of the localization listener\n  //! \\return The world frame id\n  //!\n  const std::string& getWorldFrameId() const;\n\nprivate:\n  //! @brief Callback for odom and accel\n  //!\n  //! Puts the information from the odom and accel messages in a Robot Localization Estimator state and sets the most\n  //! recent state of the estimator.\n  //!\n  //! @param[in] odometry message\n  //! @param[in] accel message\n  //!\n  void odomAndAccelCallback(const nav_msgs::Odometry& odom, const geometry_msgs::AccelWithCovarianceStamped& accel);\n\n  //! @brief The core state estimator that facilitates inter- and\n  //! extrapolation between buffered states.\n  //!\n  RobotLocalizationEstimator* estimator_;\n\n  //! @brief A public handle to the ROS node\n  //!\n  ros::NodeHandle nh_;\n\n  //! @brief A private handle to the ROS node\n  //!\n  ros::NodeHandle nh_p_;\n\n  //! @brief Subscriber to the odometry state topic (output of a filter node)\n  //!\n  message_filters::Subscriber<nav_msgs::Odometry> odom_sub_;\n\n  //! @brief Subscriber to the acceleration state topic (output of a filter node)\n  //!\n  message_filters::Subscriber<geometry_msgs::AccelWithCovarianceStamped> accel_sub_;\n\n  //! @brief Waits for both an Odometry and an Accel message before calling a single callback function\n  //!\n  message_filters::TimeSynchronizer<nav_msgs::Odometry, geometry_msgs::AccelWithCovarianceStamped> sync_;\n\n  //! @brief Child frame id received from the Odometry message\n  //!\n  std::string base_frame_id_;\n\n  //! @brief Frame id received from the odometry message\n  //!\n  std::string world_frame_id_;\n\n  //! @brief Tf buffer for looking up transforms\n  //!\n  tf2_ros::Buffer tf_buffer_;\n\n  //! @brief Transform listener to fill the tf_buffer\n  //!\n  tf2_ros::TransformListener tf_listener_;\n};\n\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_ROS_ROBOT_LOCALIZATION_LISTENER_H\n"
  },
  {
    "path": "src/robot_localization/include/robot_localization/ukf.h",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#ifndef ROBOT_LOCALIZATION_UKF_H\n#define ROBOT_LOCALIZATION_UKF_H\n\n#include \"robot_localization/filter_base.h\"\n\n#include <fstream>\n#include <vector>\n#include <set>\n#include <queue>\n\nnamespace RobotLocalization\n{\n\n//! @brief Unscented Kalman filter class\n//!\n//! Implementation of an unscenter Kalman filter (UKF). This\n//! class derives from FilterBase and overrides the predict()\n//! and correct() methods in keeping with the discrete time\n//! UKF algorithm. The algorithm was derived from the UKF\n//! Wikipedia article at\n//! (http://en.wikipedia.org/wiki/Kalman_filter#Unscented_Kalman_filter)\n//! ...and this paper:\n//! J. J. LaViola, Jr., “A comparison of unscented and extended Kalman\n//! filtering for estimating quaternion motion,” in Proc. American Control\n//! Conf., Denver, CO, June 4–6, 2003, pp. 2435–2440\n//! Obtained here: http://www.cs.ucf.edu/~jjl/pubs/laviola_acc2003.pdf\n//!\nclass Ukf: public FilterBase\n{\n  public:\n    //! @brief Constructor for the Ukf class\n    //!\n    //! @param[in] args - Generic argument container. It is assumed\n    //! that args[0] constains the alpha parameter, args[1] contains\n    //! the kappa parameter, and args[2] contains the beta parameter.\n    //!\n    explicit Ukf(std::vector<double> args);\n\n    //! @brief Destructor for the Ukf class\n    //!\n    ~Ukf();\n\n    //! @brief Carries out the correct step in the predict/update cycle.\n    //!\n    //! @param[in] measurement - The measurement to fuse with our estimate\n    //!\n    void correct(const Measurement &measurement);\n\n    //! @brief Carries out the predict step in the predict/update cycle.\n    //!\n    //! Projects the state and error matrices forward using a model of\n    //! the vehicle's motion.\n    //!\n    //! @param[in] referenceTime - The time at which the prediction is being made\n    //! @param[in] delta - The time step over which to predict.\n    //!\n    void predict(const double referenceTime, const double delta);\n\n  protected:\n    //! @brief The UKF sigma points\n    //!\n    //! Used to sample possible next states during prediction.\n    //!\n    std::vector<Eigen::VectorXd> sigmaPoints_;\n\n    //! @brief This matrix is used to generate the sigmaPoints_\n    //!\n    Eigen::MatrixXd weightedCovarSqrt_;\n\n    //! @brief The weights associated with each sigma point when generating\n    //! a new state\n    //!\n    std::vector<double> stateWeights_;\n\n    //! @brief The weights associated with each sigma point when calculating\n    //! a predicted estimateErrorCovariance_\n    //!\n    std::vector<double> covarWeights_;\n\n    //! @brief Used in weight generation for the sigma points\n    //!\n    double lambda_;\n\n    //! @brief Used to determine if we need to re-compute the sigma\n    //! points when carrying out multiple corrections\n    //!\n    bool uncorrected_;\n};\n\n}  // namespace RobotLocalization\n\n#endif  // ROBOT_LOCALIZATION_UKF_H\n"
  },
  {
    "path": "src/robot_localization/launch/dual_ekf_navsat_example.launch",
    "content": "<!--\n     This launch file provides an example of how to work with GPS data using robot_localization. It runs three nodes:\n       (1) An EKF instance that fuses odometry and IMU data and outputs an odom-frame state estimate\n       (2) A second EKF instance that fuses the same data, but also fuses the transformed GPS data from (3)\n       (3) An instance of navsat_transform_node, which takes in GPS data and produces pose data that has been\n           transformed into your robot's world frame (here, map). The node produces a map-frame state estimate.\n\n       The first EKF instance produces the odom->base_link transform. The second EKF produces the map->odom transform,\n       but requires the odom->base_link transform from the first instance in order to do so. See the\n       params/dual_ekf_navsat_example.yaml file for parameter specification.\n-->\n\n<launch>\n\n  <rosparam command=\"load\" file=\"$(find robot_localization)/params/dual_ekf_navsat_example.yaml\" />\n\n  <node pkg=\"robot_localization\" type=\"ekf_localization_node\" name=\"ekf_se_odom\" clear_params=\"true\"/>\n\n  <node pkg=\"robot_localization\" type=\"ekf_localization_node\" name=\"ekf_se_map\" clear_params=\"true\">\n    <remap from=\"odometry/filtered\" to=\"odometry/filtered_map\"/>\n  </node>\n\n  <node pkg=\"robot_localization\" type=\"navsat_transform_node\" name=\"navsat_transform\" clear_params=\"true\">\n    <remap from=\"odometry/filtered\" to=\"odometry/filtered_map\"/>\n  </node>\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/launch/ekf_template.launch",
    "content": "<launch>\n  <node pkg=\"robot_localization\" type=\"ekf_localization_node\" name=\"ekf_se\" clear_params=\"true\">\n    <rosparam command=\"load\" file=\"$(find robot_localization)/params/ekf_template.yaml\" />\n\n   <!--  Placeholder for output topic remapping\n    <remap from=\"odometry/filtered\" to=\"\"/>\n    <remap from=\"accel/filtered\" to=\"\"/>\n    -->\n\n  </node>\n</launch>\n"
  },
  {
    "path": "src/robot_localization/launch/navsat_transform_template.launch",
    "content": "<!--\n     This node needs to know the values of three variables in order to function:\n\n     (1) A world-referenced heading (yaw). The node assumes an ENU standard for heading, with 0 facing east, though it\n         can support any heading.\n     (2) Odometry data that gives the robot's current pose in its own world coordinate frame (typically map or odom)\n     (3) A latitude/longitude/altitude.\n\n     These three items allow us to compute a transform from the global frame to your robot's local frame. There are\n     several means of providing them, though keep in mind that these modes are typically mutually exclusive.\n     (1) World-referenced yaw can be provided by:\n           (a) an IMU in a sensor_msgs/Imu message (topic is /imu/data/)\n           (b) the heading in the nav_msgs/Odometry message in (2) below can be used. To enable this behavior, set the\n               use_odometry_yaw parameter to true, and set the delay parameter to some small value (~3 seconds). Be\n               careful, though: this heading must still be globally referenced, so if your state estimation node always\n               starts with a 0 heading, you CAN NOT use this option.\n           (c) the \"datum\" service. See the template parameter file (params/navsat_transform_template.yaml).\n     (2) The odometry data, which needs to have a valid frame_id, can be provided by:\n           (a) a nav_msgs/Odometry message from your robot_localization state estimation node.\n           (b) the \"datum\" service (all odometry variables are assumed to be 0 in this case). See the template\n               parameter file.\n     (3) The latitude, longitude, and altitude can be provided by:\n           (a) a sensor_msgs/NavSatFix message\n           (b) the \"datum\" service. See the template parameter file.\n     (4) Alternatively, at any time, the user can send a robot_localization/SetDatum service message to the \"datum\"\n         service. This will manually set the latitude, longitude, altitude, and world-referenced heading, and will\n         assume an odometry message containing all zeros. This will effectively set the origin at the specified\n         lat/long, with the X-axis aligned with east. The user can set this datum via the \"datum\" service, or via the\n         launch file. If the wait_for_datum parameter is set to true, then the node will attempt to use the datum\n         parameter. If the parameter is not set, it will wait until it receives a service call.\n\n     The output of this node is an odometry message that contains the GPS data transformed into the robot's world\n     coordinate frame (i.e., the frame specified by input (2)'s frame_id), or the coordinate frame defined by the\n     message sent to the \"datum\" service. Optionally, the node can also produce a NavSatFix message corresponding\n     to the filtered odometry, transformed back into lat/long coordinates. The node can also optionally publish the\n     transform from the UTM frame the the world frame.\n-->\n\n<launch>\n  <node pkg=\"robot_localization\" type=\"navsat_transform_node\" name=\"navsat_transform_node\" clear_params=\"true\">\n    <rosparam command=\"load\" file=\"$(find robot_localization)/params/navsat_transform_template.yaml\" />\n\n      <!-- Placeholders for input remapping. Set your topic names as the \"to\" values.\n      <remap from=\"imu/data\" to=\"\"/>\n      <remap from=\"odometry/filtered\" to=\"\"/>\n      <remap from=\"gps/fix\" to=\"\"/>\n      -->\n\n  </node>\n</launch>\n\n"
  },
  {
    "path": "src/robot_localization/launch/ukf_template.launch",
    "content": "<launch>\n  <node pkg=\"robot_localization\" type=\"ukf_localization_node\" name=\"ukf_se\" clear_params=\"true\">\n    <rosparam command=\"load\" file=\"$(find robot_localization)/params/ukf_template.yaml\" />\n\n    <!--  Placeholder for output topic remapping\n    <remap from=\"odometry/filtered\" to=\"\"/>\n    <remap from=\"accel/filtered\" to=\"\"/>\n    -->\n\n  </node>\n</launch>\n"
  },
  {
    "path": "src/robot_localization/package.xml",
    "content": "<?xml version=\"1.0\"?>\n<package format=\"2\">\n  <name>robot_localization</name>\n  <version>2.4.3</version>\n  <description>Provides nonlinear state estimation through sensor fusion of an abritrary number of sensors.</description>\n\n  <maintainer email=\"ayrton04@gmail.com\">Tom Moore</maintainer>\n\n  <license>BSD</license>\n\n  <url type=\"website\">http://ros.org/wiki/robot_localization</url>\n\n  <author email=\"ayrton04@gmail.com\">Tom Moore</author> \n\n  <buildtool_depend>catkin</buildtool_depend>\n\n  <depend>cmake_modules</depend>\n  <depend>diagnostic_msgs</depend>\n  <depend>diagnostic_updater</depend>\n  <depend>eigen</depend>\n  <depend>eigen_conversions</depend>\n  <depend>geographic_msgs</depend>\n  <depend>geometry_msgs</depend>\n  <depend>message_filters</depend>\n  <depend>nav_msgs</depend>\n  <depend>roscpp</depend>\n  <depend>sensor_msgs</depend>\n  <depend>std_msgs</depend>\n  <depend>std_srvs</depend>\n  <depend>tf2</depend>\n  <depend>tf2_geometry_msgs</depend>\n  <depend>tf2_ros</depend>\n  <depend>xmlrpcpp</depend>\n  <depend>yaml-cpp</depend>\n\n  <build_depend>message_generation</build_depend>\n  <build_depend>python-catkin-pkg</build_depend>\n  <build_depend>roslint</build_depend>\n\n  <exec_depend>message_runtime</exec_depend>\n\n  <test_depend>rosbag</test_depend>\n  <test_depend>rostest</test_depend>\n  <test_depend>rosunit</test_depend>\n\n  <export>\n    <rosdoc config=\"rosdoc.yaml\" />\n  </export>\n\n</package>\n"
  },
  {
    "path": "src/robot_localization/params/dual_ekf_navsat_example.yaml",
    "content": "# For parameter descriptions, please refer to the template parameter files for each node.\n\nekf_se_odom:\n  frequency: 30\n  sensor_timeout: 0.1\n  two_d_mode: false\n  transform_time_offset: 0.0\n  transform_timeout: 0.0\n  print_diagnostics: true\n  debug: false\n\n  map_frame: map\n  odom_frame: odom\n  base_link_frame: base_link\n  world_frame: odom\n\n  odom0: odometry/wheel\n  odom0_config: [false, false, false,\n                 false, false, false,\n                 true,  true,  true,\n                 false, false, true,\n                 false, false, false]\n  odom0_queue_size: 10\n  odom0_nodelay: true\n  odom0_differential: false\n  odom0_relative: false\n\n  imu0: imu/data\n  imu0_config: [false, false, false,\n                true,  true,  false,\n                false, false, false,\n                true,  true,  true,\n                true,  true,  true]\n  imu0_nodelay: false\n  imu0_differential: false\n  imu0_relative: false\n  imu0_queue_size: 10\n  imu0_remove_gravitational_acceleration: true\n\n  use_control: false\n\n  process_noise_covariance: [1e-3, 0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    1e-3, 0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    1e-3, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0.3,  0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0.3,  0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0.01, 0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0.5,   0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0.5,   0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0.1,  0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0.3,  0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.3,  0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.3,  0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.3,  0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.3,  0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.3]\n\n  initial_estimate_covariance: [1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    1.0,  0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    1.0,  0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    1.0,  0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    1.0,  0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    1.0,  0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    1.0,   0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1.0,   0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1.0,   0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1.0,  0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1.0,  0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1.0]\n\nekf_se_map:\n  frequency: 30\n  sensor_timeout: 0.1\n  two_d_mode: false\n  transform_time_offset: 0.0\n  transform_timeout: 0.0\n  print_diagnostics: true\n  debug: false\n\n  map_frame: map\n  odom_frame: odom\n  base_link_frame: base_link\n  world_frame: map\n\n  odom0: odometry/wheel\n  odom0_config: [false, false, false,\n                 false, false, false,\n                 true,  true,  true,\n                 false, false, true,\n                 false, false, false]\n  odom0_queue_size: 10\n  odom0_nodelay: true\n  odom0_differential: false\n  odom0_relative: false\n\n  odom1: odometry/gps\n  odom1_config: [true,  true,  false,\n                 false, false, false,\n                 false, false, false,\n                 false, false, false,\n                 false, false, false]\n  odom1_queue_size: 10\n  odom1_nodelay: true\n  odom1_differential: false\n  odom1_relative: false\n\n  imu0: imu/data\n  imu0_config: [false, false, false,\n                true,  true,  false,\n                false, false, false,\n                true,  true,  true,\n                true,  true,  true]\n  imu0_nodelay: true\n  imu0_differential: false\n  imu0_relative: false\n  imu0_queue_size: 10\n  imu0_remove_gravitational_acceleration: true\n\n  use_control: false\n\n  process_noise_covariance: [1.0,  0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    1.0,  0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    1e-3, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0.3,  0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0.3,  0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0.01, 0,     0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0.5,   0,     0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0.5,   0,    0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0.1,  0,    0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0.3,  0,    0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.3,  0,    0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.3,  0,    0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.3,  0,    0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.3,  0,\n                             0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.3]\n\n  initial_estimate_covariance: [1.0,  0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    1.0,  0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    1.0,  0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    1.0,  0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    1.0,  0,    0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    1.0,  0,    0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    1.0,  0,     0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    1.0,   0,     0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1.0,   0,     0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1.0,   0,    0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1.0,  0,    0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1.0,  0,\n                                0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1.0]\n\nnavsat_transform:\n  frequency: 30\n  delay: 3.0\n  magnetic_declination_radians: 0.0429351  # For lat/long 55.944831, -3.186998\n  yaw_offset: 1.570796327  # IMU reads 0 facing magnetic north, not east\n  zero_altitude: false\n  broadcast_utm_transform: true\n  publish_filtered_gps: true\n  use_odometry_yaw: false\n  wait_for_datum: false\n\n"
  },
  {
    "path": "src/robot_localization/params/ekf_template.yaml",
    "content": "# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin\n# computation until it receives at least one message from one of the inputs. It will then run continuously at the\n# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified.\nfrequency: 30\n\n# The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict\n# cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the\n# filter will generate new output. Defaults to 1 / frequency if not specified.\nsensor_timeout: 0.1\n\n# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is\n# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar\n# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected\n# by, for example, an IMU. Defaults to false if unspecified.\ntwo_d_mode: false\n\n# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for\n# future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if\n# unspecified.\ntransform_time_offset: 0.0\n\n# Use this parameter to provide specify how long the tf listener should wait for a transform to become available. \n# Defaults to 0.0 if unspecified.\ntransform_timeout: 0.0\n\n# If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is\n# unhappy with any settings or data.\nprint_diagnostics: true\n\n# Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by\n# debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious\n# effects on the performance of the node. Defaults to false if unspecified.\ndebug: false\n\n# Defaults to \"robot_localization_debug.txt\" if unspecified. Please specify the full path.\ndebug_out_file: /path/to/debug/file.txt\n\n# Whether to broadcast the transformation over the /tf topic. Defaults to true if unspecified.\npublish_tf: true\n\n# Whether to publish the acceleration state. Defaults to false if unspecified.\npublish_acceleration: false\n\n# REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and\n# earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames.\n# The robot's position in the odom frame will drift over time, but is accurate in the short term and should be\n# continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom\n# frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your\n# robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based\n# localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame.\n# ekf_localization_node and ukf_localization_node are not concerned with the earth frame.\n# Here is how to use the following settings:\n# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.\n#     1a. If your system does not have a map_frame, just remove it, and make sure \"world_frame\" is set to the value of\n#         odom_frame.\n# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set\n#   \"world_frame\" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes.\n# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates\n# from landmark observations) then:\n#     3a. Set your \"world_frame\" to your map_frame value\n#     3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state\n#         estimation node from robot_localization! However, that instance should *not* fuse the global data.\nmap_frame: map              # Defaults to \"map\" if unspecified\nodom_frame: odom            # Defaults to \"odom\" if unspecified\nbase_link_frame: base_link  # Defaults to \"base_link\" if unspecified\nworld_frame: odom           # Defaults to the value of odom_frame if unspecified\n\n# The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry,\n# geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped,\n# sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its \"base\" name, e.g., odom0,\n# odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no\n# default values, and must be specified.\nodom0: example/odom\n\n# Each sensor reading updates some or all of the filter's state. These options give you greater control over which\n# values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only\n# want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the\n# values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types\n# do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message\n# has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false\n# if unspecified, effectively making this parameter required for each sensor.\nodom0_config: [true,  true,  false,\n               false, false, false,\n               false, false, false,\n               false, false, true,\n               false, false, false]\n\n# If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase\n# the size of the subscription queue so that more measurements are fused.\nodom0_queue_size: 2\n\n# [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result\n# of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's\n# algorithm.\nodom0_nodelay: false\n\n# [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under-\n# report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they\n# arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also\n# measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't\n# always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose\n# data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then\n# integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true\n# for twist measurements has no effect.\nodom0_differential: false\n\n# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a \"zero point\"\n# for all future measurements. While you can achieve the same effect with the differential paremeter, the key\n# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before\n# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true.\nodom0_relative: false\n\n# [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to\n# control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to\n# numeric_limits<double>::max() if unspecified. It is strongly recommended that these parameters be removed if not\n# required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation.\n# For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying\n# the thresholds.\nodom0_pose_rejection_threshold: 5\nodom0_twist_rejection_threshold: 1\n\n# Further input parameter examples\nodom1: example/another_odom\nodom1_config: [false, false, true,\n               false, false, false,\n               false, false, false,\n               false, false, true,\n               false, false, false]\nodom1_differential: false\nodom1_relative: true\nodom1_queue_size: 2\nodom1_pose_rejection_threshold: 2\nodom1_twist_rejection_threshold: 0.2\nodom1_nodelay: false\n\npose0: example/pose\npose0_config: [true,  true,  false,\n               false, false, false,\n               false, false, false,\n               false, false, false,\n               false, false, false]\npose0_differential: true\npose0_relative: false\npose0_queue_size: 5\npose0_rejection_threshold: 2  # Note the difference in parameter name\npose0_nodelay: false\n\ntwist0: example/twist\ntwist0_config: [false, false, false,\n                false, false, false,\n                true,  true,  true,\n                false, false, false,\n                false, false, false]\ntwist0_queue_size: 3\ntwist0_rejection_threshold: 2\ntwist0_nodelay: false\n\nimu0: example/imu\nimu0_config: [false, false, false,\n              true,  true,  true,\n              false, false, false,\n              true,  true,  true,\n              true,  true,  true]\nimu0_nodelay: false\nimu0_differential: false\nimu0_relative: true\nimu0_queue_size: 5\nimu0_pose_rejection_threshold: 0.8                 # Note the difference in parameter names\nimu0_twist_rejection_threshold: 0.8                #\nimu0_linear_acceleration_rejection_threshold: 0.8  #\n\n# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set\n# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame.\nimu0_remove_gravitational_acceleration: true\n\n# [ADVANCED]  The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no\n# acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During\n# correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be\n# problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When\n# this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially\n# noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance\n# for the velocity variable in question, or decrease the  variance of the variable in question in the measurement\n# itself. In addition, users can also take advantage of the control command being issued to the robot at the time we\n# make the prediction. If control is used, it will get converted into an acceleration term, which will be used during\n# predicition. Note that if an acceleration measurement for the variable in question is available from one of the\n# inputs, the control term will be ignored.\n# Whether or not we use the control input during predicition. Defaults to false.\nuse_control: true\n# Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to\n# false.\nstamped_control: false\n# The last issued control command will be used in prediction for this period. Defaults to 0.2.\ncontrol_timeout: 0.2\n# Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw.\ncontrol_config: [true, false, false, false, false, true]\n# Places limits on how large the acceleration term will be. Should match your robot's kinematics.\nacceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4]\n# Acceleration and deceleration limits are not always the same for robots.\ndeceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5]\n# If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these\n# gains\nacceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9]\n# If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these\n# gains\ndeceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0]\n\n# [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is\n# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each\n# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be.\n# However, if users find that a given variable is slow to converge, one approach is to increase the\n# process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error\n# to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are\n# ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if\n# unspecified.\nprocess_noise_covariance: [0.05, 0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0.05, 0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0.06, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0.03, 0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0.03, 0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0.06, 0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0.025, 0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0.025, 0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0.04, 0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0.01, 0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.01, 0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.02, 0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.01, 0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.01, 0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.015]\n\n# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal\n# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in\n# question. Users should take care not to use large values for variables that will not be measured directly. The values\n# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below\n#if unspecified.\ninitial_estimate_covariance: [1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    1e-9, 0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    1e-9, 0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    1e-9, 0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    1e-9,  0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1e-9,  0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1e-9,  0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1e-9, 0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1e-9, 0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1e-9]\n\n"
  },
  {
    "path": "src/robot_localization/params/navsat_transform_template.yaml",
    "content": "# Frequency of the main run loop\nfrequency: 30\n\n# Delay time, in seconds, before we calculate the transform from the UTM frame to your world frame. This is especially\n# important if you have use_odometry_yaw set to true. Defaults to 0.\ndelay: 3.0\n\n# PLEASE READ: Like all nodes in robot_localization, this node assumes that your IMU data is reported in the ENU frame.\n# Many IMUs report data in the NED frame, so you'll want to verify that your data is in the correct frame before using\n# it. \n\n# If your IMU does not account for magnetic declination, enter the value for your location here. If you don't know it,\n# see http://www.ngdc.noaa.gov/geomag-web/ (make sure to convert the value to radians). This parameter is mandatory.\nmagnetic_declination_radians: 0\n\n# Your IMU's yaw, once the magentic_declination_radians value is added to it, should report 0 when facing east. If it\n# doesn't, enter the offset here. Defaults to 0.\nyaw_offset: 0.0\n\n# If this is true, the altitude is set to 0 in the output odometry message. Defaults to false.\nzero_altitude: false\n\n# If this is true, the transform world_frame->utm transform is broadcast for use by other nodes. Defaults to false.\nbroadcast_utm_transform: false\n\n# If this is true, the utm->world_frame transform will be published instead of the world_frame->utm transform. \n# Note that broadcast_utm_transform still has to be enabled. Defaults to false.\nbroadcast_utm_transform_as_parent_frame: false\n\n# If this is true, all received odometry data is converted back to a lat/lon and published as a NavSatFix message as\n# /gps/filtered. Defaults to false.\npublish_filtered_gps: false\n\n# If this is true, the node ignores the IMU data and gets its heading from the odometry source (typically the\n# /odometry/filtered topic coming from one of robot_localization's state estimation nodes). BE CAREFUL when using this!\n# The yaw value in your odometry source *must* be world-referenced, e.g., you cannot use your odometry source for yaw\n# if your yaw data is based purely on integrated velocities. Defaults to false.\nuse_odometry_yaw: false\n\n# If true, will retrieve the datum from the 'datum' parameter below, if available. If no 'datum' parameter exists,\n# navsat_transform_node will wait until the user calls the 'datum' service with the SetDatum service message.\nwait_for_datum: false\n\n# Instead of using the first GPS location and IMU-based heading for the local-frame origin, users can specify the\n# origin (datum) using this parameter. The fields in the parameter represent latitude and longitude in decimal degrees,\n# and heading in radians. As navsat_transform_node assumes an ENU standard, a 0 heading corresponds to east.\ndatum: [55.944904, -3.186693, 0.0]\n\n"
  },
  {
    "path": "src/robot_localization/params/ukf_template.yaml",
    "content": "# The frequency, in Hz, at which the filter will output a position estimate. Note that the filter will not begin\n# computation until it receives at least one message from one of the inputs. It will then run continuously at the\n# frequency specified here, regardless of whether it receives more measurements. Defaults to 30 if unspecified.\nfrequency: 30\n\n# The period, in seconds, after which we consider a sensor to have timed out. In this event, we carry out a predict\n# cycle on the EKF without correcting it. This parameter can be thought of as the minimum frequency with which the\n# filter will generate new output. Defaults to 1 / frequency if not specified.\nsensor_timeout: 0.1\n\n# ekf_localization_node and ukf_localization_node both use a 3D omnidirectional motion model. If this parameter is\n# set to true, no 3D information will be used in your state estimate. Use this if you are operating in a planar\n# environment and want to ignore the effect of small variations in the ground plane that might otherwise be detected\n# by, for example, an IMU. Defaults to false if unspecified.\ntwo_d_mode: false\n\n# Use this parameter to provide an offset to the transform generated by ekf_localization_node. This can be used for\n# future dating the transform, which is required for interaction with some other packages. Defaults to 0.0 if\n# unspecified.\ntransform_time_offset: 0.0\n\n# Use this parameter to provide specify how long the tf listener should wait for a transform to become available. \n# Defaults to 0.0 if unspecified.\ntransform_timeout: 0.0\n\n# If you're having trouble, try setting this to true, and then echo the /diagnostics_agg topic to see if the node is\n# unhappy with any settings or data.\nprint_diagnostics: true\n\n# Debug settings. Not for the faint of heart. Outputs a ludicrous amount of information to the file specified by\n# debug_out_file. I hope you like matrices! Please note that setting this to true will have strongly deleterious\n# effects on the performance of the node. Defaults to false if unspecified.\ndebug: false\n\n# Defaults to \"robot_localization_debug.txt\" if unspecified. Please specify the full path.\ndebug_out_file: /path/to/debug/file.txt\n\n# REP-105 (http://www.ros.org/reps/rep-0105.html) specifies four principal coordinate frames: base_link, odom, map, and\n# earth. base_link is the coordinate frame that is affixed to the robot. Both odom and map are world-fixed frames.\n# The robot's position in the odom frame will drift over time, but is accurate in the short term and should be\n# continuous. The odom frame is therefore the best frame for executing local motion plans. The map frame, like the odom\n# frame, is a world-fixed coordinate frame, and while it contains the most globally accurate position estimate for your\n# robot, it is subject to discrete jumps, e.g., due to the fusion of GPS data or a correction from a map-based\n# localization node. The earth frame is used to relate multiple map frames by giving them a common reference frame.\n# ekf_localization_node and ukf_localization_node are not concerned with the earth frame.\n# Here is how to use the following settings:\n# 1. Set the map_frame, odom_frame, and base_link frames to the appropriate frame names for your system.\n#     1a. If your system does not have a map_frame, just remove it, and make sure \"world_frame\" is set to the value of\n#         odom_frame.\n# 2. If you are fusing continuous position data such as wheel encoder odometry, visual odometry, or IMU data, set\n#   \"world_frame\" to your odom_frame value. This is the default behavior for robot_localization's state estimation nodes.\n# 3. If you are fusing global absolute position data that is subject to discrete jumps (e.g., GPS or position updates\n# from landmark observations) then:\n#     3a. Set your \"world_frame\" to your map_frame value\n#     3b. MAKE SURE something else is generating the odom->base_link transform. Note that this can even be another state\n#         estimation node from robot_localization! However, that instance should *not* fuse the global data.\nmap_frame: map              # Defaults to \"map\" if unspecified\nodom_frame: odom            # Defaults to \"odom\" if unspecified\nbase_link_frame: base_link  # Defaults to \"base_link\" if unspecified\nworld_frame: odom           # Defaults to the value of odom_frame if unspecified\n\n# The filter accepts an arbitrary number of inputs from each input message type (nav_msgs/Odometry,\n# geometry_msgs/PoseWithCovarianceStamped, geometry_msgs/TwistWithCovarianceStamped,\n# sensor_msgs/Imu). To add an input, simply append the next number in the sequence to its \"base\" name, e.g., odom0,\n# odom1, twist0, twist1, imu0, imu1, imu2, etc. The value should be the topic name. These parameters obviously have no\n# default values, and must be specified.\nodom0: example/odom\n\n# Each sensor reading updates some or all of the filter's state. These options give you greater control over which\n# values from each measurement are fed to the filter. For example, if you have an odometry message as input, but only\n# want to use its Z position value, then set the entire vector to false, except for the third entry. The order of the\n# values is x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Note that not some message types\n# do not provide some of the state variables estimated by the filter. For example, a TwistWithCovarianceStamped message\n# has no pose information, so the first six values would be meaningless in that case. Each vector defaults to all false\n# if unspecified, effectively making this parameter required for each sensor.\nodom0_config: [true,  true,  false,\n               false, false, false,\n               false, false, false,\n               false, false, true,\n               false, false, false]\n\n# If you have high-frequency data or are running with a low frequency parameter value, then you may want to increase\n# the size of the subscription queue so that more measurements are fused.\nodom0_queue_size: 2\n\n# [ADVANCED] Large messages in ROS can exhibit strange behavior when they arrive at a high frequency. This is a result\n# of Nagle's algorithm. This option tells the ROS subscriber to use the tcpNoDelay option, which disables Nagle's\n# algorithm.\nodom0_nodelay: false\n\n# [ADVANCED] When measuring one pose variable with two sensors, a situation can arise in which both sensors under-\n# report their covariances. This can lead to the filter rapidly jumping back and forth between each measurement as they\n# arrive. In these cases, it often makes sense to (a) correct the measurement covariances, or (b) if velocity is also\n# measured by one of the sensors, let one sensor measure pose, and the other velocity. However, doing (a) or (b) isn't\n# always feasible, and so we expose the differential parameter. When differential mode is enabled, all absolute pose\n# data is converted to velocity data by differentiating the absolute pose measurements. These velocities are then\n# integrated as usual. NOTE: this only applies to sensors that provide pose measurements; setting differential to true\n# for twist measurements has no effect.\nodom0_differential: false\n\n# [ADVANCED] When the node starts, if this parameter is true, then the first measurement is treated as a \"zero point\"\n# for all future measurements. While you can achieve the same effect with the differential paremeter, the key\n# difference is that the relative parameter doesn't cause the measurement to be converted to a velocity before\n# integrating it. If you simply want your measurements to start at 0 for a given sensor, set this to true.\nodom0_relative: false\n\n# [ADVANCED] If your data is subject to outliers, use these threshold settings, expressed as Mahalanobis distances, to\n# control how far away from the current vehicle state a sensor measurement is permitted to be. Each defaults to\n# numeric_limits<double>::max() if unspecified. It is strongly recommended that these parameters be removed if not\n# required. Data is specified at the level of pose and twist variables, rather than for each variable in isolation.\n# For messages that have both pose and twist data, the parameter specifies to which part of the message we are applying\n# the thresholds.\nodom0_pose_rejection_threshold: 5\nodom0_twist_rejection_threshold: 1\n\n# Further input parameter examples\nodom1: example/another_odom\nodom1_config: [false, false, true,\n               false, false, false,\n               false, false, false,\n               false, false, true,\n               false, false, false]\nodom1_differential: false\nodom1_relative: true\nodom1_queue_size: 2\nodom1_pose_rejection_threshold: 2\nodom1_twist_rejection_threshold: 0.2\nodom1_nodelay: false\n\npose0: example/pose\npose0_config: [true,  true,  false,\n               false, false, false,\n               false, false, false,\n               false, false, false,\n               false, false, false]\npose0_differential: true\npose0_relative: false\npose0_queue_size: 5\npose0_rejection_threshold: 2  # Note the difference in parameter name\npose0_nodelay: false\n\ntwist0: example/twist\ntwist0_config: [false, false, false,\n                false, false, false,\n                true,  true,  true,\n                false, false, false,\n                false, false, false]\ntwist0_queue_size: 3\ntwist0_rejection_threshold: 2\ntwist0_nodelay: false\n\nimu0: example/imu\nimu0_config: [false, false, false,\n              true,  true,  true,\n              false, false, false,\n              true,  true,  true,\n              true,  true,  true]\nimu0_nodelay: false\nimu0_differential: false\nimu0_relative: true\nimu0_queue_size: 5\nimu0_pose_rejection_threshold: 0.8                 # Note the difference in parameter names\nimu0_twist_rejection_threshold: 0.8                #\nimu0_linear_acceleration_rejection_threshold: 0.8  #\n\n# [ADVANCED] Some IMUs automatically remove acceleration due to gravity, and others don't. If yours doesn't, please set\n# this to true, and *make sure* your data conforms to REP-103, specifically, that the data is in ENU frame.\nimu0_remove_gravitational_acceleration: true\n\n# [ADVANCED]  The EKF and UKF models follow a standard predict/correct cycle. During prediction, if there is no\n# acceleration reference, the velocity at time t+1 is simply predicted to be the same as the velocity at time t. During\n# correction, this predicted value is fused with the measured value to produce the new velocity estimate. This can be\n# problematic, as the final velocity will effectively be a weighted average of the old velocity and the new one. When\n# this velocity is the integrated into a new pose, the result can be sluggish covergence. This effect is especially\n# noticeable with LIDAR data during rotations. To get around it, users can try inflating the process_noise_covariance\n# for the velocity variable in question, or decrease the  variance of the variable in question in the measurement\n# itself. In addition, users can also take advantage of the control command being issued to the robot at the time we\n# make the prediction. If control is used, it will get converted into an acceleration term, which will be used during\n# predicition. Note that if an acceleration measurement for the variable in question is available from one of the\n# inputs, the control term will be ignored.\n# Whether or not we use the control input during predicition. Defaults to false.\nuse_control: true\n# Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to\n# false.\nstamped_control: false\n# The last issued control command will be used in prediction for this period. Defaults to 0.2.\ncontrol_timeout: 0.2\n# Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw.\ncontrol_config: [true, false, false, false, false, true]\n# Places limits on how large the acceleration term will be. Should match your robot's kinematics.\nacceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4]\n# Acceleration and deceleration limits are not always the same for robots.\ndeceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5]\n# If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these\n# gains\nacceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9]\n# If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these\n# gains\ndeceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0]\n\n# [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is\n# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each\n# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be.\n# However, if users find that a given variable is slow to converge, one approach is to increase the\n# process_noise_covariance diagonal value for the variable in question, which will cause the filter's predicted error\n# to be larger, which will cause the filter to trust the incoming measurement more during correction. The values are\n# ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below if\n# unspecified.\nprocess_noise_covariance: [0.05, 0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0.05, 0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0.06, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0.03, 0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0.03, 0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0.06, 0,     0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0.025, 0,     0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0.025, 0,    0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0.04, 0,    0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0.01, 0,    0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.01, 0,    0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.02, 0,    0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.01, 0,    0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.01, 0,\n                           0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.015]\n\n# [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal\n# value (variance) to a large value will result in rapid convergence for initial measurements of the variable in\n# question. Users should take care not to use large values for variables that will not be measured directly. The values\n# are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the matrix below\n#if unspecified.\ninitial_estimate_covariance: [1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    1e-9, 0,    0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    1e-9, 0,    0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    1e-9, 0,     0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    1e-9,  0,     0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1e-9,  0,     0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1e-9,  0,    0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1e-9, 0,    0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1e-9, 0,\n                              0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1e-9]\n\n# [ADVANCED, UKF ONLY] The alpha and kappa variables control the spread of the sigma points. Unless you are familiar\n# with UKFs, it's probably a good idea to leave these alone.\n# Defaults to 0.001 if unspecified.\nalpha: 0.001\n# Defaults to 0 if unspecified.\nkappa: 0\n\n# [ADVANCED, UKF ONLY] The beta variable relates to the distribution of the state vector. Again, it's probably best to\n# leave this alone if you're uncertain. Defaults to 2 if unspecified.\nbeta: 2\n"
  },
  {
    "path": "src/robot_localization/rosdoc.yaml",
    "content": " - builder: sphinx\n   sphinx_root_dir: doc\n - builder: doxygen\n   output_dir: api\n   file_patterns: '*.cpp *.h *.dox *.md'\n   exclude_patterns: '*/test/*'\n"
  },
  {
    "path": "src/robot_localization/src/ekf.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ekf.h\"\n#include \"robot_localization/filter_common.h\"\n\n#include <XmlRpcException.h>\n\n#include <iomanip>\n#include <limits>\n#include <sstream>\n#include <vector>\n\nnamespace RobotLocalization\n{\n  Ekf::Ekf(std::vector<double>) :\n    FilterBase()  // Must initialize filter base!\n  {\n  }\n\n  Ekf::~Ekf()\n  {\n  }\n\n  void Ekf::correct(const Measurement &measurement)\n  {\n    FB_DEBUG(\"---------------------- Ekf::correct ----------------------\\n\" <<\n             \"State is:\\n\" << state_ << \"\\n\"\n             \"Topic is:\\n\" << measurement.topicName_ << \"\\n\"\n             \"Measurement is:\\n\" << measurement.measurement_ << \"\\n\"\n             \"Measurement topic name is:\\n\" << measurement.topicName_ << \"\\n\\n\"\n             \"Measurement covariance is:\\n\" << measurement.covariance_ << \"\\n\");\n\n    // We don't want to update everything, so we need to build matrices that only update\n    // the measured parts of our state vector. Throughout prediction and correction, we\n    // attempt to maximize efficiency in Eigen.\n\n    // First, determine how many state vector values we're updating\n    std::vector<size_t> updateIndices;\n    for (size_t i = 0; i < measurement.updateVector_.size(); ++i)\n    {\n      if (measurement.updateVector_[i])\n      {\n        // Handle nan and inf values in measurements\n        if (std::isnan(measurement.measurement_(i)))\n        {\n          FB_DEBUG(\"Value at index \" << i << \" was nan. Excluding from update.\\n\");\n        }\n        else if (std::isinf(measurement.measurement_(i)))\n        {\n          FB_DEBUG(\"Value at index \" << i << \" was inf. Excluding from update.\\n\");\n        }\n        else\n        {\n          updateIndices.push_back(i);\n        }\n      }\n    }\n\n    FB_DEBUG(\"Update indices are:\\n\" << updateIndices << \"\\n\");\n\n    size_t updateSize = updateIndices.size();\n\n    // Now set up the relevant matrices\n    Eigen::VectorXd stateSubset(updateSize);                              // x (in most literature)\n    Eigen::VectorXd measurementSubset(updateSize);                        // z\n    Eigen::MatrixXd measurementCovarianceSubset(updateSize, updateSize);  // R\n    Eigen::MatrixXd stateToMeasurementSubset(updateSize, state_.rows());  // H\n    Eigen::MatrixXd kalmanGainSubset(state_.rows(), updateSize);          // K\n    Eigen::VectorXd innovationSubset(updateSize);                         // z - Hx\n\n    stateSubset.setZero();\n    measurementSubset.setZero();\n    measurementCovarianceSubset.setZero();\n    stateToMeasurementSubset.setZero();\n    kalmanGainSubset.setZero();\n    innovationSubset.setZero();\n\n    // Now build the sub-matrices from the full-sized matrices\n    for (size_t i = 0; i < updateSize; ++i)\n    {\n      measurementSubset(i) = measurement.measurement_(updateIndices[i]);\n      stateSubset(i) = state_(updateIndices[i]);\n\n      for (size_t j = 0; j < updateSize; ++j)\n      {\n        measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]);\n      }\n\n      // Handle negative (read: bad) covariances in the measurement. Rather\n      // than exclude the measurement or make up a covariance, just take\n      // the absolute value.\n      if (measurementCovarianceSubset(i, i) < 0)\n      {\n        FB_DEBUG(\"WARNING: Negative covariance for index \" << i <<\n                 \" of measurement (value is\" << measurementCovarianceSubset(i, i) <<\n                 \"). Using absolute value...\\n\");\n\n        measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i));\n      }\n\n      // If the measurement variance for a given variable is very\n      // near 0 (as in e-50 or so) and the variance for that\n      // variable in the covariance matrix is also near zero, then\n      // the Kalman gain computation will blow up. Really, no\n      // measurement can be completely without error, so add a small\n      // amount in that case.\n      if (measurementCovarianceSubset(i, i) < 1e-9)\n      {\n        FB_DEBUG(\"WARNING: measurement had very small error covariance for index \" << updateIndices[i] <<\n                 \". Adding some noise to maintain filter stability.\\n\");\n\n        measurementCovarianceSubset(i, i) = 1e-9;\n      }\n    }\n\n    // The state-to-measurement function, h, will now be a measurement_size x full_state_size\n    // matrix, with ones in the (i, i) locations of the values to be updated\n    for (size_t i = 0; i < updateSize; ++i)\n    {\n      stateToMeasurementSubset(i, updateIndices[i]) = 1;\n    }\n\n    FB_DEBUG(\"Current state subset is:\\n\" << stateSubset <<\n             \"\\nMeasurement subset is:\\n\" << measurementSubset <<\n             \"\\nMeasurement covariance subset is:\\n\" << measurementCovarianceSubset <<\n             \"\\nState-to-measurement subset is:\\n\" << stateToMeasurementSubset << \"\\n\");\n\n    // (1) Compute the Kalman gain: K = (PH') / (HPH' + R)\n    Eigen::MatrixXd pht = estimateErrorCovariance_ * stateToMeasurementSubset.transpose();\n    Eigen::MatrixXd hphrInv  = (stateToMeasurementSubset * pht + measurementCovarianceSubset).inverse();\n    kalmanGainSubset.noalias() = pht * hphrInv;\n\n    innovationSubset = (measurementSubset - stateSubset);\n\n    // Wrap angles in the innovation\n    for (size_t i = 0; i < updateSize; ++i)\n    {\n      if (updateIndices[i] == StateMemberRoll  ||\n          updateIndices[i] == StateMemberPitch ||\n          updateIndices[i] == StateMemberYaw)\n      {\n        while (innovationSubset(i) < -PI)\n        {\n          innovationSubset(i) += TAU;\n        }\n\n        while (innovationSubset(i) > PI)\n        {\n          innovationSubset(i) -= TAU;\n        }\n      }\n    }\n\n    // (2) Check Mahalanobis distance between mapped measurement and state.\n    if (checkMahalanobisThreshold(innovationSubset, hphrInv, measurement.mahalanobisThresh_))\n    {\n      // (3) Apply the gain to the difference between the state and measurement: x = x + K(z - Hx)\n      state_.noalias() += kalmanGainSubset * innovationSubset;\n\n      // (4) Update the estimate error covariance using the Joseph form: (I - KH)P(I - KH)' + KRK'\n      Eigen::MatrixXd gainResidual = identity_;\n      gainResidual.noalias() -= kalmanGainSubset * stateToMeasurementSubset;\n      estimateErrorCovariance_ = gainResidual * estimateErrorCovariance_ * gainResidual.transpose();\n      estimateErrorCovariance_.noalias() += kalmanGainSubset *\n                                            measurementCovarianceSubset *\n                                            kalmanGainSubset.transpose();\n\n      // Handle wrapping of angles\n      wrapStateAngles();\n\n      FB_DEBUG(\"Kalman gain subset is:\\n\" << kalmanGainSubset <<\n               \"\\nInnovation is:\\n\" << innovationSubset <<\n               \"\\nCorrected full state is:\\n\" << state_ <<\n               \"\\nCorrected full estimate error covariance is:\\n\" << estimateErrorCovariance_ <<\n               \"\\n\\n---------------------- /Ekf::correct ----------------------\\n\");\n    }\n  }\n\n  void Ekf::predict(const double referenceTime, const double delta)\n  {\n    FB_DEBUG(\"---------------------- Ekf::predict ----------------------\\n\" <<\n             \"delta is \" << delta << \"\\n\" <<\n             \"state is \" << state_ << \"\\n\");\n\n    double roll = state_(StateMemberRoll);\n    double pitch = state_(StateMemberPitch);\n    double yaw = state_(StateMemberYaw);\n    double xVel = state_(StateMemberVx);\n    double yVel = state_(StateMemberVy);\n    double zVel = state_(StateMemberVz);\n    double rollVel = state_(StateMemberVroll);\n    double pitchVel = state_(StateMemberVpitch);\n    double yawVel = state_(StateMemberVyaw);\n    double xAcc = state_(StateMemberAx);\n    double yAcc = state_(StateMemberAy);\n    double zAcc = state_(StateMemberAz);\n\n    // We'll need these trig calculations a lot.\n    double sp = ::sin(pitch);\n    double cp = ::cos(pitch);\n\n    double sr = ::sin(roll);\n    double cr = ::cos(roll);\n\n    double sy = ::sin(yaw);\n    double cy = ::cos(yaw);\n\n    prepareControl(referenceTime, delta);\n\n    // Prepare the transfer function\n    transferFunction_(StateMemberX, StateMemberVx) = cy * cp * delta;\n    transferFunction_(StateMemberX, StateMemberVy) = (cy * sp * sr - sy * cr) * delta;\n    transferFunction_(StateMemberX, StateMemberVz) = (cy * sp * cr + sy * sr) * delta;\n    transferFunction_(StateMemberX, StateMemberAx) = 0.5 * transferFunction_(StateMemberX, StateMemberVx) * delta;\n    transferFunction_(StateMemberX, StateMemberAy) = 0.5 * transferFunction_(StateMemberX, StateMemberVy) * delta;\n    transferFunction_(StateMemberX, StateMemberAz) = 0.5 * transferFunction_(StateMemberX, StateMemberVz) * delta;\n    transferFunction_(StateMemberY, StateMemberVx) = sy * cp * delta;\n    transferFunction_(StateMemberY, StateMemberVy) = (sy * sp * sr + cy * cr) * delta;\n    transferFunction_(StateMemberY, StateMemberVz) = (sy * sp * cr - cy * sr) * delta;\n    transferFunction_(StateMemberY, StateMemberAx) = 0.5 * transferFunction_(StateMemberY, StateMemberVx) * delta;\n    transferFunction_(StateMemberY, StateMemberAy) = 0.5 * transferFunction_(StateMemberY, StateMemberVy) * delta;\n    transferFunction_(StateMemberY, StateMemberAz) = 0.5 * transferFunction_(StateMemberY, StateMemberVz) * delta;\n    transferFunction_(StateMemberZ, StateMemberVx) = -sp * delta;\n    transferFunction_(StateMemberZ, StateMemberVy) = cp * sr * delta;\n    transferFunction_(StateMemberZ, StateMemberVz) = cp * cr * delta;\n    transferFunction_(StateMemberZ, StateMemberAx) = 0.5 * transferFunction_(StateMemberZ, StateMemberVx) * delta;\n    transferFunction_(StateMemberZ, StateMemberAy) = 0.5 * transferFunction_(StateMemberZ, StateMemberVy) * delta;\n    transferFunction_(StateMemberZ, StateMemberAz) = 0.5 * transferFunction_(StateMemberZ, StateMemberVz) * delta;\n    transferFunction_(StateMemberRoll, StateMemberVroll) = transferFunction_(StateMemberX, StateMemberVx);\n    transferFunction_(StateMemberRoll, StateMemberVpitch) = transferFunction_(StateMemberX, StateMemberVy);\n    transferFunction_(StateMemberRoll, StateMemberVyaw) = transferFunction_(StateMemberX, StateMemberVz);\n    transferFunction_(StateMemberPitch, StateMemberVroll) = transferFunction_(StateMemberY, StateMemberVx);\n    transferFunction_(StateMemberPitch, StateMemberVpitch) = transferFunction_(StateMemberY, StateMemberVy);\n    transferFunction_(StateMemberPitch, StateMemberVyaw) = transferFunction_(StateMemberY, StateMemberVz);\n    transferFunction_(StateMemberYaw, StateMemberVroll) = transferFunction_(StateMemberZ, StateMemberVx);\n    transferFunction_(StateMemberYaw, StateMemberVpitch) = transferFunction_(StateMemberZ, StateMemberVy);\n    transferFunction_(StateMemberYaw, StateMemberVyaw) = transferFunction_(StateMemberZ, StateMemberVz);\n    transferFunction_(StateMemberVx, StateMemberAx) = delta;\n    transferFunction_(StateMemberVy, StateMemberAy) = delta;\n    transferFunction_(StateMemberVz, StateMemberAz) = delta;\n\n    // Prepare the transfer function Jacobian. This function is analytically derived from the\n    // transfer function.\n    double xCoeff = 0.0;\n    double yCoeff = 0.0;\n    double zCoeff = 0.0;\n    double oneHalfATSquared = 0.5 * delta * delta;\n\n    yCoeff = cy * sp * cr + sy * sr;\n    zCoeff = -cy * sp * sr + sy * cr;\n    double dFx_dR = (yCoeff * yVel + zCoeff * zVel) * delta +\n                    (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;\n    double dFR_dR = 1 + (yCoeff * pitchVel + zCoeff * yawVel) * delta;\n\n    xCoeff = -cy * sp;\n    yCoeff = cy * cp * sr;\n    zCoeff = cy * cp * cr;\n    double dFx_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +\n                    (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;\n    double dFR_dP = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;\n\n    xCoeff = -sy * cp;\n    yCoeff = -sy * sp * sr - cy * cr;\n    zCoeff = -sy * sp * cr + cy * sr;\n    double dFx_dY = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +\n                    (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;\n    double dFR_dY = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;\n\n    yCoeff = sy * sp * cr - cy * sr;\n    zCoeff = -sy * sp * sr - cy * cr;\n    double dFy_dR = (yCoeff * yVel + zCoeff * zVel) * delta +\n                    (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;\n    double dFP_dR = (yCoeff * pitchVel + zCoeff * yawVel) * delta;\n\n    xCoeff = -sy * sp;\n    yCoeff = sy * cp * sr;\n    zCoeff = sy * cp * cr;\n    double dFy_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +\n                    (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;\n    double dFP_dP = 1 + (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;\n\n    xCoeff = cy * cp;\n    yCoeff = cy * sp * sr - sy * cr;\n    zCoeff = cy * sp * cr + sy * sr;\n    double dFy_dY = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +\n                    (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;\n    double dFP_dY = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;\n\n    yCoeff = cp * cr;\n    zCoeff = -cp * sr;\n    double dFz_dR = (yCoeff * yVel + zCoeff * zVel) * delta +\n                    (yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;\n    double dFY_dR = (yCoeff * pitchVel + zCoeff * yawVel) * delta;\n\n    xCoeff = -cp;\n    yCoeff = -sp * sr;\n    zCoeff = -sp * cr;\n    double dFz_dP = (xCoeff * xVel + yCoeff * yVel + zCoeff * zVel) * delta +\n                    (xCoeff * xAcc + yCoeff * yAcc + zCoeff * zAcc) * oneHalfATSquared;\n    double dFY_dP = (xCoeff * rollVel + yCoeff * pitchVel + zCoeff * yawVel) * delta;\n\n    // Much of the transfer function Jacobian is identical to the transfer function\n    transferFunctionJacobian_ = transferFunction_;\n    transferFunctionJacobian_(StateMemberX, StateMemberRoll) = dFx_dR;\n    transferFunctionJacobian_(StateMemberX, StateMemberPitch) = dFx_dP;\n    transferFunctionJacobian_(StateMemberX, StateMemberYaw) = dFx_dY;\n    transferFunctionJacobian_(StateMemberY, StateMemberRoll) = dFy_dR;\n    transferFunctionJacobian_(StateMemberY, StateMemberPitch) = dFy_dP;\n    transferFunctionJacobian_(StateMemberY, StateMemberYaw) = dFy_dY;\n    transferFunctionJacobian_(StateMemberZ, StateMemberRoll) = dFz_dR;\n    transferFunctionJacobian_(StateMemberZ, StateMemberPitch) = dFz_dP;\n    transferFunctionJacobian_(StateMemberRoll, StateMemberRoll) = dFR_dR;\n    transferFunctionJacobian_(StateMemberRoll, StateMemberPitch) = dFR_dP;\n    transferFunctionJacobian_(StateMemberRoll, StateMemberYaw) = dFR_dY;\n    transferFunctionJacobian_(StateMemberPitch, StateMemberRoll) = dFP_dR;\n    transferFunctionJacobian_(StateMemberPitch, StateMemberPitch) = dFP_dP;\n    transferFunctionJacobian_(StateMemberPitch, StateMemberYaw) = dFP_dY;\n    transferFunctionJacobian_(StateMemberYaw, StateMemberRoll) = dFY_dR;\n    transferFunctionJacobian_(StateMemberYaw, StateMemberPitch) = dFY_dP;\n\n    FB_DEBUG(\"Transfer function is:\\n\" << transferFunction_ <<\n             \"\\nTransfer function Jacobian is:\\n\" << transferFunctionJacobian_ <<\n             \"\\nProcess noise covariance is:\\n\" << processNoiseCovariance_ <<\n             \"\\nCurrent state is:\\n\" << state_ << \"\\n\");\n\n    Eigen::MatrixXd *processNoiseCovariance = &processNoiseCovariance_;\n\n    if (useDynamicProcessNoiseCovariance_)\n    {\n      computeDynamicProcessNoiseCovariance(state_, delta);\n      processNoiseCovariance = &dynamicProcessNoiseCovariance_;\n    }\n\n    // (1) Apply control terms, which are actually accelerations\n    state_(StateMemberVroll) += controlAcceleration_(ControlMemberVroll) * delta;\n    state_(StateMemberVpitch) += controlAcceleration_(ControlMemberVpitch) * delta;\n    state_(StateMemberVyaw) += controlAcceleration_(ControlMemberVyaw) * delta;\n\n    state_(StateMemberAx) = (controlUpdateVector_[ControlMemberVx] ?\n      controlAcceleration_(ControlMemberVx) : state_(StateMemberAx));\n    state_(StateMemberAy) = (controlUpdateVector_[ControlMemberVy] ?\n      controlAcceleration_(ControlMemberVy) : state_(StateMemberAy));\n    state_(StateMemberAz) = (controlUpdateVector_[ControlMemberVz] ?\n      controlAcceleration_(ControlMemberVz) : state_(StateMemberAz));\n\n    // (2) Project the state forward: x = Ax + Bu (really, x = f(x, u))\n    state_ = transferFunction_ * state_;\n\n    // Handle wrapping\n    wrapStateAngles();\n\n    FB_DEBUG(\"Predicted state is:\\n\" << state_ <<\n             \"\\nCurrent estimate error covariance is:\\n\" <<  estimateErrorCovariance_ << \"\\n\");\n\n    // (3) Project the error forward: P = J * P * J' + Q\n    estimateErrorCovariance_ = (transferFunctionJacobian_ *\n                                estimateErrorCovariance_ *\n                                transferFunctionJacobian_.transpose());\n    estimateErrorCovariance_.noalias() += delta * (*processNoiseCovariance);\n\n    FB_DEBUG(\"Predicted estimate error covariance is:\\n\" << estimateErrorCovariance_ <<\n             \"\\n\\n--------------------- /Ekf::predict ----------------------\\n\");\n  }\n\n}  // namespace RobotLocalization\n"
  },
  {
    "path": "src/robot_localization/src/ekf_localization_node.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_filter_types.h\"\n\n#include <ros/ros.h>\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"ekf_navigation_node\");\n\n  RobotLocalization::RosEkf ekf;\n\n  ekf.run();\n\n  return EXIT_SUCCESS;\n}\n"
  },
  {
    "path": "src/robot_localization/src/filter_base.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/filter_base.h\"\n#include \"robot_localization/filter_common.h\"\n\n#include <iomanip>\n#include <iostream>\n#include <limits>\n#include <sstream>\n#include <vector>\n\nnamespace RobotLocalization\n{\n  FilterBase::FilterBase() :\n    accelerationGains_(TWIST_SIZE, 0.0),\n    accelerationLimits_(TWIST_SIZE, 0.0),\n    decelerationGains_(TWIST_SIZE, 0.0),\n    decelerationLimits_(TWIST_SIZE, 0.0),\n    controlAcceleration_(TWIST_SIZE),\n    controlTimeout_(0.0),\n    controlUpdateVector_(TWIST_SIZE, 0),\n    dynamicProcessNoiseCovariance_(STATE_SIZE, STATE_SIZE),\n    latestControlTime_(0.0),\n    state_(STATE_SIZE),\n    predictedState_(STATE_SIZE),\n    transferFunction_(STATE_SIZE, STATE_SIZE),\n    transferFunctionJacobian_(STATE_SIZE, STATE_SIZE),\n    estimateErrorCovariance_(STATE_SIZE, STATE_SIZE),\n    covarianceEpsilon_(STATE_SIZE, STATE_SIZE),\n    processNoiseCovariance_(STATE_SIZE, STATE_SIZE),\n    identity_(STATE_SIZE, STATE_SIZE),\n    debug_(false),\n    debugStream_(NULL),\n    useControl_(false),\n    useDynamicProcessNoiseCovariance_(false)\n  {\n    reset();\n  }\n\n  FilterBase::~FilterBase()\n  {\n  }\n\n  void FilterBase::reset()\n  {\n    initialized_ = false;\n\n    // Clear the state and predicted state\n    state_.setZero();\n    predictedState_.setZero();\n    controlAcceleration_.setZero();\n\n    // Prepare the invariant parts of the transfer\n    // function\n    transferFunction_.setIdentity();\n\n    // Clear the Jacobian\n    transferFunctionJacobian_.setZero();\n\n    // Set the estimate error covariance. We want our measurements\n    // to be accepted rapidly when the filter starts, so we should\n    // initialize the state's covariance with large values.\n    estimateErrorCovariance_.setIdentity();\n    estimateErrorCovariance_ *= 1e-9;\n\n    // We need the identity for the update equations\n    identity_.setIdentity();\n\n    // Set the epsilon matrix to be a matrix with small values on the diagonal\n    // It is used to maintain the positive-definite property of the covariance\n    covarianceEpsilon_.setIdentity();\n    covarianceEpsilon_ *= 0.001;\n\n    // Assume 30Hz from sensor data (configurable)\n    sensorTimeout_ = 0.033333333;\n\n    // Initialize our measurement time\n    lastMeasurementTime_ = 0;\n\n    // These can be overridden via the launch parameters,\n    // but we need default values.\n    processNoiseCovariance_.setZero();\n    processNoiseCovariance_(StateMemberX, StateMemberX) = 0.05;\n    processNoiseCovariance_(StateMemberY, StateMemberY) = 0.05;\n    processNoiseCovariance_(StateMemberZ, StateMemberZ) = 0.06;\n    processNoiseCovariance_(StateMemberRoll, StateMemberRoll) = 0.03;\n    processNoiseCovariance_(StateMemberPitch, StateMemberPitch) = 0.03;\n    processNoiseCovariance_(StateMemberYaw, StateMemberYaw) = 0.06;\n    processNoiseCovariance_(StateMemberVx, StateMemberVx) = 0.025;\n    processNoiseCovariance_(StateMemberVy, StateMemberVy) = 0.025;\n    processNoiseCovariance_(StateMemberVz, StateMemberVz) = 0.04;\n    processNoiseCovariance_(StateMemberVroll, StateMemberVroll) = 0.01;\n    processNoiseCovariance_(StateMemberVpitch, StateMemberVpitch) = 0.01;\n    processNoiseCovariance_(StateMemberVyaw, StateMemberVyaw) = 0.02;\n    processNoiseCovariance_(StateMemberAx, StateMemberAx) = 0.01;\n    processNoiseCovariance_(StateMemberAy, StateMemberAy) = 0.01;\n    processNoiseCovariance_(StateMemberAz, StateMemberAz) = 0.015;\n\n    dynamicProcessNoiseCovariance_ = processNoiseCovariance_;\n  }\n\n  void FilterBase::computeDynamicProcessNoiseCovariance(const Eigen::VectorXd &state, const double delta)\n  {\n    // A more principled approach would be to get the current velocity from the state, make a diagonal matrix from it,\n    // and then rotate it to be in the world frame (i.e., the same frame as the pose data). We could then use this\n    // rotated velocity matrix to scale the process noise covariance for the pose variables as\n    // rotatedVelocityMatrix * poseCovariance * rotatedVelocityMatrix'\n    // However, this presents trouble for robots that may incur rotational error as a result of linear motion (and\n    // vice-versa). Instead, we create a diagonal matrix whose diagonal values are the vector norm of the state's\n    // velocity. We use that to scale the process noise covariance.\n    Eigen::MatrixXd velocityMatrix(TWIST_SIZE, TWIST_SIZE);\n    velocityMatrix.setIdentity();\n    velocityMatrix.diagonal() *= state.segment(POSITION_V_OFFSET, TWIST_SIZE).norm();\n\n    dynamicProcessNoiseCovariance_.block<TWIST_SIZE, TWIST_SIZE>(POSITION_OFFSET, POSITION_OFFSET) =\n      velocityMatrix *\n      processNoiseCovariance_.block<TWIST_SIZE, TWIST_SIZE>(POSITION_OFFSET, POSITION_OFFSET) *\n      velocityMatrix.transpose();\n  }\n\n  const Eigen::VectorXd& FilterBase::getControl()\n  {\n    return latestControl_;\n  }\n\n  double FilterBase::getControlTime()\n  {\n    return latestControlTime_;\n  }\n\n  bool FilterBase::getDebug()\n  {\n    return debug_;\n  }\n\n  const Eigen::MatrixXd& FilterBase::getEstimateErrorCovariance()\n  {\n    return estimateErrorCovariance_;\n  }\n\n  bool FilterBase::getInitializedStatus()\n  {\n    return initialized_;\n  }\n\n  double FilterBase::getLastMeasurementTime()\n  {\n    return lastMeasurementTime_;\n  }\n\n  const Eigen::VectorXd& FilterBase::getPredictedState()\n  {\n    return predictedState_;\n  }\n\n  const Eigen::MatrixXd& FilterBase::getProcessNoiseCovariance()\n  {\n    return processNoiseCovariance_;\n  }\n\n  double FilterBase::getSensorTimeout()\n  {\n    return sensorTimeout_;\n  }\n\n  const Eigen::VectorXd& FilterBase::getState()\n  {\n    return state_;\n  }\n\n  void FilterBase::processMeasurement(const Measurement &measurement)\n  {\n    FB_DEBUG(\"------ FilterBase::processMeasurement (\" << measurement.topicName_ << \") ------\\n\");\n\n    double delta = 0.0;\n\n    // If we've had a previous reading, then go through the predict/update\n    // cycle. Otherwise, set our state and covariance to whatever we get\n    // from this measurement.\n    if (initialized_)\n    {\n      // Determine how much time has passed since our last measurement\n      delta = measurement.time_ - lastMeasurementTime_;\n\n      FB_DEBUG(\"Filter is already initialized. Carrying out predict/correct loop...\\n\"\n               \"Measurement time is \" << std::setprecision(20) << measurement.time_ <<\n               \", last measurement time is \" << lastMeasurementTime_ << \", delta is \" << delta << \"\\n\");\n\n      // Only want to carry out a prediction if it's\n      // forward in time. Otherwise, just correct.\n      if (delta > 0)\n      {\n        validateDelta(delta);\n        predict(measurement.time_, delta);\n\n        // Return this to the user\n        predictedState_ = state_;\n      }\n\n      correct(measurement);\n    }\n    else\n    {\n      FB_DEBUG(\"First measurement. Initializing filter.\\n\");\n\n      // Initialize the filter, but only with the values we're using\n      size_t measurementLength = measurement.updateVector_.size();\n      for (size_t i = 0; i < measurementLength; ++i)\n      {\n        state_[i] = (measurement.updateVector_[i] ? measurement.measurement_[i] : state_[i]);\n      }\n\n      // Same for covariance\n      for (size_t i = 0; i < measurementLength; ++i)\n      {\n        for (size_t j = 0; j < measurementLength; ++j)\n        {\n          estimateErrorCovariance_(i, j) = (measurement.updateVector_[i] && measurement.updateVector_[j] ?\n                                            measurement.covariance_(i, j) :\n                                            estimateErrorCovariance_(i, j));\n        }\n      }\n\n      initialized_ = true;\n    }\n\n    if (delta >= 0.0)\n    {\n      lastMeasurementTime_ = measurement.time_;\n    }\n\n    FB_DEBUG(\"------ /FilterBase::processMeasurement (\" << measurement.topicName_ << \") ------\\n\");\n  }\n\n  void FilterBase::setControl(const Eigen::VectorXd &control, const double controlTime)\n  {\n    latestControl_ = control;\n    latestControlTime_ = controlTime;\n  }\n\n  void FilterBase::setControlParams(const std::vector<int> &updateVector, const double controlTimeout,\n    const std::vector<double> &accelerationLimits, const std::vector<double> &accelerationGains,\n    const std::vector<double> &decelerationLimits, const std::vector<double> &decelerationGains)\n  {\n    useControl_ = true;\n    controlUpdateVector_ = updateVector;\n    controlTimeout_ = controlTimeout;\n    accelerationLimits_ = accelerationLimits;\n    accelerationGains_ = accelerationGains;\n    decelerationLimits_ = decelerationLimits;\n    decelerationGains_ = decelerationGains;\n  }\n\n  void FilterBase::setDebug(const bool debug, std::ostream *outStream)\n  {\n    if (debug)\n    {\n      if (outStream != NULL)\n      {\n        debugStream_ = outStream;\n        debug_ = true;\n      }\n      else\n      {\n        debug_ = false;\n      }\n    }\n    else\n    {\n      debug_ = false;\n    }\n  }\n\n  void FilterBase::setUseDynamicProcessNoiseCovariance(const bool useDynamicProcessNoiseCovariance)\n  {\n    useDynamicProcessNoiseCovariance_ = useDynamicProcessNoiseCovariance;\n  }\n\n  void FilterBase::setEstimateErrorCovariance(const Eigen::MatrixXd &estimateErrorCovariance)\n  {\n    estimateErrorCovariance_ = estimateErrorCovariance;\n  }\n\n  void FilterBase::setLastMeasurementTime(const double lastMeasurementTime)\n  {\n    lastMeasurementTime_ = lastMeasurementTime;\n  }\n\n  void FilterBase::setProcessNoiseCovariance(const Eigen::MatrixXd &processNoiseCovariance)\n  {\n    processNoiseCovariance_ = processNoiseCovariance;\n    dynamicProcessNoiseCovariance_ = processNoiseCovariance_;\n  }\n\n  void FilterBase::setSensorTimeout(const double sensorTimeout)\n  {\n    sensorTimeout_ = sensorTimeout;\n  }\n\n  void FilterBase::setState(const Eigen::VectorXd &state)\n  {\n    state_ = state;\n  }\n\n  void FilterBase::validateDelta(double &delta)\n  {\n    // This handles issues with ROS time when use_sim_time is on and we're playing from bags.\n    if (delta > 100000.0)\n    {\n      FB_DEBUG(\"Delta was very large. Suspect playing from bag file. Setting to 0.01\\n\");\n\n      delta = 0.01;\n    }\n  }\n\n\n  void FilterBase::prepareControl(const double referenceTime, const double predictionDelta)\n  {\n    controlAcceleration_.setZero();\n\n    if (useControl_)\n    {\n      bool timedOut = ::fabs(referenceTime - latestControlTime_) >= controlTimeout_;\n\n      if (timedOut)\n      {\n        FB_DEBUG(\"Control timed out. Reference time was \" << referenceTime << \", latest control time was \" <<\n          latestControlTime_ << \", control timeout was \" << controlTimeout_ << \"\\n\");\n      }\n\n      for (size_t controlInd = 0; controlInd < TWIST_SIZE; ++controlInd)\n      {\n        if (controlUpdateVector_[controlInd])\n        {\n          controlAcceleration_(controlInd) = computeControlAcceleration(state_(controlInd + POSITION_V_OFFSET),\n            (timedOut ? 0.0 : latestControl_(controlInd)), accelerationLimits_[controlInd],\n            accelerationGains_[controlInd], decelerationLimits_[controlInd], decelerationGains_[controlInd]);\n        }\n      }\n    }\n  }\n\n  void FilterBase::wrapStateAngles()\n  {\n    state_(StateMemberRoll)  = FilterUtilities::clampRotation(state_(StateMemberRoll));\n    state_(StateMemberPitch) = FilterUtilities::clampRotation(state_(StateMemberPitch));\n    state_(StateMemberYaw)   = FilterUtilities::clampRotation(state_(StateMemberYaw));\n  }\n\n  bool FilterBase::checkMahalanobisThreshold(const Eigen::VectorXd &innovation,\n                                             const Eigen::MatrixXd &invCovariance,\n                                             const double nsigmas)\n  {\n    double sqMahalanobis = innovation.dot(invCovariance * innovation);\n    double threshold = nsigmas * nsigmas;\n\n    if (sqMahalanobis >= threshold)\n    {\n      FB_DEBUG(\"Innovation mahalanobis distance test failed. Squared Mahalanobis is: \" << sqMahalanobis << \"\\n\" <<\n               \"Threshold is: \" << threshold << \"\\n\" <<\n               \"Innovation is: \" << innovation << \"\\n\" <<\n               \"Innovation covariance is:\\n\" << invCovariance << \"\\n\");\n\n      return false;\n    }\n\n    return true;\n  }\n}  // namespace RobotLocalization\n"
  },
  {
    "path": "src/robot_localization/src/filter_utilities.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/filter_utilities.h\"\n#include \"robot_localization/filter_common.h\"\n\n#include <string>\n#include <vector>\n\nstd::ostream& operator<<(std::ostream& os, const Eigen::MatrixXd &mat)\n{\n  os << \"[\";\n\n  int rowCount = static_cast<int>(mat.rows());\n\n  for (int row = 0; row < rowCount; ++row)\n  {\n    if (row > 0)\n    {\n      os << \" \";\n    }\n\n    for (int col = 0; col < mat.cols(); ++col)\n    {\n      os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << mat(row, col);\n    }\n\n    if (row < rowCount - 1)\n    {\n      os << \"\\n\";\n    }\n  }\n\n  os << \"]\\n\";\n\n  return os;\n}\n\nstd::ostream& operator<<(std::ostream& os, const Eigen::VectorXd &vec)\n{\n  os << \"[\";\n  for (int dim = 0; dim < vec.rows(); ++dim)\n  {\n    os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << vec(dim);\n  }\n  os << \"]\\n\";\n\n  return os;\n}\n\nstd::ostream& operator<<(std::ostream& os, const std::vector<size_t> &vec)\n{\n  os << \"[\";\n  for (size_t dim = 0; dim < vec.size(); ++dim)\n  {\n    os << std::setiosflags(std::ios::left) << std::setw(12) << std::setprecision(5) << vec[dim];\n  }\n  os << \"]\\n\";\n\n  return os;\n}\n\nstd::ostream& operator<<(std::ostream& os, const std::vector<int> &vec)\n{\n  os << \"[\";\n  for (size_t dim = 0; dim < vec.size(); ++dim)\n  {\n    os << std::setiosflags(std::ios::left) << std::setw(3) << (vec[dim] ? \"t\" : \"f\");\n  }\n  os << \"]\\n\";\n\n  return os;\n}\n\nnamespace RobotLocalization\n{\n\nnamespace FilterUtilities\n{\n  void appendPrefix(std::string tfPrefix, std::string &frameId)\n  {\n    // Strip all leading slashes for tf2 compliance\n    if (!frameId.empty() && frameId.at(0) == '/')\n    {\n      frameId = frameId.substr(1);\n    }\n\n    if (!tfPrefix.empty() && tfPrefix.at(0) == '/')\n    {\n      tfPrefix = tfPrefix.substr(1);\n    }\n\n    // If we do have a tf prefix, then put a slash in between\n    if (!tfPrefix.empty())\n    {\n      frameId = tfPrefix + \"/\" + frameId;\n    }\n  }\n\n  double clampRotation(double rotation)\n  {\n    while (rotation > PI)\n    {\n      rotation -= TAU;\n    }\n\n    while (rotation < -PI)\n    {\n      rotation += TAU;\n    }\n\n    return rotation;\n  }\n\n}  // namespace FilterUtilities\n\n}  // namespace RobotLocalization\n"
  },
  {
    "path": "src/robot_localization/src/navsat_transform.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/navsat_transform.h\"\n#include \"robot_localization/filter_common.h\"\n#include \"robot_localization/filter_utilities.h\"\n#include \"robot_localization/navsat_conversions.h\"\n#include \"robot_localization/ros_filter_utilities.h\"\n\n#include <tf2_geometry_msgs/tf2_geometry_msgs.h>\n#include <XmlRpcException.h>\n\n#include <string>\n\nnamespace RobotLocalization\n{\n  NavSatTransform::NavSatTransform() :\n    magnetic_declination_(0.0),\n    utm_odom_tf_yaw_(0.0),\n    yaw_offset_(0.0),\n    transform_timeout_(ros::Duration(0)),\n    broadcast_utm_transform_(false),\n    broadcast_utm_transform_as_parent_frame_(false),\n    has_transform_odom_(false),\n    has_transform_gps_(false),\n    has_transform_imu_(false),\n    transform_good_(false),\n    gps_frame_id_(\"\"),\n    gps_updated_(false),\n    odom_updated_(false),\n    publish_gps_(false),\n    use_odometry_yaw_(false),\n    use_manual_datum_(false),\n    zero_altitude_(false),\n    world_frame_id_(\"odom\"),\n    base_link_frame_id_(\"base_link\"),\n    utm_zone_(\"\"),\n    tf_listener_(tf_buffer_)\n  {\n    latest_utm_covariance_.resize(POSE_SIZE, POSE_SIZE);\n    latest_odom_covariance_.resize(POSE_SIZE, POSE_SIZE);\n  }\n\n  NavSatTransform::~NavSatTransform()\n  {\n  }\n\n  void NavSatTransform::run()\n  {\n    ros::Time::init();\n\n    double frequency = 10.0;\n    double delay = 0.0;\n    double transform_timeout = 0.0;\n\n    ros::NodeHandle nh;\n    ros::NodeHandle nh_priv(\"~\");\n\n    // Load the parameters we need\n    nh_priv.getParam(\"magnetic_declination_radians\", magnetic_declination_);\n    nh_priv.param(\"yaw_offset\", yaw_offset_, 0.0);\n    nh_priv.param(\"broadcast_utm_transform\", broadcast_utm_transform_, false);\n    nh_priv.param(\"broadcast_utm_transform_as_parent_frame\", broadcast_utm_transform_as_parent_frame_, false);\n    nh_priv.param(\"zero_altitude\", zero_altitude_, false);\n    nh_priv.param(\"publish_filtered_gps\", publish_gps_, false);\n    nh_priv.param(\"use_odometry_yaw\", use_odometry_yaw_, false);\n    nh_priv.param(\"wait_for_datum\", use_manual_datum_, false);\n    nh_priv.param(\"frequency\", frequency, 10.0);\n    nh_priv.param(\"delay\", delay, 0.0);\n    nh_priv.param(\"transform_timeout\", transform_timeout, 0.0);\n    transform_timeout_.fromSec(transform_timeout);\n\n    // Subscribe to the messages and services we need\n    ros::ServiceServer datum_srv = nh.advertiseService(\"datum\", &NavSatTransform::datumCallback, this);\n\n    if (use_manual_datum_ && nh_priv.hasParam(\"datum\"))\n    {\n      XmlRpc::XmlRpcValue datum_config;\n\n      try\n      {\n        double datum_lat;\n        double datum_lon;\n        double datum_yaw;\n\n        nh_priv.getParam(\"datum\", datum_config);\n\n        // Handle datum specification. Users should always specify a baseLinkFrameId_ in the\n        // datum config, but we had a release where it wasn't used, so we'll maintain compatibility.\n        ROS_ASSERT(datum_config.getType() == XmlRpc::XmlRpcValue::TypeArray);\n        ROS_ASSERT(datum_config.size() >= 3);\n\n        if (datum_config.size() > 3)\n        {\n          ROS_WARN_STREAM(\"Deprecated datum parameter configuration detected. Only the first three parameters \"\n              \"(latitude, longitude, yaw) will be used. frame_ids will be derived from odometry and navsat inputs.\");\n        }\n\n        std::ostringstream ostr;\n        ostr << std::setprecision(20) << datum_config[0] << \" \" << datum_config[1] << \" \" << datum_config[2];\n        std::istringstream istr(ostr.str());\n        istr >> datum_lat >> datum_lon >> datum_yaw;\n\n        // Try to resolve tf_prefix\n        std::string tf_prefix = \"\";\n        std::string tf_prefix_path = \"\";\n        if (nh_priv.searchParam(\"tf_prefix\", tf_prefix_path))\n        {\n          nh_priv.getParam(tf_prefix_path, tf_prefix);\n        }\n\n        // Append the tf prefix in a tf2-friendly manner\n        FilterUtilities::appendPrefix(tf_prefix, world_frame_id_);\n        FilterUtilities::appendPrefix(tf_prefix, base_link_frame_id_);\n\n        robot_localization::SetDatum::Request request;\n        request.geo_pose.position.latitude = datum_lat;\n        request.geo_pose.position.longitude = datum_lon;\n        request.geo_pose.position.altitude = 0.0;\n        tf2::Quaternion quat;\n        quat.setRPY(0.0, 0.0, datum_yaw);\n        request.geo_pose.orientation = tf2::toMsg(quat);\n        robot_localization::SetDatum::Response response;\n        datumCallback(request, response);\n      }\n      catch (XmlRpc::XmlRpcException &e)\n      {\n        ROS_ERROR_STREAM(\"ERROR reading sensor config: \" << e.getMessage() <<\n                         \" for process_noise_covariance (type: \" << datum_config.getType() << \")\");\n      }\n    }\n\n    ros::Subscriber odom_sub = nh.subscribe(\"odometry/filtered\", 1, &NavSatTransform::odomCallback, this);\n    ros::Subscriber gps_sub = nh.subscribe(\"gps/fix\", 1, &NavSatTransform::gpsFixCallback, this);\n    ros::Subscriber imu_sub;\n\n    if (!use_odometry_yaw_ && !use_manual_datum_)\n    {\n      imu_sub = nh.subscribe(\"imu/data\", 1, &NavSatTransform::imuCallback, this);\n    }\n\n    ros::Publisher gps_odom_pub = nh.advertise<nav_msgs::Odometry>(\"odometry/gps\", 10);\n    ros::Publisher filtered_gps_pub;\n\n    if (publish_gps_)\n    {\n      filtered_gps_pub = nh.advertise<sensor_msgs::NavSatFix>(\"gps/filtered\", 10);\n    }\n\n    // Sleep for the parameterized amount of time, to give\n    // other nodes time to start up (not always necessary)\n    ros::Duration start_delay(delay);\n    start_delay.sleep();\n\n    ros::Rate rate(frequency);\n    while (ros::ok())\n    {\n      ros::spinOnce();\n\n      if (!transform_good_)\n      {\n        computeTransform();\n\n        if (transform_good_ && !use_odometry_yaw_ && !use_manual_datum_)\n        {\n          // Once we have the transform, we don't need the IMU\n          imu_sub.shutdown();\n        }\n      }\n      else\n      {\n        nav_msgs::Odometry gps_odom;\n        if (prepareGpsOdometry(gps_odom))\n        {\n          gps_odom_pub.publish(gps_odom);\n        }\n\n        if (publish_gps_)\n        {\n          sensor_msgs::NavSatFix odom_gps;\n          if (prepareFilteredGps(odom_gps))\n          {\n            filtered_gps_pub.publish(odom_gps);\n          }\n        }\n      }\n\n      rate.sleep();\n    }\n  }\n\n  void NavSatTransform::computeTransform()\n  {\n    // Only do this if:\n    // 1. We haven't computed the odom_frame->utm_frame transform before\n    // 2. We've received the data we need\n    if (!transform_good_ &&\n        has_transform_odom_ &&\n        has_transform_gps_ &&\n        has_transform_imu_)\n    {\n      // 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\n      // the robot's origin.\n      tf2::Transform transform_utm_pose_corrected;\n      if (!use_manual_datum_)\n      {\n        getRobotOriginUtmPose(transform_utm_pose_, transform_utm_pose_corrected, ros::Time(0));\n      }\n      else\n      {\n        transform_utm_pose_corrected = transform_utm_pose_;\n      }\n\n      // Get the IMU's current RPY values. Need the raw values (for yaw, anyway).\n      tf2::Matrix3x3 mat(transform_orientation_);\n\n      // Convert to RPY\n      double imu_roll;\n      double imu_pitch;\n      double imu_yaw;\n      mat.getRPY(imu_roll, imu_pitch, imu_yaw);\n\n      /* The IMU's heading was likely originally reported w.r.t. magnetic north.\n       * However, all the nodes in robot_localization assume that orientation data,\n       * including that reported by IMUs, is reported in an ENU frame, with a 0 yaw\n       * value being reported when facing east and increasing counter-clockwise (i.e.,\n       * towards north). Conveniently, this aligns with the UTM grid, where X is east\n       * and Y is north. However, we have two additional considerations:\n       *   1. The IMU may have its non-ENU frame data transformed to ENU, but there's\n       *      a possibility that its data has not been corrected for magnetic\n       *      declination. We need to account for this. A positive magnetic\n       *      declination is counter-clockwise in an ENU frame. Therefore, if\n       *      we have a magnetic declination of N radians, then when the sensor\n       *      is facing a heading of N, it reports 0. Therefore, we need to add\n       *      the declination angle.\n       *   2. To account for any other offsets that may not be accounted for by the\n       *      IMU driver or any interim processing node, we expose a yaw offset that\n       *      lets users work with navsat_transform_node.\n       */\n      imu_yaw += (magnetic_declination_ + yaw_offset_);\n\n      ROS_INFO_STREAM(\"Corrected for magnetic declination of \" << std::fixed << magnetic_declination_ <<\n                      \" and user-specified offset of \" << yaw_offset_ << \".\" <<\n                      \" Transform heading factor is now \" << imu_yaw);\n\n      // Convert to tf-friendly structures\n      tf2::Quaternion imu_quat;\n      imu_quat.setRPY(0.0, 0.0, imu_yaw);\n\n      // The transform order will be orig_odom_pos * orig_utm_pos_inverse * cur_utm_pos.\n      // Doing it this way will allow us to cope with having non-zero odometry position\n      // when we get our first GPS message.\n      tf2::Transform utm_pose_with_orientation;\n      utm_pose_with_orientation.setOrigin(transform_utm_pose_corrected.getOrigin());\n      utm_pose_with_orientation.setRotation(imu_quat);\n\n      utm_world_transform_.mult(transform_world_pose_, utm_pose_with_orientation.inverse());\n\n      utm_world_trans_inverse_ = utm_world_transform_.inverse();\n\n      ROS_INFO_STREAM(\"Transform world frame pose is: \" << transform_world_pose_);\n      ROS_INFO_STREAM(\"World frame->utm transform is \" << utm_world_transform_);\n\n      transform_good_ = true;\n\n      // Send out the (static) UTM transform in case anyone else would like to use it.\n      if (broadcast_utm_transform_)\n      {\n        geometry_msgs::TransformStamped utm_transform_stamped;\n        utm_transform_stamped.header.stamp = ros::Time::now();\n        utm_transform_stamped.header.frame_id = (broadcast_utm_transform_as_parent_frame_ ? \"utm\" : world_frame_id_);\n        utm_transform_stamped.child_frame_id = (broadcast_utm_transform_as_parent_frame_ ? world_frame_id_ : \"utm\");\n        utm_transform_stamped.transform = (broadcast_utm_transform_as_parent_frame_ ?\n                                             tf2::toMsg(utm_world_trans_inverse_) : tf2::toMsg(utm_world_transform_));\n        utm_transform_stamped.transform.translation.z = (zero_altitude_ ?\n                                                           0.0 : utm_transform_stamped.transform.translation.z);\n        utm_broadcaster_.sendTransform(utm_transform_stamped);\n      }\n    }\n  }\n\n  bool NavSatTransform::datumCallback(robot_localization::SetDatum::Request& request,\n                                      robot_localization::SetDatum::Response&)\n  {\n    // If we get a service call with a manual datum, even if we already computed the transform using the robot's\n    // initial pose, then we want to assume that we are using a datum from now on, and we want other methods to\n    // not attempt to transform the values we are specifying here.\n    use_manual_datum_ = true;\n\n    transform_good_ = false;\n\n    sensor_msgs::NavSatFix *fix = new sensor_msgs::NavSatFix();\n    fix->latitude = request.geo_pose.position.latitude;\n    fix->longitude = request.geo_pose.position.longitude;\n    fix->altitude = request.geo_pose.position.altitude;\n    fix->header.stamp = ros::Time::now();\n    fix->position_covariance[0] = 0.1;\n    fix->position_covariance[4] = 0.1;\n    fix->position_covariance[8] = 0.1;\n    fix->position_covariance_type = sensor_msgs::NavSatStatus::STATUS_FIX;\n    sensor_msgs::NavSatFixConstPtr fix_ptr(fix);\n    setTransformGps(fix_ptr);\n\n    nav_msgs::Odometry *odom = new nav_msgs::Odometry();\n    odom->pose.pose.orientation.x = 0;\n    odom->pose.pose.orientation.y = 0;\n    odom->pose.pose.orientation.z = 0;\n    odom->pose.pose.orientation.w = 1;\n    odom->pose.pose.position.x = 0;\n    odom->pose.pose.position.y = 0;\n    odom->pose.pose.position.z = 0;\n    odom->header.frame_id = world_frame_id_;\n    odom->child_frame_id = base_link_frame_id_;\n    nav_msgs::OdometryConstPtr odom_ptr(odom);\n    setTransformOdometry(odom_ptr);\n\n    sensor_msgs::Imu *imu = new sensor_msgs::Imu();\n    imu->orientation = request.geo_pose.orientation;\n    imu->header.frame_id = base_link_frame_id_;\n    sensor_msgs::ImuConstPtr imu_ptr(imu);\n    imuCallback(imu_ptr);\n\n    return true;\n  }\n\n  void NavSatTransform::getRobotOriginUtmPose(const tf2::Transform &gps_utm_pose,\n                                              tf2::Transform &robot_utm_pose,\n                                              const ros::Time &transform_time)\n  {\n    robot_utm_pose.setIdentity();\n\n    // Get linear offset from origin for the GPS\n    tf2::Transform offset;\n    bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_,\n                                                                 base_link_frame_id_,\n                                                                 gps_frame_id_,\n                                                                 transform_time,\n                                                                 ros::Duration(transform_timeout_),\n                                                                 offset);\n\n    if (can_transform)\n    {\n      // Get the orientation we'll use for our UTM->world transform\n      tf2::Quaternion utm_orientation = transform_orientation_;\n      tf2::Matrix3x3 mat(utm_orientation);\n\n      // Add the offsets\n      double roll;\n      double pitch;\n      double yaw;\n      mat.getRPY(roll, pitch, yaw);\n      yaw += (magnetic_declination_ + yaw_offset_);\n      utm_orientation.setRPY(roll, pitch, yaw);\n\n      // Rotate the GPS linear offset by the orientation\n      // Zero out the orientation, because the GPS orientation is meaningless, and if it's non-zero, it will make the\n      // the computation of robot_utm_pose erroneous.\n      offset.setOrigin(tf2::quatRotate(utm_orientation, offset.getOrigin()));\n      offset.setRotation(tf2::Quaternion::getIdentity());\n\n      // Update the initial pose\n      robot_utm_pose = offset.inverse() * gps_utm_pose;\n    }\n    else\n    {\n      if (gps_frame_id_ != \"\")\n      {\n        ROS_WARN_STREAM_ONCE(\"Unable to obtain \" << base_link_frame_id_ << \"->\" << gps_frame_id_ <<\n          \" transform. Will assume navsat device is mounted at robot's origin\");\n      }\n\n      robot_utm_pose = gps_utm_pose;\n    }\n  }\n\n  void NavSatTransform::getRobotOriginWorldPose(const tf2::Transform &gps_odom_pose,\n                                                tf2::Transform &robot_odom_pose,\n                                                const ros::Time &transform_time)\n  {\n    robot_odom_pose.setIdentity();\n\n    // Remove the offset from base_link\n    tf2::Transform gps_offset_rotated;\n    bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_,\n                                                                 base_link_frame_id_,\n                                                                 gps_frame_id_,\n                                                                 transform_time,\n                                                                 transform_timeout_,\n                                                                 gps_offset_rotated);\n\n    if (can_transform)\n    {\n      tf2::Transform robot_orientation;\n      can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_,\n                                                              world_frame_id_,\n                                                              base_link_frame_id_,\n                                                              transform_time,\n                                                              transform_timeout_,\n                                                              robot_orientation);\n\n      if (can_transform)\n      {\n        // Zero out rotation because we don't care about the orientation of the\n        // GPS receiver relative to base_link\n        gps_offset_rotated.setOrigin(tf2::quatRotate(robot_orientation.getRotation(), gps_offset_rotated.getOrigin()));\n        gps_offset_rotated.setRotation(tf2::Quaternion::getIdentity());\n        robot_odom_pose = gps_offset_rotated.inverse() * gps_odom_pose;\n      }\n      else\n      {\n        ROS_WARN_STREAM_THROTTLE(5.0, \"Could not obtain \" << world_frame_id_ << \"->\" << base_link_frame_id_ <<\n          \" transform. Will not remove offset of navsat device from robot's origin.\");\n      }\n    }\n    else\n    {\n      ROS_WARN_STREAM_THROTTLE(5.0, \"Could not obtain \" << base_link_frame_id_ << \"->\" << gps_frame_id_ <<\n        \" transform. Will not remove offset of navsat device from robot's origin.\");\n    }\n  }\n\n  void NavSatTransform::gpsFixCallback(const sensor_msgs::NavSatFixConstPtr& msg)\n  {\n    gps_frame_id_ = msg->header.frame_id;\n\n    if (gps_frame_id_.empty())\n    {\n      ROS_WARN_STREAM_ONCE(\"NavSatFix message has empty frame_id. Will assume navsat device is mounted at robot's \"\n        \"origin.\");\n    }\n\n    // Make sure the GPS data is usable\n    bool good_gps = (msg->status.status != sensor_msgs::NavSatStatus::STATUS_NO_FIX &&\n                     !std::isnan(msg->altitude) &&\n                     !std::isnan(msg->latitude) &&\n                     !std::isnan(msg->longitude));\n\n    if (good_gps)\n    {\n      // If we haven't computed the transform yet, then\n      // store this message as the initial GPS data to use\n      if (!transform_good_ && !use_manual_datum_)\n      {\n        setTransformGps(msg);\n      }\n\n      double utmX = 0;\n      double utmY = 0;\n      std::string utm_zone_tmp;\n      NavsatConversions::LLtoUTM(msg->latitude, msg->longitude, utmY, utmX, utm_zone_tmp);\n      latest_utm_pose_.setOrigin(tf2::Vector3(utmX, utmY, msg->altitude));\n      latest_utm_covariance_.setZero();\n\n      // Copy the measurement's covariance matrix so that we can rotate it later\n      for (size_t i = 0; i < POSITION_SIZE; i++)\n      {\n        for (size_t j = 0; j < POSITION_SIZE; j++)\n        {\n          latest_utm_covariance_(i, j) = msg->position_covariance[POSITION_SIZE * i + j];\n        }\n      }\n\n      gps_update_time_ = msg->header.stamp;\n      gps_updated_ = true;\n    }\n  }\n\n  void NavSatTransform::imuCallback(const sensor_msgs::ImuConstPtr& msg)\n  {\n    // We need the baseLinkFrameId_ from the odometry message, so\n    // we need to wait until we receive it.\n    if (has_transform_odom_)\n    {\n      /* This method only gets called if we don't yet have the\n       * IMU data (the subscriber gets shut down once we compute\n       * the transform), so we can assumed that every IMU message\n       * that comes here is meant to be used for that purpose. */\n      tf2::fromMsg(msg->orientation, transform_orientation_);\n\n      // Correct for the IMU's orientation w.r.t. base_link\n      tf2::Transform target_frame_trans;\n      bool can_transform = RosFilterUtilities::lookupTransformSafe(tf_buffer_,\n                                                                   base_link_frame_id_,\n                                                                   msg->header.frame_id,\n                                                                   msg->header.stamp,\n                                                                   transform_timeout_,\n                                                                   target_frame_trans);\n\n      if (can_transform)\n      {\n        double roll_offset = 0;\n        double pitch_offset = 0;\n        double yaw_offset = 0;\n        double roll = 0;\n        double pitch = 0;\n        double yaw = 0;\n        RosFilterUtilities::quatToRPY(target_frame_trans.getRotation(), roll_offset, pitch_offset, yaw_offset);\n        RosFilterUtilities::quatToRPY(transform_orientation_, roll, pitch, yaw);\n\n        ROS_DEBUG_STREAM(\"Initial orientation is \" << transform_orientation_);\n\n        // Apply the offset (making sure to bound them), and throw them in a vector\n        tf2::Vector3 rpy_angles(FilterUtilities::clampRotation(roll - roll_offset),\n                                FilterUtilities::clampRotation(pitch - pitch_offset),\n                                FilterUtilities::clampRotation(yaw - yaw_offset));\n\n        // Now we need to rotate the roll and pitch by the yaw offset value.\n        // Imagine a case where an IMU is mounted facing sideways. In that case\n        // pitch for the IMU's world frame is roll for the robot.\n        tf2::Matrix3x3 mat;\n        mat.setRPY(0.0, 0.0, yaw_offset);\n        rpy_angles = mat * rpy_angles;\n        transform_orientation_.setRPY(rpy_angles.getX(), rpy_angles.getY(), rpy_angles.getZ());\n\n        ROS_DEBUG_STREAM(\"Initial corrected orientation roll, pitch, yaw is (\" <<\n                         rpy_angles.getX() << \", \" << rpy_angles.getY() << \", \" << rpy_angles.getZ() << \")\");\n\n        has_transform_imu_ = true;\n      }\n    }\n  }\n\n  void NavSatTransform::odomCallback(const nav_msgs::OdometryConstPtr& msg)\n  {\n    world_frame_id_ = msg->header.frame_id;\n    base_link_frame_id_ = msg->child_frame_id;\n\n    if (!transform_good_ && !use_manual_datum_)\n    {\n      setTransformOdometry(msg);\n    }\n\n    tf2::fromMsg(msg->pose.pose, latest_world_pose_);\n    latest_odom_covariance_.setZero();\n    for (size_t row = 0; row < POSE_SIZE; ++row)\n    {\n      for (size_t col = 0; col < POSE_SIZE; ++col)\n      {\n        latest_odom_covariance_(row, col) = msg->pose.covariance[row * POSE_SIZE + col];\n      }\n    }\n\n    odom_update_time_ = msg->header.stamp;\n    odom_updated_ = true;\n  }\n\n\n  bool NavSatTransform::prepareFilteredGps(sensor_msgs::NavSatFix &filtered_gps)\n  {\n    bool new_data = false;\n\n    if (transform_good_ && odom_updated_)\n    {\n      tf2::Transform odom_as_utm;\n\n      odom_as_utm.mult(utm_world_trans_inverse_, latest_world_pose_);\n      odom_as_utm.setRotation(tf2::Quaternion::getIdentity());\n\n      // Rotate the covariance as well\n      tf2::Matrix3x3 rot(utm_world_trans_inverse_.getRotation());\n      Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE);\n      rot_6d.setIdentity();\n\n      for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd)\n      {\n        rot_6d(rInd, 0) = rot.getRow(rInd).getX();\n        rot_6d(rInd, 1) = rot.getRow(rInd).getY();\n        rot_6d(rInd, 2) = rot.getRow(rInd).getZ();\n        rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX();\n        rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY();\n        rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ();\n      }\n\n      // Rotate the covariance\n      latest_odom_covariance_ = rot_6d * latest_odom_covariance_.eval() * rot_6d.transpose();\n\n      // Now convert the data back to lat/long and place into the message\n      NavsatConversions::UTMtoLL(odom_as_utm.getOrigin().getY(),\n                                 odom_as_utm.getOrigin().getX(),\n                                 utm_zone_,\n                                 filtered_gps.latitude,\n                                 filtered_gps.longitude);\n      filtered_gps.altitude = odom_as_utm.getOrigin().getZ();\n\n      // Copy the measurement's covariance matrix back\n      for (size_t i = 0; i < POSITION_SIZE; i++)\n      {\n        for (size_t j = 0; j < POSITION_SIZE; j++)\n        {\n          filtered_gps.position_covariance[POSITION_SIZE * i + j] = latest_odom_covariance_(i, j);\n        }\n      }\n\n      filtered_gps.position_covariance_type = sensor_msgs::NavSatFix::COVARIANCE_TYPE_KNOWN;\n      filtered_gps.status.status = sensor_msgs::NavSatStatus::STATUS_GBAS_FIX;\n      filtered_gps.header.frame_id = \"gps\";\n      filtered_gps.header.stamp = odom_update_time_;\n\n      // Mark this GPS as used\n      odom_updated_ = false;\n      new_data = true;\n    }\n\n    return new_data;\n  }\n\n  bool NavSatTransform::prepareGpsOdometry(nav_msgs::Odometry &gps_odom)\n  {\n    bool new_data = false;\n\n    if (transform_good_ && gps_updated_ && odom_updated_)\n    {\n      tf2::Transform transformed_utm_gps;\n\n      transformed_utm_gps.mult(utm_world_transform_, latest_utm_pose_);\n      transformed_utm_gps.setRotation(tf2::Quaternion::getIdentity());\n\n      // Set header information stamp because we would like to know the robot's position at that timestamp\n      gps_odom.header.frame_id = world_frame_id_;\n      gps_odom.header.stamp = gps_update_time_;\n\n      // Want the pose of the vehicle origin, not the GPS\n      tf2::Transform transformed_utm_robot;\n      getRobotOriginWorldPose(transformed_utm_gps, transformed_utm_robot, gps_odom.header.stamp);\n\n      // Rotate the covariance as well\n      tf2::Matrix3x3 rot(utm_world_transform_.getRotation());\n      Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE);\n      rot_6d.setIdentity();\n\n      for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd)\n      {\n        rot_6d(rInd, 0) = rot.getRow(rInd).getX();\n        rot_6d(rInd, 1) = rot.getRow(rInd).getY();\n        rot_6d(rInd, 2) = rot.getRow(rInd).getZ();\n        rot_6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX();\n        rot_6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY();\n        rot_6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ();\n      }\n\n      // Rotate the covariance\n      latest_utm_covariance_ = rot_6d * latest_utm_covariance_.eval() * rot_6d.transpose();\n\n      // Now fill out the message. Set the orientation to the identity.\n      tf2::toMsg(transformed_utm_robot, gps_odom.pose.pose);\n      gps_odom.pose.pose.position.z = (zero_altitude_ ? 0.0 : gps_odom.pose.pose.position.z);\n\n      // Copy the measurement's covariance matrix so that we can rotate it later\n      for (size_t i = 0; i < POSE_SIZE; i++)\n      {\n        for (size_t j = 0; j < POSE_SIZE; j++)\n        {\n          gps_odom.pose.covariance[POSE_SIZE * i + j] = latest_utm_covariance_(i, j);\n        }\n      }\n\n      // Mark this GPS as used\n      gps_updated_ = false;\n      new_data = true;\n    }\n\n    return new_data;\n  }\n\n  void NavSatTransform::setTransformGps(const sensor_msgs::NavSatFixConstPtr& msg)\n  {\n    double utm_x = 0;\n    double utm_y = 0;\n    NavsatConversions::LLtoUTM(msg->latitude, msg->longitude, utm_y, utm_x, utm_zone_);\n\n    ROS_INFO_STREAM(\"Datum (latitude, longitude, altitude) is (\" << std::fixed << msg->latitude << \", \" <<\n                    msg->longitude << \", \" << msg->altitude << \")\");\n    ROS_INFO_STREAM(\"Datum UTM coordinate is (\" << std::fixed << utm_x << \", \" << utm_y << \")\");\n\n    transform_utm_pose_.setOrigin(tf2::Vector3(utm_x, utm_y, msg->altitude));\n    transform_utm_pose_.setRotation(tf2::Quaternion::getIdentity());\n    has_transform_gps_ = true;\n  }\n\n  void NavSatTransform::setTransformOdometry(const nav_msgs::OdometryConstPtr& msg)\n  {\n    tf2::fromMsg(msg->pose.pose, transform_world_pose_);\n    has_transform_odom_ = true;\n\n    ROS_INFO_STREAM(\"Initial odometry pose is \" << transform_world_pose_);\n\n    // Users can optionally use the (potentially fused) heading from\n    // the odometry source, which may have multiple fused sources of\n    // heading data, and so would act as a better heading for the\n    // UTM->world_frame transform.\n    if (!transform_good_ && use_odometry_yaw_ && !use_manual_datum_)\n    {\n      sensor_msgs::Imu *imu = new sensor_msgs::Imu();\n      imu->orientation = msg->pose.pose.orientation;\n      imu->header.frame_id = msg->child_frame_id;\n      imu->header.stamp = msg->header.stamp;\n      sensor_msgs::ImuConstPtr imuPtr(imu);\n      imuCallback(imuPtr);\n    }\n  }\n\n}  // namespace RobotLocalization\n"
  },
  {
    "path": "src/robot_localization/src/navsat_transform_node.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/navsat_transform.h\"\n\n#include <ros/ros.h>\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"navsat_transform_node\");\n\n  RobotLocalization::NavSatTransform trans;\n\n  trans.run();\n\n  return EXIT_SUCCESS;\n}\n\n\n"
  },
  {
    "path": "src/robot_localization/src/robot_localization_estimator.cpp",
    "content": "/*\n * Copyright (c) 2016, TNO IVS Helmond.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/robot_localization_estimator.h\"\n#include \"robot_localization/ekf.h\"\n#include \"robot_localization/ukf.h\"\n\n#include <vector>\n\nnamespace RobotLocalization\n{\nRobotLocalizationEstimator::RobotLocalizationEstimator(unsigned int buffer_capacity,\n                                                       FilterType filter_type,\n                                                       const Eigen::MatrixXd& process_noise_covariance,\n                                                       const std::vector<double>& filter_args)\n{\n  state_buffer_.set_capacity(buffer_capacity);\n\n  // Set up the filter that is used for predictions\n  if ( filter_type == FilterTypes::EKF )\n  {\n    filter_ = new Ekf;\n  }\n  else if ( filter_type == FilterTypes::UKF )\n  {\n    filter_ = new Ukf(filter_args);\n  }\n\n  filter_->setProcessNoiseCovariance(process_noise_covariance);\n}\n\nRobotLocalizationEstimator::~RobotLocalizationEstimator()\n{\n  delete filter_;\n}\n\nvoid RobotLocalizationEstimator::setState(const EstimatorState& state)\n{\n  // If newly received state is newer than any in the buffer, push back\n  if ( state_buffer_.empty() || state.time_stamp > state_buffer_.back().time_stamp )\n  {\n    state_buffer_.push_back(state);\n  }\n  // If it is older, put it in the right position\n  else\n  {\n    for ( boost::circular_buffer<EstimatorState>::iterator it = state_buffer_.begin(); it != state_buffer_.end(); ++it )\n    {\n      if ( state.time_stamp < it->time_stamp )\n      {\n        state_buffer_.insert(it, state);\n        return;\n      }\n    }\n  }\n}\n\nEstimatorResult RobotLocalizationEstimator::getState(const double time,\n                                                     EstimatorState& state) const\n{\n  // If there's nothing in the buffer, there's nothing to give.\n  if ( state_buffer_.size() == 0 )\n  {\n    return EstimatorResults::EmptyBuffer;\n  }\n\n  // Set state to the most recent one for now\n  state = state_buffer_.back();\n\n  // Go through buffer from new to old\n  EstimatorState last_state_before_time = state_buffer_.front();\n  EstimatorState next_state_after_time = state_buffer_.back();\n  bool previous_state_found = false;\n  bool next_state_found = false;\n\n  for (boost::circular_buffer<EstimatorState>::const_reverse_iterator it = state_buffer_.rbegin();\n       it != state_buffer_.rend(); ++it)\n  {\n    /* If the time stamp of the current state from the buffer is\n     * older than the requested time, store it as the last state\n     * before the requested time. If it is younger, save it as the\n     * next one after, and go on to find the last one before.\n     */\n    if ( it->time_stamp == time )\n    {\n      state = *it;\n      return EstimatorResults::Exact;\n    }\n    else if ( it->time_stamp <= time )\n    {\n      last_state_before_time = *it;\n      previous_state_found = true;\n      break;\n    }\n    else\n    {\n      next_state_after_time = *it;\n      next_state_found = true;\n    }\n  }\n\n  // If we found a previous state and a next state, we can do interpolation\n  if ( previous_state_found && next_state_found )\n  {\n    interpolate(last_state_before_time, next_state_after_time, time, state);\n    return EstimatorResults::Interpolation;\n  }\n\n  // If only a previous state is found, we can do extrapolation into the future\n  else if ( previous_state_found )\n  {\n    extrapolate(last_state_before_time, time, state);\n    return EstimatorResults::ExtrapolationIntoFuture;\n  }\n\n  // If only a next state is found, we'll have to extrapolate into the past.\n  else if ( next_state_found )\n  {\n    extrapolate(next_state_after_time, time, state);\n    return EstimatorResults::ExtrapolationIntoPast;\n  }\n\n  else\n  {\n    return EstimatorResults::Failed;\n  }\n}\n\nvoid RobotLocalizationEstimator::setBufferCapacity(const int capacity)\n{\n  state_buffer_.set_capacity(capacity);\n}\n\nvoid RobotLocalizationEstimator::clearBuffer()\n{\n  state_buffer_.clear();\n}\n\nunsigned int RobotLocalizationEstimator::getBufferCapacity() const\n{\n  return state_buffer_.capacity();\n}\n\nunsigned int RobotLocalizationEstimator::getSize() const\n{\n  return state_buffer_.size();\n}\n\nvoid RobotLocalizationEstimator::extrapolate(const EstimatorState& boundary_state,\n                                             const double requested_time,\n                                             EstimatorState& state_at_req_time) const\n{\n  // Set up the filter with the boundary state\n  filter_->setState(boundary_state.state);\n  filter_->setEstimateErrorCovariance(boundary_state.covariance);\n\n  // Calculate how much time we need to extrapolate into the future\n  double delta = requested_time - boundary_state.time_stamp;\n\n  // Use the filter to predict\n  filter_->predict(boundary_state.time_stamp, delta);\n\n  state_at_req_time.time_stamp = requested_time;\n  state_at_req_time.state = filter_->getState();\n  state_at_req_time.covariance = filter_->getEstimateErrorCovariance();\n\n  return;\n}\n\nvoid RobotLocalizationEstimator::interpolate(const EstimatorState& given_state_1,\n                                             const EstimatorState& given_state_2,\n                                             const double requested_time,\n                                             EstimatorState& state_at_req_time) const\n{\n  /*\n   * TODO: Right now, we only extrapolate from the last known state before the requested time. But as the state after\n   * the requested time is also known, we may want to perform interpolation between states.\n   */\n  extrapolate(given_state_1, requested_time, state_at_req_time);\n  return;\n}\n\n}  // namespace RobotLocalization\n"
  },
  {
    "path": "src/robot_localization/src/robot_localization_listener_node.cpp",
    "content": "/*\n * Copyright (c) 2016, TNO IVS Helmond.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_robot_localization_listener.h\"\n#include \"robot_localization/GetState.h\"\n\n#include <string>\n\nnamespace RobotLocalization\n{\n\nclass RobotLocalizationListenerNode\n{\npublic:\n  RobotLocalizationListenerNode()\n  {\n    service_ = n_.advertiseService(\"get_state\", &RobotLocalizationListenerNode::getStateCallback, this);\n  }\n\n  std::string getService()\n  {\n    return service_.getService();\n  }\n\nprivate:\n  RosRobotLocalizationListener rll_;\n  ros::NodeHandle n_;\n  ros::ServiceServer service_;\n\n  bool getStateCallback(robot_localization::GetState::Request  &req,\n                        robot_localization::GetState::Response &res)\n  {\n    Eigen::VectorXd state(STATE_SIZE);\n    Eigen::MatrixXd covariance(STATE_SIZE, STATE_SIZE);\n\n    if ( !rll_.getState(req.time_stamp, req.frame_id, state, covariance) )\n    {\n      ROS_ERROR(\"Robot Localization Listener Node: Listener instance returned false at getState call.\");\n      return false;\n    }\n\n    for (size_t i = 0; i < STATE_SIZE; i++)\n    {\n      res.state[i] = (*(state.data() + i));\n    }\n\n    for (size_t i = 0; i < STATE_SIZE * STATE_SIZE; i++)\n    {\n      res.covariance[i] = (*(covariance.data() + i));\n    }\n\n    ROS_DEBUG(\"Robot Localization Listener Node: Listener responded with state and covariance at the requested time.\");\n    return true;\n  }\n};\n\n}  // namespace RobotLocalization\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"robot_localization_listener_node\");\n\n  RobotLocalization::RobotLocalizationListenerNode rlln;\n  ROS_INFO_STREAM(\"Robot Localization Listener Node: Ready to handle GetState requests at \" << rlln.getService());\n\n  ros::spin();\n\n  return 0;\n}\n"
  },
  {
    "path": "src/robot_localization/src/ros_filter.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_filter.h\"\n#include \"robot_localization/filter_utilities.h\"\n#include \"robot_localization/ekf.h\"\n#include \"robot_localization/ukf.h\"\n\n#include <tf2_geometry_msgs/tf2_geometry_msgs.h>\n\n#include <algorithm>\n#include <map>\n#include <string>\n#include <utility>\n#include <vector>\n#include <limits>\n\nnamespace RobotLocalization\n{\n  template<typename T>\n  RosFilter<T>::RosFilter(std::vector<double> args) :\n      staticDiagErrorLevel_(diagnostic_msgs::DiagnosticStatus::OK),\n      tfListener_(tfBuffer_),\n      dynamicDiagErrorLevel_(diagnostic_msgs::DiagnosticStatus::OK),\n      filter_(args),\n      frequency_(30.0),\n      historyLength_(0),\n      lastSetPoseTime_(0),\n      latestControl_(),\n      latestControlTime_(0),\n      tfTimeout_(ros::Duration(0)),\n      nhLocal_(\"~\"),\n      predictToCurrentTime_(false),\n      printDiagnostics_(true),\n      gravitationalAcc_(9.80665),\n      publishTransform_(true),\n      publishAcceleration_(false),\n      twoDMode_(false),\n      useControl_(false),\n      smoothLaggedData_(false),\n      disabledAtStartup_(false),\n      enabled_(false)\n  {\n    stateVariableNames_.push_back(\"X\");\n    stateVariableNames_.push_back(\"Y\");\n    stateVariableNames_.push_back(\"Z\");\n    stateVariableNames_.push_back(\"ROLL\");\n    stateVariableNames_.push_back(\"PITCH\");\n    stateVariableNames_.push_back(\"YAW\");\n    stateVariableNames_.push_back(\"X_VELOCITY\");\n    stateVariableNames_.push_back(\"Y_VELOCITY\");\n    stateVariableNames_.push_back(\"Z_VELOCITY\");\n    stateVariableNames_.push_back(\"ROLL_VELOCITY\");\n    stateVariableNames_.push_back(\"PITCH_VELOCITY\");\n    stateVariableNames_.push_back(\"YAW_VELOCITY\");\n    stateVariableNames_.push_back(\"X_ACCELERATION\");\n    stateVariableNames_.push_back(\"Y_ACCELERATION\");\n    stateVariableNames_.push_back(\"Z_ACCELERATION\");\n\n    diagnosticUpdater_.setHardwareID(\"none\");\n  }\n\n  template<typename T>\n  RosFilter<T>::~RosFilter()\n  {\n    topicSubs_.clear();\n  }\n\n  template<typename T>\n  void RosFilter<T>::reset()\n  {\n    // Get rid of any initial poses (pretend we've never had a measurement)\n    initialMeasurements_.clear();\n    previousMeasurements_.clear();\n    previousMeasurementCovariances_.clear();\n\n    // Clear the measurement queue.\n    // This prevents us from immediately undoing our reset.\n    while (!measurementQueue_.empty() && ros::ok())\n    {\n      measurementQueue_.pop();\n    }\n\n    filterStateHistory_.clear();\n    measurementHistory_.clear();\n\n    // Also set the last set pose time, so we ignore all messages\n    // that occur before it\n    lastSetPoseTime_ = ros::Time(0);\n\n    // clear tf buffer to avoid TF_OLD_DATA errors\n    tfBuffer_.clear();\n\n    // clear last message timestamp, so older messages will be accepted\n    lastMessageTimes_.clear();\n\n    // reset filter to uninitialized state\n    filter_.reset();\n\n    // clear all waiting callbacks\n    ros::getGlobalCallbackQueue()->clear();\n  }\n\n  // @todo: Replace with AccelWithCovarianceStamped\n  template<typename T>\n  void RosFilter<T>::accelerationCallback(const sensor_msgs::Imu::ConstPtr &msg, const CallbackData &callbackData,\n    const std::string &targetFrame)\n  {\n    // If we've just reset the filter, then we want to ignore any messages\n    // that arrive with an older timestamp\n    if (msg->header.stamp <= lastSetPoseTime_)\n    {\n      return;\n    }\n\n    const std::string &topicName = callbackData.topicName_;\n\n    RF_DEBUG(\"------ RosFilter::accelerationCallback (\" << topicName << \") ------\\n\"\n             \"Twist message:\\n\" << *msg);\n\n    if (lastMessageTimes_.count(topicName) == 0)\n    {\n      lastMessageTimes_.insert(std::pair<std::string, ros::Time>(topicName, msg->header.stamp));\n    }\n\n    // Make sure this message is newer than the last one\n    if (msg->header.stamp >= lastMessageTimes_[topicName])\n    {\n      RF_DEBUG(\"Update vector for \" << topicName << \" is:\\n\" << topicName);\n\n      Eigen::VectorXd measurement(STATE_SIZE);\n      Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);\n\n      measurement.setZero();\n      measurementCovariance.setZero();\n\n      // Make sure we're actually updating at least one of these variables\n      std::vector<int> updateVectorCorrected = callbackData.updateVector_;\n\n      // Prepare the twist data for inclusion in the filter\n      if (prepareAcceleration(msg, topicName, targetFrame, updateVectorCorrected, measurement,\n            measurementCovariance))\n      {\n        // Store the measurement. Add an \"acceleration\" suffix so we know what kind of measurement\n        // we're dealing with when we debug the core filter logic.\n        enqueueMeasurement(topicName,\n                           measurement,\n                           measurementCovariance,\n                           updateVectorCorrected,\n                           callbackData.rejectionThreshold_,\n                           msg->header.stamp);\n\n        RF_DEBUG(\"Enqueued new measurement for \" << topicName << \"_acceleration\\n\");\n      }\n      else\n      {\n        RF_DEBUG(\"Did *not* enqueue measurement for \" << topicName << \"_acceleration\\n\");\n      }\n\n      lastMessageTimes_[topicName] = msg->header.stamp;\n\n      RF_DEBUG(\"Last message time for \" << topicName << \" is now \" <<\n        lastMessageTimes_[topicName] << \"\\n\");\n    }\n    else if (resetOnTimeJump_ && ros::Time::isSimTime())\n    {\n      reset();\n    }\n    else\n    {\n      std::stringstream stream;\n      stream << \"The \" << topicName << \" message has a timestamp before that of the previous message received,\" <<\n                \" this message will be ignored. This may indicate a bad timestamp. (message time: \" <<\n                msg->header.stamp.toSec() << \")\";\n      addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                    topicName + \"_timestamp\",\n                    stream.str(),\n                    false);\n\n      RF_DEBUG(\"Message is too old. Last message time for \" << topicName <<\n               \" is \" << lastMessageTimes_[topicName] << \", current message time is \" <<\n               msg->header.stamp << \".\\n\");\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::accelerationCallback (\" << topicName << \") ------\\n\");\n  }\n\n  template<typename T>\n  void RosFilter<T>::controlCallback(const geometry_msgs::Twist::ConstPtr &msg)\n  {\n    geometry_msgs::TwistStampedPtr twistStampedPtr = geometry_msgs::TwistStampedPtr(new geometry_msgs::TwistStamped());\n    twistStampedPtr->twist = *msg;\n    twistStampedPtr->header.frame_id = baseLinkFrameId_;\n    twistStampedPtr->header.stamp = ros::Time::now();\n    controlCallback(twistStampedPtr);\n  }\n\n  template<typename T>\n  void RosFilter<T>::controlCallback(const geometry_msgs::TwistStamped::ConstPtr &msg)\n  {\n    if (msg->header.frame_id == baseLinkFrameId_ || msg->header.frame_id == \"\")\n    {\n      latestControl_(ControlMemberVx) = msg->twist.linear.x;\n      latestControl_(ControlMemberVy) = msg->twist.linear.y;\n      latestControl_(ControlMemberVz) = msg->twist.linear.z;\n      latestControl_(ControlMemberVroll) = msg->twist.angular.x;\n      latestControl_(ControlMemberVpitch) = msg->twist.angular.y;\n      latestControl_(ControlMemberVyaw) = msg->twist.angular.z;\n      latestControlTime_ = msg->header.stamp;\n\n      // Update the filter with this control term\n      filter_.setControl(latestControl_, msg->header.stamp.toSec());\n    }\n    else\n    {\n      ROS_WARN_STREAM_THROTTLE(5.0, \"Commanded velocities must be given in the robot's body frame (\" <<\n        baseLinkFrameId_ << \"). Message frame was \" << msg->header.frame_id);\n    }\n  }\n\n  template<typename T>\n  void RosFilter<T>::enqueueMeasurement(const std::string &topicName,\n                                        const Eigen::VectorXd &measurement,\n                                        const Eigen::MatrixXd &measurementCovariance,\n                                        const std::vector<int> &updateVector,\n                                        const double mahalanobisThresh,\n                                        const ros::Time &time)\n  {\n    MeasurementPtr meas = MeasurementPtr(new Measurement());\n\n    meas->topicName_ = topicName;\n    meas->measurement_ = measurement;\n    meas->covariance_ = measurementCovariance;\n    meas->updateVector_ = updateVector;\n    meas->time_ = time.toSec();\n    meas->mahalanobisThresh_ = mahalanobisThresh;\n    meas->latestControl_ = latestControl_;\n    meas->latestControlTime_ = latestControlTime_.toSec();\n    measurementQueue_.push(meas);\n  }\n\n  template<typename T>\n  void RosFilter<T>::forceTwoD(Eigen::VectorXd &measurement,\n                               Eigen::MatrixXd &measurementCovariance,\n                               std::vector<int> &updateVector)\n  {\n    measurement(StateMemberZ) = 0.0;\n    measurement(StateMemberRoll) = 0.0;\n    measurement(StateMemberPitch) = 0.0;\n    measurement(StateMemberVz) = 0.0;\n    measurement(StateMemberVroll) = 0.0;\n    measurement(StateMemberVpitch) = 0.0;\n    measurement(StateMemberAz) = 0.0;\n\n    measurementCovariance(StateMemberZ, StateMemberZ) = 1e-6;\n    measurementCovariance(StateMemberRoll, StateMemberRoll) = 1e-6;\n    measurementCovariance(StateMemberPitch, StateMemberPitch) = 1e-6;\n    measurementCovariance(StateMemberVz, StateMemberVz) = 1e-6;\n    measurementCovariance(StateMemberVroll, StateMemberVroll) = 1e-6;\n    measurementCovariance(StateMemberVpitch, StateMemberVpitch) = 1e-6;\n    measurementCovariance(StateMemberAz, StateMemberAz) = 1e-6;\n\n    updateVector[StateMemberZ] = 1;\n    updateVector[StateMemberRoll] = 1;\n    updateVector[StateMemberPitch] = 1;\n    updateVector[StateMemberVz] = 1;\n    updateVector[StateMemberVroll] = 1;\n    updateVector[StateMemberVpitch] = 1;\n    updateVector[StateMemberAz] = 1;\n  }\n\n  template<typename T>\n  bool RosFilter<T>::getFilteredOdometryMessage(nav_msgs::Odometry &message)\n  {\n    // If the filter has received a measurement at some point...\n    if (filter_.getInitializedStatus())\n    {\n      // Grab our current state and covariance estimates\n      const Eigen::VectorXd &state = filter_.getState();\n      const Eigen::MatrixXd &estimateErrorCovariance = filter_.getEstimateErrorCovariance();\n\n      // Convert from roll, pitch, and yaw back to quaternion for\n      // orientation values\n      tf2::Quaternion quat;\n      quat.setRPY(state(StateMemberRoll), state(StateMemberPitch), state(StateMemberYaw));\n\n      // Fill out the message\n      message.pose.pose.position.x = state(StateMemberX);\n      message.pose.pose.position.y = state(StateMemberY);\n      message.pose.pose.position.z = state(StateMemberZ);\n      message.pose.pose.orientation.x = quat.x();\n      message.pose.pose.orientation.y = quat.y();\n      message.pose.pose.orientation.z = quat.z();\n      message.pose.pose.orientation.w = quat.w();\n      message.twist.twist.linear.x = state(StateMemberVx);\n      message.twist.twist.linear.y = state(StateMemberVy);\n      message.twist.twist.linear.z = state(StateMemberVz);\n      message.twist.twist.angular.x = state(StateMemberVroll);\n      message.twist.twist.angular.y = state(StateMemberVpitch);\n      message.twist.twist.angular.z = state(StateMemberVyaw);\n\n      // Our covariance matrix layout doesn't quite match\n      for (size_t i = 0; i < POSE_SIZE; i++)\n      {\n        for (size_t j = 0; j < POSE_SIZE; j++)\n        {\n          message.pose.covariance[POSE_SIZE * i + j] = estimateErrorCovariance(i, j);\n        }\n      }\n\n      // POSE_SIZE and TWIST_SIZE are currently the same size, but we can spare a few\n      // cycles to be meticulous and not index a twist covariance array on the size of\n      // a pose covariance array\n      for (size_t i = 0; i < TWIST_SIZE; i++)\n      {\n        for (size_t j = 0; j < TWIST_SIZE; j++)\n        {\n          message.twist.covariance[TWIST_SIZE * i + j] =\n              estimateErrorCovariance(i + POSITION_V_OFFSET, j + POSITION_V_OFFSET);\n        }\n      }\n\n      message.header.stamp = ros::Time(filter_.getLastMeasurementTime());\n      message.header.frame_id = worldFrameId_;\n      message.child_frame_id = baseLinkFrameId_;\n    }\n\n    return filter_.getInitializedStatus();\n  }\n\n  template<typename T>\n  bool RosFilter<T>::getFilteredAccelMessage(geometry_msgs::AccelWithCovarianceStamped &message)\n  {\n    // If the filter has received a measurement at some point...\n    if (filter_.getInitializedStatus())\n    {\n      // Grab our current state and covariance estimates\n      const Eigen::VectorXd &state = filter_.getState();\n      const Eigen::MatrixXd &estimateErrorCovariance = filter_.getEstimateErrorCovariance();\n\n      //! Fill out the accel_msg\n      message.accel.accel.linear.x = state(StateMemberAx);\n      message.accel.accel.linear.y = state(StateMemberAy);\n      message.accel.accel.linear.z = state(StateMemberAz);\n\n      // Fill the covariance (only the left-upper matrix since we are not estimating\n      // the rotational accelerations arround the axes\n      for (size_t i = 0; i < ACCELERATION_SIZE; i++)\n      {\n        for (size_t j = 0; j < ACCELERATION_SIZE; j++)\n        {\n          // We use the POSE_SIZE since the accel cov matrix of ROS is 6x6\n          message.accel.covariance[POSE_SIZE * i + j] =\n              estimateErrorCovariance(i + POSITION_A_OFFSET, j + POSITION_A_OFFSET);\n        }\n      }\n\n      // Fill header information\n      message.header.stamp = ros::Time(filter_.getLastMeasurementTime());\n      message.header.frame_id = baseLinkFrameId_;\n    }\n\n    return filter_.getInitializedStatus();\n  }\n\n  template<typename T>\n  void RosFilter<T>::imuCallback(const sensor_msgs::Imu::ConstPtr &msg,\n                                 const std::string &topicName,\n                                 const CallbackData &poseCallbackData,\n                                 const CallbackData &twistCallbackData,\n                                 const CallbackData &accelCallbackData)\n  {\n    RF_DEBUG(\"------ RosFilter::imuCallback (\" << topicName << \") ------\\n\" << \"IMU message:\\n\" << *msg);\n\n    // If we've just reset the filter, then we want to ignore any messages\n    // that arrive with an older timestamp\n    if (msg->header.stamp <= lastSetPoseTime_)\n    {\n      std::stringstream stream;\n      stream << \"The \" << topicName << \" message has a timestamp equal to or before the last filter reset, \" <<\n                \"this message will be ignored. This may indicate an empty or bad timestamp. (message time: \" <<\n                msg->header.stamp.toSec() << \")\";\n      addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                    topicName + \"_timestamp\",\n                    stream.str(),\n                    false);\n      RF_DEBUG(\"Received message that preceded the most recent pose reset. Ignoring...\");\n\n      return;\n    }\n\n    // As with the odometry message, we can separate out the pose- and twist-related variables\n    // in the IMU message and pass them to the pose and twist callbacks (filters)\n    if (poseCallbackData.updateSum_ > 0)\n    {\n      // Per the IMU message specification, if the IMU does not provide orientation,\n      // then its first covariance value should be set to -1, and we should ignore\n      // that portion of the message. robot_localization allows users to explicitly\n      // ignore data using its parameters, but we should also be compliant with\n      // message specs.\n      if (::fabs(msg->orientation_covariance[0] + 1) < 1e-9)\n      {\n        RF_DEBUG(\"Received IMU message with -1 as its first covariance value for orientation. \"\n                 \"Ignoring orientation...\");\n      }\n      else\n      {\n        // Extract the pose (orientation) data, pass it to its filter\n        geometry_msgs::PoseWithCovarianceStamped *posPtr = new geometry_msgs::PoseWithCovarianceStamped();\n        posPtr->header = msg->header;\n        posPtr->pose.pose.orientation = msg->orientation;\n\n        // Copy the covariance for roll, pitch, and yaw\n        for (size_t i = 0; i < ORIENTATION_SIZE; i++)\n        {\n          for (size_t j = 0; j < ORIENTATION_SIZE; j++)\n          {\n            posPtr->pose.covariance[POSE_SIZE * (i + ORIENTATION_SIZE) + (j + ORIENTATION_SIZE)] =\n                msg->orientation_covariance[ORIENTATION_SIZE * i + j];\n          }\n        }\n\n        // IMU data gets handled a bit differently, since the message is ambiguous and has only a single frame_id,\n        // even though the data in it is reported in two different frames. As we assume users will specify a base_link\n        // to imu transform, we make the target frame baseLinkFrameId_ and tell the poseCallback that it is working\n        // with IMU data. This will cause it to apply different logic to the data.\n        geometry_msgs::PoseWithCovarianceStampedConstPtr pptr(posPtr);\n        poseCallback(pptr, poseCallbackData, baseLinkFrameId_, true);\n      }\n    }\n\n    if (twistCallbackData.updateSum_ > 0)\n    {\n      // Ignore rotational velocity if the first covariance value is -1\n      if (::fabs(msg->angular_velocity_covariance[0] + 1) < 1e-9)\n      {\n        RF_DEBUG(\"Received IMU message with -1 as its first covariance value for angular \"\n                 \"velocity. Ignoring angular velocity...\");\n      }\n      else\n      {\n        // Repeat for velocity\n        geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped();\n        twistPtr->header = msg->header;\n        twistPtr->twist.twist.angular = msg->angular_velocity;\n\n        // Copy the covariance\n        for (size_t i = 0; i < ORIENTATION_SIZE; i++)\n        {\n          for (size_t j = 0; j < ORIENTATION_SIZE; j++)\n          {\n            twistPtr->twist.covariance[TWIST_SIZE * (i + ORIENTATION_SIZE) + (j + ORIENTATION_SIZE)] =\n              msg->angular_velocity_covariance[ORIENTATION_SIZE * i + j];\n          }\n        }\n\n        geometry_msgs::TwistWithCovarianceStampedConstPtr tptr(twistPtr);\n        twistCallback(tptr, twistCallbackData, baseLinkFrameId_);\n      }\n    }\n\n    if (accelCallbackData.updateSum_ > 0)\n    {\n      // Ignore linear acceleration if the first covariance value is -1\n      if (::fabs(msg->linear_acceleration_covariance[0] + 1) < 1e-9)\n      {\n        RF_DEBUG(\"Received IMU message with -1 as its first covariance value for linear \"\n                 \"acceleration. Ignoring linear acceleration...\");\n      }\n      else\n      {\n        // Pass the message on\n        accelerationCallback(msg, accelCallbackData, baseLinkFrameId_);\n      }\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::imuCallback (\" << topicName << \") ------\\n\");\n  }\n\n  template<typename T>\n  void RosFilter<T>::integrateMeasurements(const ros::Time &currentTime)\n  {\n    const double currentTimeSec = currentTime.toSec();\n\n    RF_DEBUG(\"------ RosFilter::integrateMeasurements ------\\n\\n\"\n             \"Integration time is \" << std::setprecision(20) << currentTimeSec << \"\\n\"\n             << measurementQueue_.size() << \" measurements in queue.\\n\");\n\n    bool predictToCurrentTime = predictToCurrentTime_;\n\n    // If we have any measurements in the queue, process them\n    if (!measurementQueue_.empty())\n    {\n      // Check if the first measurement we're going to process is older than the filter's last measurement.\n      // This means we have received an out-of-sequence message (one with an old timestamp), and we need to\n      // revert both the filter state and measurement queue to the first state that preceded the time stamp\n      // of our first measurement.\n      const MeasurementPtr& firstMeasurement = measurementQueue_.top();\n      int restoredMeasurementCount = 0;\n      if (smoothLaggedData_ && firstMeasurement->time_ < filter_.getLastMeasurementTime())\n      {\n        RF_DEBUG(\"Received a measurement that was \" << filter_.getLastMeasurementTime() - firstMeasurement->time_ <<\n                 \" seconds in the past. Reverting filter state and measurement queue...\");\n\n        int originalCount = static_cast<int>(measurementQueue_.size());\n        const double firstMeasurementTime =  firstMeasurement->time_;\n        const std::string firstMeasurementTopic =  firstMeasurement->topicName_;\n        if (!revertTo(firstMeasurement->time_ - 1e-9))  // revertTo may invalidate firstMeasurement\n        {\n          RF_DEBUG(\"ERROR: history interval is too small to revert to time \" << firstMeasurementTime << \"\\n\");\n          ROS_WARN_STREAM_DELAYED_THROTTLE(historyLength_, \"Received old measurement for topic \" <<\n              firstMeasurementTopic << \", but history interval is insufficiently sized to revert state and \"\n            \"measurement queue.\");\n          restoredMeasurementCount = 0;\n        }\n\n        restoredMeasurementCount = static_cast<int>(measurementQueue_.size()) - originalCount;\n      }\n\n      while (!measurementQueue_.empty() && ros::ok())\n      {\n        MeasurementPtr measurement = measurementQueue_.top();\n\n        // If we've reached a measurement that has a time later than now, it should wait until a future iteration.\n        // Since measurements are stored in a priority queue, all remaining measurements will be in the future.\n        if (measurement->time_ > currentTime.toSec())\n        {\n          break;\n        }\n\n        measurementQueue_.pop();\n\n        // When we receive control messages, we call this directly in the control callback. However, we also associate\n        // a control with each sensor message so that we can support lagged smoothing. As we cannot guarantee that the\n        // new control callback will fire before a new measurement, we should only perform this operation if we are\n        // processing messages from the history. Otherwise, we may get a new measurement, store the \"old\" latest\n        // control, then receive a control, call setControl, and then overwrite that value with this one (i.e., with\n        // the \"old\" control we associated with the measurement).\n        if (useControl_ && restoredMeasurementCount > 0)\n        {\n          filter_.setControl(measurement->latestControl_, measurement->latestControlTime_);\n          restoredMeasurementCount--;\n        }\n\n        // This will call predict and, if necessary, correct\n        filter_.processMeasurement(*(measurement.get()));\n\n        // Store old states and measurements if we're smoothing\n        if (smoothLaggedData_)\n        {\n          // Invariant still holds: measurementHistoryDeque_.back().time_ < measurementQueue_.top().time_\n          measurementHistory_.push_back(measurement);\n\n          // We should only save the filter state once per unique timstamp\n          if (measurementQueue_.empty() ||\n              ::fabs(measurementQueue_.top()->time_ - filter_.getLastMeasurementTime()) > 1e-9)\n          {\n            saveFilterState(filter_);\n          }\n        }\n      }\n    }\n    else if (filter_.getInitializedStatus())\n    {\n      // In the event that we don't get any measurements for a long time,\n      // we still need to continue to estimate our state. Therefore, we\n      // should project the state forward here.\n      double lastUpdateDelta = currentTimeSec - filter_.getLastMeasurementTime();\n\n      // If we get a large delta, then continuously predict until\n      if (lastUpdateDelta >= filter_.getSensorTimeout())\n      {\n        predictToCurrentTime = true;\n\n        RF_DEBUG(\"Sensor timeout! Last measurement time was \" << filter_.getLastMeasurementTime() <<\n                 \", current time is \" << currentTimeSec <<\n                 \", delta is \" << lastUpdateDelta << \"\\n\");\n      }\n    }\n    else\n    {\n      RF_DEBUG(\"Filter not yet initialized.\\n\");\n    }\n\n    if (filter_.getInitializedStatus() && predictToCurrentTime)\n    {\n      double lastUpdateDelta = currentTimeSec - filter_.getLastMeasurementTime();\n\n      filter_.validateDelta(lastUpdateDelta);\n      filter_.predict(currentTimeSec, lastUpdateDelta);\n\n      // Update the last measurement time and last update time\n      filter_.setLastMeasurementTime(filter_.getLastMeasurementTime() + lastUpdateDelta);\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::integrateMeasurements ------\\n\");\n  }\n\n  template<typename T>\n  void RosFilter<T>::loadParams()\n  {\n    /* For diagnostic purposes, collect information about how many different\n     * sources are measuring each absolute pose variable and do not have\n     * differential integration enabled.\n     */\n    std::map<StateMembers, int> absPoseVarCounts;\n    absPoseVarCounts[StateMemberX] = 0;\n    absPoseVarCounts[StateMemberY] = 0;\n    absPoseVarCounts[StateMemberZ] = 0;\n    absPoseVarCounts[StateMemberRoll] = 0;\n    absPoseVarCounts[StateMemberPitch] = 0;\n    absPoseVarCounts[StateMemberYaw] = 0;\n\n    // Same for twist variables\n    std::map<StateMembers, int> twistVarCounts;\n    twistVarCounts[StateMemberVx] = 0;\n    twistVarCounts[StateMemberVy] = 0;\n    twistVarCounts[StateMemberVz] = 0;\n    twistVarCounts[StateMemberVroll] = 0;\n    twistVarCounts[StateMemberVpitch] = 0;\n    twistVarCounts[StateMemberVyaw] = 0;\n\n    // Determine if we'll be printing diagnostic information\n    nhLocal_.param(\"print_diagnostics\", printDiagnostics_, true);\n\n    // Check for custom gravitational acceleration value\n    nhLocal_.param(\"gravitational_acceleration\", gravitationalAcc_, 9.80665);\n\n    // Grab the debug param. If true, the node will produce a LOT of output.\n    bool debug;\n    nhLocal_.param(\"debug\", debug, false);\n\n    if (debug)\n    {\n      std::string debugOutFile;\n\n      try\n      {\n        nhLocal_.param(\"debug_out_file\", debugOutFile, std::string(\"robot_localization_debug.txt\"));\n        debugStream_.open(debugOutFile.c_str());\n\n        // Make sure we succeeded\n        if (debugStream_.is_open())\n        {\n          filter_.setDebug(debug, &debugStream_);\n        }\n        else\n        {\n          ROS_WARN_STREAM(\"RosFilter::loadParams() - unable to create debug output file \" << debugOutFile);\n        }\n      }\n      catch(const std::exception &e)\n      {\n        ROS_WARN_STREAM(\"RosFilter::loadParams() - unable to create debug output file\" << debugOutFile\n                        << \". Error was \" << e.what() << \"\\n\");\n      }\n    }\n\n    // These params specify the name of the robot's body frame (typically\n    // base_link) and odometry frame (typically odom)\n    nhLocal_.param(\"map_frame\", mapFrameId_, std::string(\"map\"));\n    nhLocal_.param(\"odom_frame\", odomFrameId_, std::string(\"odom\"));\n    nhLocal_.param(\"base_link_frame\", baseLinkFrameId_, std::string(\"base_link\"));\n\n    /*\n     * These parameters are designed to enforce compliance with REP-105:\n     * http://www.ros.org/reps/rep-0105.html\n     * When fusing absolute position data from sensors such as GPS, the state\n     * estimate can undergo discrete jumps. According to REP-105, we want three\n     * coordinate frames: map, odom, and base_link. The map frame can have\n     * discontinuities, but is the frame with the most accurate position estimate\n     * for the robot and should not suffer from drift. The odom frame drifts over\n     * time, but is guaranteed to be continuous and is accurate enough for local\n     * planning and navigation. The base_link frame is affixed to the robot. The\n     * intention is that some odometry source broadcasts the odom->base_link\n     * transform. The localization software should broadcast map->base_link.\n     * However, tf does not allow multiple parents for a coordinate frame, so\n     * we must *compute* map->base_link, but then use the existing odom->base_link\n     * transform to compute *and broadcast* map->odom.\n     *\n     * The state estimation nodes in robot_localization therefore have two \"modes.\"\n     * If your world_frame parameter value matches the odom_frame parameter value,\n     * then robot_localization will assume someone else is broadcasting a transform\n     * from odom_frame->base_link_frame, and it will compute the\n     * map_frame->odom_frame transform. Otherwise, it will simply compute the\n     * odom_frame->base_link_frame transform.\n     *\n     * The default is the latter behavior (broadcast of odom->base_link).\n     */\n    nhLocal_.param(\"world_frame\", worldFrameId_, odomFrameId_);\n\n    ROS_FATAL_COND(mapFrameId_ == odomFrameId_ ||\n                   odomFrameId_ == baseLinkFrameId_ ||\n                   mapFrameId_ == baseLinkFrameId_,\n                   \"Invalid frame configuration! The values for map_frame, odom_frame, \"\n                   \"and base_link_frame must be unique\");\n\n    // Try to resolve tf_prefix\n    std::string tfPrefix = \"\";\n    std::string tfPrefixPath = \"\";\n    if (nhLocal_.searchParam(\"tf_prefix\", tfPrefixPath))\n    {\n      nhLocal_.getParam(tfPrefixPath, tfPrefix);\n    }\n\n    // Append the tf prefix in a tf2-friendly manner\n    FilterUtilities::appendPrefix(tfPrefix, mapFrameId_);\n    FilterUtilities::appendPrefix(tfPrefix, odomFrameId_);\n    FilterUtilities::appendPrefix(tfPrefix, baseLinkFrameId_);\n    FilterUtilities::appendPrefix(tfPrefix, worldFrameId_);\n\n    // Whether we're publshing the world_frame->base_link_frame transform\n    nhLocal_.param(\"publish_tf\", publishTransform_, true);\n\n    // Whether we're publishing the acceleration state transform\n    nhLocal_.param(\"publish_acceleration\", publishAcceleration_, false);\n\n    // Transform future dating\n    double offsetTmp;\n    nhLocal_.param(\"transform_time_offset\", offsetTmp, 0.0);\n    tfTimeOffset_.fromSec(offsetTmp);\n\n    // Transform timeout\n    double timeoutTmp;\n    nhLocal_.param(\"transform_timeout\", timeoutTmp, 0.0);\n    tfTimeout_.fromSec(timeoutTmp);\n\n    // Update frequency and sensor timeout\n    double sensorTimeout;\n    nhLocal_.param(\"frequency\", frequency_, 30.0);\n    nhLocal_.param(\"sensor_timeout\", sensorTimeout, 1.0 / frequency_);\n    filter_.setSensorTimeout(sensorTimeout);\n\n    // Determine if we're in 2D mode\n    nhLocal_.param(\"two_d_mode\", twoDMode_, false);\n\n    // Smoothing window size\n    nhLocal_.param(\"smooth_lagged_data\", smoothLaggedData_, false);\n    nhLocal_.param(\"history_length\", historyLength_, 0.0);\n\n    // Wether we reset filter on jump back in time\n    nhLocal_.param(\"reset_on_time_jump\", resetOnTimeJump_, false);\n\n    if (!smoothLaggedData_ && ::fabs(historyLength_) > 1e-9)\n    {\n      ROS_WARN_STREAM(\"Filter history interval of \" << historyLength_ <<\n                      \" specified, but smooth_lagged_data is set to false. Lagged data will not be smoothed.\");\n    }\n\n    if (smoothLaggedData_ && historyLength_ < -1e9)\n    {\n      ROS_WARN_STREAM(\"Negative history interval of \" << historyLength_ <<\n                      \" specified. Absolute value will be assumed.\");\n    }\n\n    historyLength_ = ::fabs(historyLength_);\n\n    nhLocal_.param(\"predict_to_current_time\", predictToCurrentTime_, false);\n\n    // Determine if we're using a control term\n    bool stampedControl = false;\n    double controlTimeout = sensorTimeout;\n    std::vector<int> controlUpdateVector(TWIST_SIZE, 0);\n    std::vector<double> accelerationLimits(TWIST_SIZE, 1.0);\n    std::vector<double> accelerationGains(TWIST_SIZE, 1.0);\n    std::vector<double> decelerationLimits(TWIST_SIZE, 1.0);\n    std::vector<double> decelerationGains(TWIST_SIZE, 1.0);\n\n    nhLocal_.param(\"use_control\", useControl_, false);\n    nhLocal_.param(\"stamped_control\", stampedControl, false);\n    nhLocal_.param(\"control_timeout\", controlTimeout, sensorTimeout);\n\n    if (useControl_)\n    {\n      if (nhLocal_.getParam(\"control_config\", controlUpdateVector))\n      {\n        if (controlUpdateVector.size() != TWIST_SIZE)\n        {\n          ROS_ERROR_STREAM(\"Control configuration must be of size \" << TWIST_SIZE << \". Provided config was of \"\n            \"size \" << controlUpdateVector.size() << \". No control term will be used.\");\n          useControl_ = false;\n        }\n      }\n      else\n      {\n        ROS_ERROR_STREAM(\"use_control is set to true, but control_config is missing. No control term will be used.\");\n        useControl_ = false;\n      }\n\n      if (nhLocal_.getParam(\"acceleration_limits\", accelerationLimits))\n      {\n        if (accelerationLimits.size() != TWIST_SIZE)\n        {\n          ROS_ERROR_STREAM(\"Acceleration configuration must be of size \" << TWIST_SIZE << \". Provided config was of \"\n            \"size \" << accelerationLimits.size() << \". No control term will be used.\");\n          useControl_ = false;\n        }\n      }\n      else\n      {\n        ROS_WARN_STREAM(\"use_control is set to true, but acceleration_limits is missing. Will use default values.\");\n      }\n\n      if (nhLocal_.getParam(\"acceleration_gains\", accelerationGains))\n      {\n        const int size = accelerationGains.size();\n        if (size != TWIST_SIZE)\n        {\n          ROS_ERROR_STREAM(\"Acceleration gain configuration must be of size \" << TWIST_SIZE <<\n            \". Provided config was of size \" << size << \". All gains will be assumed to be 1.\");\n          std::fill_n(accelerationGains.begin(), std::min(size, TWIST_SIZE), 1.0);\n          accelerationGains.resize(TWIST_SIZE, 1.0);\n        }\n      }\n\n      if (nhLocal_.getParam(\"deceleration_limits\", decelerationLimits))\n      {\n        if (decelerationLimits.size() != TWIST_SIZE)\n        {\n          ROS_ERROR_STREAM(\"Deceleration configuration must be of size \" << TWIST_SIZE <<\n            \". Provided config was of size \" << decelerationLimits.size() << \". No control term will be used.\");\n          useControl_ = false;\n        }\n      }\n      else\n      {\n        ROS_INFO_STREAM(\"use_control is set to true, but no deceleration_limits specified. Will use acceleration \"\n          \"limits.\");\n        decelerationLimits = accelerationLimits;\n      }\n\n      if (nhLocal_.getParam(\"deceleration_gains\", decelerationGains))\n      {\n        const int size = decelerationGains.size();\n        if (size != TWIST_SIZE)\n        {\n          ROS_ERROR_STREAM(\"Deceleration gain configuration must be of size \" << TWIST_SIZE <<\n            \". Provided config was of size \" << size << \". All gains will be assumed to be 1.\");\n          std::fill_n(decelerationGains.begin(), std::min(size, TWIST_SIZE), 1.0);\n          decelerationGains.resize(TWIST_SIZE, 1.0);\n        }\n      }\n      else\n      {\n        ROS_INFO_STREAM(\"use_control is set to true, but no deceleration_gains specified. Will use acceleration \"\n          \"gains.\");\n        decelerationGains = accelerationGains;\n      }\n    }\n\n    bool dynamicProcessNoiseCovariance = false;\n    nhLocal_.param(\"dynamic_process_noise_covariance\", dynamicProcessNoiseCovariance, false);\n    filter_.setUseDynamicProcessNoiseCovariance(dynamicProcessNoiseCovariance);\n\n    std::vector<double> initialState(STATE_SIZE, 0.0);\n    if (nhLocal_.getParam(\"initial_state\", initialState))\n    {\n      if (initialState.size() != STATE_SIZE)\n      {\n        ROS_ERROR_STREAM(\"Initial state must be of size \" << STATE_SIZE << \". Provided config was of size \" <<\n          initialState.size() << \". The initial state will be ignored.\");\n      }\n      else\n      {\n        Eigen::Map<Eigen::VectorXd> eigenState(initialState.data(), initialState.size());\n        filter_.setState(eigenState);\n      }\n    }\n\n    // Check if the filter should start or not\n    nhLocal_.param(\"disabled_at_startup\", disabledAtStartup_, false);\n    enabled_ = !disabledAtStartup_;\n\n\n    // Debugging writes to file\n    RF_DEBUG(\"tf_prefix is \" << tfPrefix <<\n             \"\\nmap_frame is \" << mapFrameId_ <<\n             \"\\nodom_frame is \" << odomFrameId_ <<\n             \"\\nbase_link_frame is \" << baseLinkFrameId_ <<\n             \"\\nworld_frame is \" << worldFrameId_ <<\n             \"\\ntransform_time_offset is \" << tfTimeOffset_.toSec() <<\n             \"\\ntransform_timeout is \" << tfTimeout_.toSec() <<\n             \"\\nfrequency is \" << frequency_ <<\n             \"\\nsensor_timeout is \" << filter_.getSensorTimeout() <<\n             \"\\ntwo_d_mode is \" << (twoDMode_ ? \"true\" : \"false\") <<\n             \"\\nsmooth_lagged_data is \" << (smoothLaggedData_ ? \"true\" : \"false\") <<\n             \"\\nhistory_length is \" << historyLength_ <<\n             \"\\nuse_control is \" << (useControl_ ? \"true\" : \"false\") <<\n             \"\\nstamped_control is \" << (stampedControl ? \"true\" : \"false\") <<\n             \"\\ncontrol_config is \" << controlUpdateVector <<\n             \"\\ncontrol_timeout is \" << controlTimeout <<\n             \"\\nacceleration_limits are \" << accelerationLimits <<\n             \"\\nacceleration_gains are \" << accelerationGains <<\n             \"\\ndeceleration_limits are \" << decelerationLimits <<\n             \"\\ndeceleration_gains are \" << decelerationGains <<\n             \"\\ninitial state is \" << filter_.getState() <<\n             \"\\ndynamic_process_noise_covariance is \" << (dynamicProcessNoiseCovariance ? \"true\" : \"false\") <<\n             \"\\nprint_diagnostics is \" << (printDiagnostics_ ? \"true\" : \"false\") << \"\\n\");\n\n    // Create a subscriber for manually setting/resetting pose\n    setPoseSub_ = nh_.subscribe(\"set_pose\",\n                                1,\n                                &RosFilter<T>::setPoseCallback,\n                                this, ros::TransportHints().tcpNoDelay(false));\n\n    // Create a service for manually setting/resetting pose\n    setPoseSrv_ = nh_.advertiseService(\"set_pose\", &RosFilter<T>::setPoseSrvCallback, this);\n\n    // Create a service for manually enabling the filter\n    enableFilterSrv_ = nhLocal_.advertiseService(\"enable\", &RosFilter<T>::enableFilterSrvCallback, this);\n\n    // Init the last last measurement time so we don't get a huge initial delta\n    filter_.setLastMeasurementTime(ros::Time::now().toSec());\n\n    // Now pull in each topic to which we want to subscribe.\n    // Start with odom.\n    size_t topicInd = 0;\n    bool moreParams = false;\n    do\n    {\n      // Build the string in the form of \"odomX\", where X is the odom topic number,\n      // then check if we have any parameters with that value. Users need to make\n      // sure they don't have gaps in their configs (e.g., odom0 and then odom2)\n      std::stringstream ss;\n      ss << \"odom\" << topicInd++;\n      std::string odomTopicName = ss.str();\n      moreParams = nhLocal_.hasParam(odomTopicName);\n\n      if (moreParams)\n      {\n        // Determine if we want to integrate this sensor differentially\n        bool differential;\n        nhLocal_.param(odomTopicName + std::string(\"_differential\"), differential, false);\n\n        // Determine if we want to integrate this sensor relatively\n        bool relative;\n        nhLocal_.param(odomTopicName + std::string(\"_relative\"), relative, false);\n\n        if (relative && differential)\n        {\n          ROS_WARN_STREAM(\"Both \" << odomTopicName << \"_differential\" << \" and \" << odomTopicName <<\n                          \"_relative were set to true. Using differential mode.\");\n\n          relative = false;\n        }\n\n        std::string odomTopic;\n        nhLocal_.getParam(odomTopicName, odomTopic);\n\n        // Check for pose rejection threshold\n        double poseMahalanobisThresh;\n        nhLocal_.param(odomTopicName + std::string(\"_pose_rejection_threshold\"),\n                       poseMahalanobisThresh,\n                       std::numeric_limits<double>::max());\n\n        // Check for twist rejection threshold\n        double twistMahalanobisThresh;\n        nhLocal_.param(odomTopicName + std::string(\"_twist_rejection_threshold\"),\n                       twistMahalanobisThresh,\n                       std::numeric_limits<double>::max());\n\n        // Now pull in its boolean update vector configuration. Create separate vectors for pose\n        // and twist data, and then zero out the opposite values in each vector (no pose data in\n        // the twist update vector and vice-versa).\n        std::vector<int> updateVec = loadUpdateConfig(odomTopicName);\n        std::vector<int> poseUpdateVec = updateVec;\n        std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET, poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE, 0);\n        std::vector<int> twistUpdateVec = updateVec;\n        std::fill(twistUpdateVec.begin() + POSITION_OFFSET, twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, 0);\n\n        int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0);\n        int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0);\n        int odomQueueSize = 1;\n        nhLocal_.param(odomTopicName + \"_queue_size\", odomQueueSize, 1);\n\n        const CallbackData poseCallbackData(odomTopicName + \"_pose\", poseUpdateVec, poseUpdateSum, differential,\n          relative, poseMahalanobisThresh);\n        const CallbackData twistCallbackData(odomTopicName + \"_twist\", twistUpdateVec, twistUpdateSum, false, false,\n          twistMahalanobisThresh);\n\n        bool nodelayOdom = false;\n        nhLocal_.param(odomTopicName + \"_nodelay\", nodelayOdom, false);\n\n        // Store the odometry topic subscribers so they don't go out of scope.\n        if (poseUpdateSum + twistUpdateSum > 0)\n        {\n          topicSubs_.push_back(\n            nh_.subscribe<nav_msgs::Odometry>(odomTopic, odomQueueSize,\n              boost::bind(&RosFilter::odometryCallback, this, _1, odomTopicName, poseCallbackData, twistCallbackData),\n              ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayOdom)));\n        }\n        else\n        {\n          std::stringstream stream;\n          stream << odomTopic << \" is listed as an input topic, but all update variables are false\";\n\n          addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                        odomTopic + \"_configuration\",\n                        stream.str(),\n                        true);\n        }\n\n        if (poseUpdateSum > 0)\n        {\n          if (differential)\n          {\n            twistVarCounts[StateMemberVx] += poseUpdateVec[StateMemberX];\n            twistVarCounts[StateMemberVy] += poseUpdateVec[StateMemberY];\n            twistVarCounts[StateMemberVz] += poseUpdateVec[StateMemberZ];\n            twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll];\n            twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch];\n            twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw];\n          }\n          else\n          {\n            absPoseVarCounts[StateMemberX] += poseUpdateVec[StateMemberX];\n            absPoseVarCounts[StateMemberY] += poseUpdateVec[StateMemberY];\n            absPoseVarCounts[StateMemberZ] += poseUpdateVec[StateMemberZ];\n            absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll];\n            absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch];\n            absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw];\n          }\n        }\n\n        if (twistUpdateSum > 0)\n        {\n          twistVarCounts[StateMemberVx] += twistUpdateVec[StateMemberVx];\n          twistVarCounts[StateMemberVy] += twistUpdateVec[StateMemberVx];\n          twistVarCounts[StateMemberVz] += twistUpdateVec[StateMemberVz];\n          twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll];\n          twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch];\n          twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw];\n        }\n\n        RF_DEBUG(\"Subscribed to \" << odomTopic << \" (\" << odomTopicName << \")\\n\\t\" <<\n                 odomTopicName << \"_differential is \" << (differential ? \"true\" : \"false\") << \"\\n\\t\" <<\n                 odomTopicName << \"_pose_rejection_threshold is \" << poseMahalanobisThresh << \"\\n\\t\" <<\n                 odomTopicName << \"_twist_rejection_threshold is \" << twistMahalanobisThresh << \"\\n\\t\" <<\n                 odomTopicName << \"_queue_size is \" << odomQueueSize << \"\\n\\t\" <<\n                 odomTopicName << \" pose update vector is \" << poseUpdateVec << \"\\t\"<<\n                 odomTopicName << \" twist update vector is \" << twistUpdateVec);\n      }\n    }\n    while (moreParams);\n\n    // Repeat for pose\n    topicInd = 0;\n    moreParams = false;\n    do\n    {\n      std::stringstream ss;\n      ss << \"pose\" << topicInd++;\n      std::string poseTopicName = ss.str();\n      moreParams = nhLocal_.hasParam(poseTopicName);\n\n      if (moreParams)\n      {\n        bool differential;\n        nhLocal_.param(poseTopicName + std::string(\"_differential\"), differential, false);\n\n        // Determine if we want to integrate this sensor relatively\n        bool relative;\n        nhLocal_.param(poseTopicName + std::string(\"_relative\"), relative, false);\n\n        if (relative && differential)\n        {\n          ROS_WARN_STREAM(\"Both \" << poseTopicName << \"_differential\" << \" and \" << poseTopicName <<\n                          \"_relative were set to true. Using differential mode.\");\n\n          relative = false;\n        }\n\n        std::string poseTopic;\n        nhLocal_.getParam(poseTopicName, poseTopic);\n\n        // Check for pose rejection threshold\n        double poseMahalanobisThresh;\n        nhLocal_.param(poseTopicName + std::string(\"_rejection_threshold\"),\n                       poseMahalanobisThresh,\n                       std::numeric_limits<double>::max());\n\n        int poseQueueSize = 1;\n        nhLocal_.param(poseTopicName + \"_queue_size\", poseQueueSize, 1);\n\n        bool nodelayPose = false;\n        nhLocal_.param(poseTopicName + \"_nodelay\", nodelayPose, false);\n\n        // Pull in the sensor's config, zero out values that are invalid for the pose type\n        std::vector<int> poseUpdateVec = loadUpdateConfig(poseTopicName);\n        std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET,\n                  poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE,\n                  0);\n        std::fill(poseUpdateVec.begin() + POSITION_A_OFFSET,\n                  poseUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE,\n                  0);\n\n        int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0);\n\n        if (poseUpdateSum > 0)\n        {\n          const CallbackData callbackData(poseTopicName, poseUpdateVec, poseUpdateSum, differential, relative,\n            poseMahalanobisThresh);\n\n          topicSubs_.push_back(\n            nh_.subscribe<geometry_msgs::PoseWithCovarianceStamped>(poseTopic, poseQueueSize,\n              boost::bind(&RosFilter::poseCallback, this, _1, callbackData, worldFrameId_, false),\n              ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayPose)));\n\n          if (differential)\n          {\n            twistVarCounts[StateMemberVx] += poseUpdateVec[StateMemberX];\n            twistVarCounts[StateMemberVy] += poseUpdateVec[StateMemberY];\n            twistVarCounts[StateMemberVz] += poseUpdateVec[StateMemberZ];\n            twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll];\n            twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch];\n            twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw];\n          }\n          else\n          {\n            absPoseVarCounts[StateMemberX] += poseUpdateVec[StateMemberX];\n            absPoseVarCounts[StateMemberY] += poseUpdateVec[StateMemberY];\n            absPoseVarCounts[StateMemberZ] += poseUpdateVec[StateMemberZ];\n            absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll];\n            absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch];\n            absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw];\n          }\n        }\n        else\n        {\n          ROS_WARN_STREAM(\"Warning: \" << poseTopic << \" is listed as an input topic, \"\n                          \"but all pose update variables are false\");\n        }\n\n        RF_DEBUG(\"Subscribed to \" << poseTopic << \" (\" << poseTopicName << \")\\n\\t\" <<\n                 poseTopicName << \"_differential is \" << (differential ? \"true\" : \"false\") << \"\\n\\t\" <<\n                 poseTopicName << \"_rejection_threshold is \" << poseMahalanobisThresh << \"\\n\\t\" <<\n                 poseTopicName << \"_queue_size is \" << poseQueueSize << \"\\n\\t\" <<\n                 poseTopicName << \" update vector is \" << poseUpdateVec);\n      }\n    }\n    while (moreParams);\n\n    // Repeat for twist\n    topicInd = 0;\n    moreParams = false;\n    do\n    {\n      std::stringstream ss;\n      ss << \"twist\" << topicInd++;\n      std::string twistTopicName = ss.str();\n      moreParams = nhLocal_.hasParam(twistTopicName);\n\n      if (moreParams)\n      {\n        std::string twistTopic;\n        nhLocal_.getParam(twistTopicName, twistTopic);\n\n        // Check for twist rejection threshold\n        double twistMahalanobisThresh;\n        nhLocal_.param(twistTopicName + std::string(\"_rejection_threshold\"),\n                       twistMahalanobisThresh,\n                       std::numeric_limits<double>::max());\n\n        int twistQueueSize = 1;\n        nhLocal_.param(twistTopicName + \"_queue_size\", twistQueueSize, 1);\n\n        bool nodelayTwist = false;\n        nhLocal_.param(twistTopicName + \"_nodelay\", nodelayTwist, false);\n\n        // Pull in the sensor's config, zero out values that are invalid for the twist type\n        std::vector<int> twistUpdateVec = loadUpdateConfig(twistTopicName);\n        std::fill(twistUpdateVec.begin() + POSITION_OFFSET, twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE, 0);\n\n        int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0);\n\n        if (twistUpdateSum > 0)\n        {\n          const CallbackData callbackData(twistTopicName, twistUpdateVec, twistUpdateSum, false, false,\n            twistMahalanobisThresh);\n\n          topicSubs_.push_back(\n            nh_.subscribe<geometry_msgs::TwistWithCovarianceStamped>(twistTopic, twistQueueSize,\n              boost::bind(&RosFilter<T>::twistCallback, this, _1, callbackData, baseLinkFrameId_),\n              ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayTwist)));\n\n          twistVarCounts[StateMemberVx] += twistUpdateVec[StateMemberVx];\n          twistVarCounts[StateMemberVy] += twistUpdateVec[StateMemberVy];\n          twistVarCounts[StateMemberVz] += twistUpdateVec[StateMemberVz];\n          twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll];\n          twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch];\n          twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw];\n        }\n        else\n        {\n          ROS_WARN_STREAM(\"Warning: \" << twistTopic << \" is listed as an input topic, \"\n                          \"but all twist update variables are false\");\n        }\n\n        RF_DEBUG(\"Subscribed to \" << twistTopic << \" (\" << twistTopicName << \")\\n\\t\" <<\n                 twistTopicName << \"_rejection_threshold is \" << twistMahalanobisThresh << \"\\n\\t\" <<\n                 twistTopicName << \"_queue_size is \" << twistQueueSize << \"\\n\\t\" <<\n                 twistTopicName << \" update vector is \" << twistUpdateVec);\n      }\n    }\n    while (moreParams);\n\n    // Repeat for IMU\n    topicInd = 0;\n    moreParams = false;\n    do\n    {\n      std::stringstream ss;\n      ss << \"imu\" << topicInd++;\n      std::string imuTopicName = ss.str();\n      moreParams = nhLocal_.hasParam(imuTopicName);\n\n      if (moreParams)\n      {\n        bool differential;\n        nhLocal_.param(imuTopicName + std::string(\"_differential\"), differential, false);\n\n        // Determine if we want to integrate this sensor relatively\n        bool relative;\n        nhLocal_.param(imuTopicName + std::string(\"_relative\"), relative, false);\n\n        if (relative && differential)\n        {\n          ROS_WARN_STREAM(\"Both \" << imuTopicName << \"_differential\" << \" and \" << imuTopicName <<\n                          \"_relative were set to true. Using differential mode.\");\n\n          relative = false;\n        }\n\n        std::string imuTopic;\n        nhLocal_.getParam(imuTopicName, imuTopic);\n\n        // Check for pose rejection threshold\n        double poseMahalanobisThresh;\n        nhLocal_.param(imuTopicName + std::string(\"_pose_rejection_threshold\"),\n                       poseMahalanobisThresh,\n                       std::numeric_limits<double>::max());\n\n        // Check for angular velocity rejection threshold\n        double twistMahalanobisThresh;\n        std::string imuTwistRejectionName =\n          imuTopicName + std::string(\"_twist_rejection_threshold\");\n        nhLocal_.param(imuTwistRejectionName, twistMahalanobisThresh, std::numeric_limits<double>::max());\n\n        // Check for acceleration rejection threshold\n        double accelMahalanobisThresh;\n        nhLocal_.param(imuTopicName + std::string(\"_linear_acceleration_rejection_threshold\"),\n                       accelMahalanobisThresh,\n                       std::numeric_limits<double>::max());\n\n        bool removeGravAcc = false;\n        nhLocal_.param(imuTopicName + \"_remove_gravitational_acceleration\", removeGravAcc, false);\n        removeGravitationalAcc_[imuTopicName + \"_acceleration\"] = removeGravAcc;\n\n        // Now pull in its boolean update vector configuration and differential\n        // update configuration (as this contains pose information)\n        std::vector<int> updateVec = loadUpdateConfig(imuTopicName);\n\n        std::vector<int> poseUpdateVec = updateVec;\n        std::fill(poseUpdateVec.begin() + POSITION_V_OFFSET,\n                  poseUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE,\n                  0);\n        std::fill(poseUpdateVec.begin() + POSITION_A_OFFSET,\n                  poseUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE,\n                  0);\n\n        std::vector<int> twistUpdateVec = updateVec;\n        std::fill(twistUpdateVec.begin() + POSITION_OFFSET,\n                  twistUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE,\n                  0);\n        std::fill(twistUpdateVec.begin() + POSITION_A_OFFSET,\n                  twistUpdateVec.begin() + POSITION_A_OFFSET + ACCELERATION_SIZE,\n                  0);\n\n        std::vector<int> accelUpdateVec = updateVec;\n        std::fill(accelUpdateVec.begin() + POSITION_OFFSET,\n                  accelUpdateVec.begin() + POSITION_OFFSET + POSE_SIZE,\n                  0);\n        std::fill(accelUpdateVec.begin() + POSITION_V_OFFSET,\n                  accelUpdateVec.begin() + POSITION_V_OFFSET + TWIST_SIZE,\n                  0);\n\n        int poseUpdateSum = std::accumulate(poseUpdateVec.begin(), poseUpdateVec.end(), 0);\n        int twistUpdateSum = std::accumulate(twistUpdateVec.begin(), twistUpdateVec.end(), 0);\n        int accelUpdateSum = std::accumulate(accelUpdateVec.begin(), accelUpdateVec.end(), 0);\n\n        // Check if we're using control input for any of the acceleration variables; turn off if so\n        if (static_cast<bool>(controlUpdateVector[ControlMemberVx]) && static_cast<bool>(accelUpdateVec[StateMemberAx]))\n        {\n          ROS_WARN_STREAM(\"X acceleration is being measured from IMU; X velocity control input is disabled\");\n          controlUpdateVector[ControlMemberVx] = 0;\n        }\n        if (static_cast<bool>(controlUpdateVector[ControlMemberVy]) && static_cast<bool>(accelUpdateVec[StateMemberAy]))\n        {\n          ROS_WARN_STREAM(\"Y acceleration is being measured from IMU; Y velocity control input is disabled\");\n          controlUpdateVector[ControlMemberVy] = 0;\n        }\n        if (static_cast<bool>(controlUpdateVector[ControlMemberVz]) && static_cast<bool>(accelUpdateVec[StateMemberAz]))\n        {\n          ROS_WARN_STREAM(\"Z acceleration is being measured from IMU; Z velocity control input is disabled\");\n          controlUpdateVector[ControlMemberVz] = 0;\n        }\n\n        int imuQueueSize = 1;\n        nhLocal_.param(imuTopicName + \"_queue_size\", imuQueueSize, 1);\n\n        bool nodelayImu = false;\n        nhLocal_.param(imuTopicName + \"_nodelay\", nodelayImu, false);\n\n        if (poseUpdateSum + twistUpdateSum + accelUpdateSum > 0)\n        {\n          const CallbackData poseCallbackData(imuTopicName + \"_pose\", poseUpdateVec, poseUpdateSum, differential,\n            relative, poseMahalanobisThresh);\n          const CallbackData twistCallbackData(imuTopicName + \"_twist\", twistUpdateVec, twistUpdateSum, differential,\n            relative, twistMahalanobisThresh);\n          const CallbackData accelCallbackData(imuTopicName + \"_acceleration\", accelUpdateVec, accelUpdateSum,\n            differential, relative, accelMahalanobisThresh);\n\n          topicSubs_.push_back(\n            nh_.subscribe<sensor_msgs::Imu>(imuTopic, imuQueueSize,\n              boost::bind(&RosFilter<T>::imuCallback, this, _1, imuTopicName, poseCallbackData, twistCallbackData,\n                accelCallbackData), ros::VoidPtr(), ros::TransportHints().tcpNoDelay(nodelayImu)));\n        }\n        else\n        {\n          ROS_WARN_STREAM(\"Warning: \" << imuTopic << \" is listed as an input topic, \"\n                          \"but all its update variables are false\");\n        }\n\n        if (poseUpdateSum > 0)\n        {\n          if (differential)\n          {\n            twistVarCounts[StateMemberVroll] += poseUpdateVec[StateMemberRoll];\n            twistVarCounts[StateMemberVpitch] += poseUpdateVec[StateMemberPitch];\n            twistVarCounts[StateMemberVyaw] += poseUpdateVec[StateMemberYaw];\n          }\n          else\n          {\n            absPoseVarCounts[StateMemberRoll] += poseUpdateVec[StateMemberRoll];\n            absPoseVarCounts[StateMemberPitch] += poseUpdateVec[StateMemberPitch];\n            absPoseVarCounts[StateMemberYaw] += poseUpdateVec[StateMemberYaw];\n          }\n        }\n\n        if (twistUpdateSum > 0)\n        {\n          twistVarCounts[StateMemberVroll] += twistUpdateVec[StateMemberVroll];\n          twistVarCounts[StateMemberVpitch] += twistUpdateVec[StateMemberVpitch];\n          twistVarCounts[StateMemberVyaw] += twistUpdateVec[StateMemberVyaw];\n        }\n\n        RF_DEBUG(\"Subscribed to \" << imuTopic << \" (\" << imuTopicName << \")\\n\\t\" <<\n                 imuTopicName << \"_differential is \" << (differential ? \"true\" : \"false\") << \"\\n\\t\" <<\n                 imuTopicName << \"_pose_rejection_threshold is \" << poseMahalanobisThresh << \"\\n\\t\" <<\n                 imuTopicName << \"_twist_rejection_threshold is \" << twistMahalanobisThresh << \"\\n\\t\" <<\n                 imuTopicName << \"_linear_acceleration_rejection_threshold is \" << accelMahalanobisThresh << \"\\n\\t\" <<\n                 imuTopicName << \"_remove_gravitational_acceleration is \" <<\n                                 (removeGravAcc ? \"true\" : \"false\") << \"\\n\\t\" <<\n                 imuTopicName << \"_queue_size is \" << imuQueueSize << \"\\n\\t\" <<\n                 imuTopicName << \" pose update vector is \" << poseUpdateVec << \"\\t\"<<\n                 imuTopicName << \" twist update vector is \" << twistUpdateVec << \"\\t\" <<\n                 imuTopicName << \" acceleration update vector is \" << accelUpdateVec);\n      }\n    }\n    while (moreParams);\n\n    // Now that we've checked if IMU linear acceleration is being used, we can determine our final control parameters\n    if (useControl_ && std::accumulate(controlUpdateVector.begin(), controlUpdateVector.end(), 0) == 0)\n    {\n      ROS_ERROR_STREAM(\"use_control is set to true, but control_config has only false values. No control term \"\n        \"will be used.\");\n      useControl_ = false;\n    }\n\n    // If we're using control, set the parameters and create the necessary subscribers\n    if (useControl_)\n    {\n      latestControl_.resize(TWIST_SIZE);\n      latestControl_.setZero();\n\n      filter_.setControlParams(controlUpdateVector, controlTimeout, accelerationLimits, accelerationGains,\n        decelerationLimits, decelerationGains);\n\n      if (stampedControl)\n      {\n        controlSub_ = nh_.subscribe<geometry_msgs::TwistStamped>(\"cmd_vel\", 1, &RosFilter<T>::controlCallback, this);\n      }\n      else\n      {\n        controlSub_ = nh_.subscribe<geometry_msgs::Twist>(\"cmd_vel\", 1, &RosFilter<T>::controlCallback, this);\n      }\n    }\n\n    /* Warn users about:\n    *    1. Multiple non-differential input sources\n    *    2. No absolute *or* velocity measurements for pose variables\n    */\n    if (printDiagnostics_)\n    {\n      for (int stateVar = StateMemberX; stateVar <= StateMemberYaw; ++stateVar)\n      {\n        if (absPoseVarCounts[static_cast<StateMembers>(stateVar)] > 1)\n        {\n          std::stringstream stream;\n          stream <<  absPoseVarCounts[static_cast<StateMembers>(stateVar - POSITION_OFFSET)] <<\n              \" absolute pose inputs detected for \" << stateVariableNames_[stateVar] <<\n              \". This may result in oscillations. Please ensure that your variances for each \"\n              \"measured variable are set appropriately.\";\n\n          addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                        stateVariableNames_[stateVar] + \"_configuration\",\n                        stream.str(),\n                        true);\n        }\n        else if (absPoseVarCounts[static_cast<StateMembers>(stateVar)] == 0)\n        {\n          if ((static_cast<StateMembers>(stateVar) == StateMemberX &&\n               twistVarCounts[static_cast<StateMembers>(StateMemberVx)] == 0) ||\n              (static_cast<StateMembers>(stateVar) == StateMemberY &&\n               twistVarCounts[static_cast<StateMembers>(StateMemberVy)] == 0) ||\n              (static_cast<StateMembers>(stateVar) == StateMemberZ &&\n               twistVarCounts[static_cast<StateMembers>(StateMemberVz)] == 0 &&\n               twoDMode_ == false) ||\n              (static_cast<StateMembers>(stateVar) == StateMemberRoll &&\n               twistVarCounts[static_cast<StateMembers>(StateMemberVroll)] == 0 &&\n               twoDMode_ == false) ||\n              (static_cast<StateMembers>(stateVar) == StateMemberPitch &&\n               twistVarCounts[static_cast<StateMembers>(StateMemberVpitch)] == 0 &&\n               twoDMode_ == false) ||\n              (static_cast<StateMembers>(stateVar) == StateMemberYaw &&\n               twistVarCounts[static_cast<StateMembers>(StateMemberVyaw)] == 0))\n          {\n            std::stringstream stream;\n            stream << \"Neither \" << stateVariableNames_[stateVar] << \" nor its \"\n                      \"velocity is being measured. This will result in unbounded \"\n                      \"error growth and erratic filter behavior.\";\n\n            addDiagnostic(diagnostic_msgs::DiagnosticStatus::ERROR,\n                          stateVariableNames_[stateVar] + \"_configuration\",\n                          stream.str(),\n                          true);\n          }\n        }\n      }\n    }\n\n    // Load up the process noise covariance (from the launch file/parameter server)\n    Eigen::MatrixXd processNoiseCovariance(STATE_SIZE, STATE_SIZE);\n    processNoiseCovariance.setZero();\n    XmlRpc::XmlRpcValue processNoiseCovarConfig;\n\n    if (nhLocal_.hasParam(\"process_noise_covariance\"))\n    {\n      try\n      {\n        nhLocal_.getParam(\"process_noise_covariance\", processNoiseCovarConfig);\n\n        ROS_ASSERT(processNoiseCovarConfig.getType() == XmlRpc::XmlRpcValue::TypeArray);\n\n        int matSize = processNoiseCovariance.rows();\n\n        for (int i = 0; i < matSize; i++)\n        {\n          for (int j = 0; j < matSize; j++)\n          {\n            try\n            {\n              // These matrices can cause problems if all the types\n              // aren't specified with decimal points. Handle that\n              // using string streams.\n              std::ostringstream ostr;\n              ostr << processNoiseCovarConfig[matSize * i + j];\n              std::istringstream istr(ostr.str());\n              istr >> processNoiseCovariance(i, j);\n            }\n            catch(XmlRpc::XmlRpcException &e)\n            {\n              throw e;\n            }\n            catch(...)\n            {\n              throw;\n            }\n          }\n        }\n\n        RF_DEBUG(\"Process noise covariance is:\\n\" << processNoiseCovariance << \"\\n\");\n      }\n      catch (XmlRpc::XmlRpcException &e)\n      {\n        ROS_ERROR_STREAM(\"ERROR reading sensor config: \" <<\n                         e.getMessage() <<\n                         \" for process_noise_covariance (type: \" <<\n                         processNoiseCovarConfig.getType() << \")\");\n      }\n\n      filter_.setProcessNoiseCovariance(processNoiseCovariance);\n    }\n\n    // Load up the process noise covariance (from the launch file/parameter server)\n    Eigen::MatrixXd initialEstimateErrorCovariance(STATE_SIZE, STATE_SIZE);\n    initialEstimateErrorCovariance.setZero();\n    XmlRpc::XmlRpcValue estimateErrorCovarConfig;\n\n    if (nhLocal_.hasParam(\"initial_estimate_covariance\"))\n    {\n      try\n      {\n        nhLocal_.getParam(\"initial_estimate_covariance\", estimateErrorCovarConfig);\n\n        ROS_ASSERT(estimateErrorCovarConfig.getType() == XmlRpc::XmlRpcValue::TypeArray);\n\n        int matSize = initialEstimateErrorCovariance.rows();\n\n        for (int i = 0; i < matSize; i++)\n        {\n          for (int j = 0; j < matSize; j++)\n          {\n            try\n            {\n              // These matrices can cause problems if all the types\n              // aren't specified with decimal points. Handle that\n              // using string streams.\n              std::ostringstream ostr;\n              ostr << estimateErrorCovarConfig[matSize * i + j];\n              std::istringstream istr(ostr.str());\n              istr >> initialEstimateErrorCovariance(i, j);\n            }\n            catch(XmlRpc::XmlRpcException &e)\n            {\n              throw e;\n            }\n            catch(...)\n            {\n              throw;\n            }\n          }\n        }\n\n        RF_DEBUG(\"Initial estimate error covariance is:\\n\" << initialEstimateErrorCovariance << \"\\n\");\n      }\n      catch (XmlRpc::XmlRpcException &e)\n      {\n        ROS_ERROR_STREAM(\"ERROR reading initial_estimate_covariance (type: \" <<\n                         estimateErrorCovarConfig.getType() <<\n                         \"): \" <<\n                         e.getMessage());\n      }\n      catch(...)\n      {\n        ROS_ERROR_STREAM(\n          \"ERROR reading initial_estimate_covariance (type: \" << estimateErrorCovarConfig.getType() << \")\");\n      }\n\n      filter_.setEstimateErrorCovariance(initialEstimateErrorCovariance);\n    }\n  }\n\n  template<typename T>\n  void RosFilter<T>::odometryCallback(const nav_msgs::Odometry::ConstPtr &msg, const std::string &topicName,\n    const CallbackData &poseCallbackData, const CallbackData &twistCallbackData)\n  {\n    // If we've just reset the filter, then we want to ignore any messages\n    // that arrive with an older timestamp\n    if (msg->header.stamp <= lastSetPoseTime_)\n    {\n      std::stringstream stream;\n      stream << \"The \" << topicName << \" message has a timestamp equal to or before the last filter reset, \" <<\n                \"this message will be ignored. This may indicate an empty or bad timestamp. (message time: \" <<\n                msg->header.stamp.toSec() << \")\";\n      addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                    topicName + \"_timestamp\",\n                    stream.str(),\n                    false);\n      RF_DEBUG(\"Received message that preceded the most recent pose reset. Ignoring...\");\n      return;\n    }\n\n    RF_DEBUG(\"------ RosFilter::odometryCallback (\" << topicName << \") ------\\n\" << \"Odometry message:\\n\" << *msg);\n\n    if (poseCallbackData.updateSum_ > 0)\n    {\n      // Grab the pose portion of the message and pass it to the poseCallback\n      geometry_msgs::PoseWithCovarianceStamped *posPtr = new geometry_msgs::PoseWithCovarianceStamped();\n      posPtr->header = msg->header;\n      posPtr->pose = msg->pose;  // Entire pose object, also copies covariance\n\n      geometry_msgs::PoseWithCovarianceStampedConstPtr pptr(posPtr);\n      poseCallback(pptr, poseCallbackData, worldFrameId_, false);\n    }\n\n    if (twistCallbackData.updateSum_ > 0)\n    {\n      // Grab the twist portion of the message and pass it to the twistCallback\n      geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped();\n      twistPtr->header = msg->header;\n      twistPtr->header.frame_id = msg->child_frame_id;\n      twistPtr->twist = msg->twist;  // Entire twist object, also copies covariance\n\n      geometry_msgs::TwistWithCovarianceStampedConstPtr tptr(twistPtr);\n      twistCallback(tptr, twistCallbackData, baseLinkFrameId_);\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::odometryCallback (\" << topicName << \") ------\\n\");\n  }\n\n  template<typename T>\n  void RosFilter<T>::poseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg,\n                                  const CallbackData &callbackData,\n                                  const std::string &targetFrame,\n                                  const bool imuData)\n  {\n    const std::string &topicName = callbackData.topicName_;\n\n    // If we've just reset the filter, then we want to ignore any messages\n    // that arrive with an older timestamp\n    if (msg->header.stamp <= lastSetPoseTime_)\n    {\n      std::stringstream stream;\n      stream << \"The \" << topicName << \" message has a timestamp equal to or before the last filter reset, \" <<\n                \"this message will be ignored. This may indicate an empty or bad timestamp. (message time: \" <<\n                msg->header.stamp.toSec() << \")\";\n      addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                    topicName + \"_timestamp\",\n                    stream.str(),\n                    false);\n      return;\n    }\n\n    RF_DEBUG(\"------ RosFilter::poseCallback (\" << topicName << \") ------\\n\" <<\n             \"Pose message:\\n\" << *msg);\n\n    // Put the initial value in the lastMessagTimes_ for this variable if it's empty\n    if (lastMessageTimes_.count(topicName) == 0)\n    {\n      lastMessageTimes_.insert(std::pair<std::string, ros::Time>(topicName, msg->header.stamp));\n    }\n\n    // Make sure this message is newer than the last one\n    if (msg->header.stamp >= lastMessageTimes_[topicName])\n    {\n      RF_DEBUG(\"Update vector for \" << topicName << \" is:\\n\" << callbackData.updateVector_);\n\n      Eigen::VectorXd measurement(STATE_SIZE);\n      Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);\n\n      measurement.setZero();\n      measurementCovariance.setZero();\n\n      // Make sure we're actually updating at least one of these variables\n      std::vector<int> updateVectorCorrected = callbackData.updateVector_;\n\n      // Prepare the pose data for inclusion in the filter\n      if (preparePose(msg,\n                      topicName,\n                      targetFrame,\n                      callbackData.differential_,\n                      callbackData.relative_,\n                      imuData,\n                      updateVectorCorrected,\n                      measurement,\n                      measurementCovariance))\n      {\n        // Store the measurement. Add a \"pose\" suffix so we know what kind of measurement\n        // we're dealing with when we debug the core filter logic.\n        enqueueMeasurement(topicName,\n                           measurement,\n                           measurementCovariance,\n                           updateVectorCorrected,\n                           callbackData.rejectionThreshold_,\n                           msg->header.stamp);\n\n        RF_DEBUG(\"Enqueued new measurement for \" << topicName << \"\\n\");\n      }\n      else\n      {\n        RF_DEBUG(\"Did *not* enqueue measurement for \" << topicName << \"\\n\");\n      }\n\n      lastMessageTimes_[topicName] = msg->header.stamp;\n\n      RF_DEBUG(\"Last message time for \" << topicName << \" is now \" <<\n        lastMessageTimes_[topicName] << \"\\n\");\n    }\n    else if (resetOnTimeJump_ && ros::Time::isSimTime())\n    {\n      reset();\n    }\n    else\n    {\n      std::stringstream stream;\n      stream << \"The \" << topicName << \" message has a timestamp before that of the previous message received,\" <<\n                \" this message will be ignored. This may indicate a bad timestamp. (message time: \" <<\n                msg->header.stamp.toSec() << \")\";\n      addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                    topicName + \"_timestamp\",\n                    stream.str(),\n                    false);\n\n      RF_DEBUG(\"Message is too old. Last message time for \" << topicName << \" is \"\n               << lastMessageTimes_[topicName] << \", current message time is \"\n               << msg->header.stamp << \".\\n\");\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::poseCallback (\" << topicName << \") ------\\n\");\n  }\n\n  template<typename T>\n  void RosFilter<T>::run()\n  {\n    ROS_INFO(\"Waiting for valid clock time...\");\n    ros::Time::waitForValid();\n    ROS_INFO(\"Valid clock time received. Starting node.\");\n\n    loadParams();\n\n    if (printDiagnostics_)\n    {\n      diagnosticUpdater_.add(\"Filter diagnostic updater\", this, &RosFilter<T>::aggregateDiagnostics);\n    }\n\n    // Set up the frequency diagnostic\n    double minFrequency = frequency_ - 2;\n    double maxFrequency = frequency_ + 2;\n    diagnostic_updater::HeaderlessTopicDiagnostic freqDiag(\"odometry/filtered\",\n                                                           diagnosticUpdater_,\n                                                           diagnostic_updater::FrequencyStatusParam(&minFrequency,\n                                                                                                    &maxFrequency,\n                                                                                                    0.1, 10));\n\n    // We may need to broadcast a different transform than\n    // the one we've already calculated.\n    tf2::Transform mapOdomTrans;\n    tf2::Transform odomBaseLinkTrans;\n    geometry_msgs::TransformStamped mapOdomTransMsg;\n    ros::Time curTime;\n    ros::Time lastDiagTime = ros::Time::now();\n\n    // Clear out the transforms\n    worldBaseLinkTransMsg_.transform = tf2::toMsg(tf2::Transform::getIdentity());\n    mapOdomTransMsg.transform = tf2::toMsg(tf2::Transform::getIdentity());\n\n    // Publisher\n    ros::Publisher positionPub = nh_.advertise<nav_msgs::Odometry>(\"odometry/filtered\", 20);\n    tf2_ros::TransformBroadcaster worldTransformBroadcaster;\n\n    // Optional acceleration publisher\n    ros::Publisher accelPub;\n    if (publishAcceleration_)\n    {\n      accelPub = nh_.advertise<geometry_msgs::AccelWithCovarianceStamped>(\"accel/filtered\", 20);\n    }\n\n    const ros::Duration loop_cycle_time(1.0 / frequency_);\n    ros::Time loop_end_time = ros::Time::now();\n\n    // Wait for the filter to be enabled\n    while (!enabled_ && ros::ok())\n    {\n      ROS_WARN_STREAM_ONCE(\"[\" << ros::this_node::getName() << \":] This filter is disabled. To enable it call the service \" << ros::this_node::getName() << \"/enable\");\n      ros::spinOnce();\n      if (enabled_)\n      {\n        break;\n      }\n    }\n\n    while (ros::ok())\n    {\n      // The spin will call all the available callbacks and enqueue\n      // their received measurements\n      ros::spinOnce();\n      curTime = ros::Time::now();\n\n      // Now we'll integrate any measurements we've received\n      integrateMeasurements(curTime);\n\n      // Get latest state and publish it\n      nav_msgs::Odometry filteredPosition;\n\n      if (getFilteredOdometryMessage(filteredPosition))\n      {\n        worldBaseLinkTransMsg_.header.stamp = filteredPosition.header.stamp + tfTimeOffset_;\n        worldBaseLinkTransMsg_.header.frame_id = filteredPosition.header.frame_id;\n        worldBaseLinkTransMsg_.child_frame_id = filteredPosition.child_frame_id;\n\n        worldBaseLinkTransMsg_.transform.translation.x = filteredPosition.pose.pose.position.x;\n        worldBaseLinkTransMsg_.transform.translation.y = filteredPosition.pose.pose.position.y;\n        worldBaseLinkTransMsg_.transform.translation.z = filteredPosition.pose.pose.position.z;\n        worldBaseLinkTransMsg_.transform.rotation = filteredPosition.pose.pose.orientation;\n\n        // the filteredPosition is the message containing the state and covariances: nav_msgs Odometry\n\n        if (!validateFilterOutput(filteredPosition))\n        {\n          ROS_ERROR_STREAM(\"Critical Error, NaNs were detected in the output state of the filter.\" <<\n                \" This was likely due to poorly coniditioned process, noise, or sensor covariances.\");\n        }\n\n        // If the worldFrameId_ is the odomFrameId_ frame, then we can just send the transform. If the\n        // worldFrameId_ is the mapFrameId_ frame, we'll have some work to do.\n        if (publishTransform_)\n        {\n          if (filteredPosition.header.frame_id == odomFrameId_)\n          {\n            worldTransformBroadcaster.sendTransform(worldBaseLinkTransMsg_);\n          }\n          else if (filteredPosition.header.frame_id == mapFrameId_)\n          {\n            try\n            {\n              tf2::Transform worldBaseLinkTrans;\n              tf2::fromMsg(worldBaseLinkTransMsg_.transform, worldBaseLinkTrans);\n\n              if (!RosFilterUtilities::lookupTransformSafe(\n                     tfBuffer_,\n                     baseLinkFrameId_,\n                     odomFrameId_,\n                     ros::Time(filter_.getLastMeasurementTime()),\n                     odomBaseLinkTrans,\n                     true))\n              {\n                ROS_ERROR_STREAM_DELAYED_THROTTLE(1.0, \"Unable to retrieve \" << odomFrameId_ << \"->\" <<\n                  baseLinkFrameId_ << \" transform. Skipping iteration...\");\n                continue;\n              }\n\n              /*\n               * First, see these two references:\n               * http://wiki.ros.org/tf/Overview/Using%20Published%20Transforms#lookupTransform\n               * http://wiki.ros.org/geometry/CoordinateFrameConventions#Transform_Direction\n               * We have a transform from mapFrameId_->baseLinkFrameId_, but it would actually transform\n               * a given pose from baseLinkFrameId_->mapFrameId_. We then used lookupTransform, whose\n               * first two arguments are target frame and source frame, to get a transform from\n               * baseLinkFrameId_->odomFrameId_. However, this transform would actually transform data\n               * from odomFrameId_->baseLinkFrameId_. Now imagine that we have a position in the\n               * mapFrameId_ frame. First, we multiply it by the inverse of the\n               * mapFrameId_->baseLinkFrameId, which will transform that data from mapFrameId_ to\n               * baseLinkFrameId_. Now we want to go from baseLinkFrameId_->odomFrameId_, but the\n               * transform we have takes data from odomFrameId_->baseLinkFrameId_, so we need its\n               * inverse as well. We have now transformed our data from mapFrameId_ to odomFrameId_.\n               * However, if we want other users to be able to do the same, we need to broadcast\n               * the inverse of that entire transform.\n              */\n\n              mapOdomTrans.mult(worldBaseLinkTrans, odomBaseLinkTrans);\n\n              mapOdomTransMsg.transform = tf2::toMsg(mapOdomTrans);\n              mapOdomTransMsg.header.stamp = filteredPosition.header.stamp + tfTimeOffset_;\n              mapOdomTransMsg.header.frame_id = mapFrameId_;\n              mapOdomTransMsg.child_frame_id = odomFrameId_;\n\n              worldTransformBroadcaster.sendTransform(mapOdomTransMsg);\n            }\n            catch(...)\n            {\n              ROS_ERROR_STREAM_DELAYED_THROTTLE(5.0, \"Could not obtain transform from \"\n                                                << odomFrameId_ << \"->\" << baseLinkFrameId_);\n            }\n          }\n          else\n          {\n            ROS_ERROR_STREAM(\"Odometry message frame_id was \" << filteredPosition.header.frame_id <<\n                             \", expected \" << mapFrameId_ << \" or \" << odomFrameId_);\n          }\n        }\n\n        // Fire off the position and the transform\n        positionPub.publish(filteredPosition);\n\n        if (printDiagnostics_)\n        {\n          freqDiag.tick();\n        }\n      }\n\n      // Publish the acceleration if desired and filter is initialized\n      geometry_msgs::AccelWithCovarianceStamped filteredAcceleration;\n      if (publishAcceleration_ && getFilteredAccelMessage(filteredAcceleration))\n      {\n        accelPub.publish(filteredAcceleration);\n      }\n\n      /* Diagnostics can behave strangely when playing back from bag\n       * files and using simulated time, so we have to check for\n       * time suddenly moving backwards as well as the standard\n       * timeout criterion before publishing. */\n      double diagDuration = (curTime - lastDiagTime).toSec();\n      if (printDiagnostics_ && (diagDuration >= diagnosticUpdater_.getPeriod() || diagDuration < 0.0))\n      {\n        diagnosticUpdater_.force_update();\n        lastDiagTime = curTime;\n      }\n\n      // Clear out expired history data\n      if (smoothLaggedData_)\n      {\n        clearExpiredHistory(filter_.getLastMeasurementTime() - historyLength_);\n      }\n\n      ros::Duration loop_elapsed_time = ros::Time::now() - loop_end_time;\n\n      if (loop_elapsed_time > loop_cycle_time)\n      {\n        ROS_WARN_STREAM_DELAYED_THROTTLE(1.0, \"Failed to meet update rate! Took \" << std::setprecision(20) <<\n          loop_elapsed_time.toSec() << \" seconds. Try decreasing the rate, limiting sensor output frequency, or \"\n          \"limiting the number of sensors.\");\n      }\n      else\n      {\n        ros::Duration sleep_time = loop_cycle_time - loop_elapsed_time;\n        sleep_time.sleep();\n      }\n\n      loop_end_time = ros::Time::now();\n    }\n  }\n\n  template<typename T>\n  void RosFilter<T>::setPoseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)\n  {\n    RF_DEBUG(\"------ RosFilter::setPoseCallback ------\\nPose message:\\n\" << *msg);\n\n    std::string topicName(\"setPose\");\n\n    // Get rid of any initial poses (pretend we've never had a measurement)\n    initialMeasurements_.clear();\n    previousMeasurements_.clear();\n    previousMeasurementCovariances_.clear();\n\n    // Clear out the measurement queue so that we don't immediately undo our\n    // reset.\n    while (!measurementQueue_.empty() && ros::ok())\n    {\n      measurementQueue_.pop();\n    }\n\n    filterStateHistory_.clear();\n    measurementHistory_.clear();\n\n    // Also set the last set pose time, so we ignore all messages\n    // that occur before it\n    lastSetPoseTime_ = msg->header.stamp;\n\n    // Set the state vector to the reported pose\n    Eigen::VectorXd measurement(STATE_SIZE);\n    Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);\n    std::vector<int> updateVector(STATE_SIZE, true);\n\n    // We only measure pose variables, so initialize the vector to 0\n    measurement.setZero();\n\n    // Set this to the identity and let the message reset it\n    measurementCovariance.setIdentity();\n    measurementCovariance *= 1e-6;\n\n    // Prepare the pose data (really just using this to transform it into the target frame).\n    // Twist data is going to get zeroed out.\n    preparePose(msg, topicName, worldFrameId_, false, false, false, updateVector, measurement, measurementCovariance);\n\n    // For the state\n    filter_.setState(measurement);\n    filter_.setEstimateErrorCovariance(measurementCovariance);\n\n    filter_.setLastMeasurementTime(ros::Time::now().toSec());\n\n    // This method can apparently cancel all callbacks, and may stop the executing of the very callback that we're\n    // currently in. Therefore, nothing of consequence should come after it.\n    ros::getGlobalCallbackQueue()->clear();\n\n    RF_DEBUG(\"\\n------ /RosFilter::setPoseCallback ------\\n\");\n  }\n\n  template<typename T>\n  bool RosFilter<T>::setPoseSrvCallback(robot_localization::SetPose::Request& request,\n                          robot_localization::SetPose::Response&)\n  {\n    geometry_msgs::PoseWithCovarianceStamped::Ptr msg;\n    msg = boost::make_shared<geometry_msgs::PoseWithCovarianceStamped>(request.pose);\n    setPoseCallback(msg);\n\n    return true;\n  }\n\n  template<typename T>\n  bool RosFilter<T>::enableFilterSrvCallback(std_srvs::Empty::Request&,\n                                             std_srvs::Empty::Response&)\n  {\n    RF_DEBUG(\"\\n[\" << ros::this_node::getName() << \":]\" << \" ------ /RosFilter::enableFilterSrvCallback ------\\n\");\n    if (enabled_) {\n      ROS_WARN_STREAM(\"[\" << ros::this_node::getName() << \":] Asking for enabling filter service, but the filter was already enabled! Use param disabled_at_startup.\");\n    } else {\n      ROS_INFO_STREAM(\"[\" << ros::this_node::getName() << \":] Enabling filter...\");\n      enabled_ = true;\n    }\n    return true;\n  }\n\n  template<typename T>\n  void RosFilter<T>::twistCallback(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg,\n                                   const CallbackData &callbackData,\n                                   const std::string &targetFrame)\n  {\n    const std::string &topicName = callbackData.topicName_;\n\n    // If we've just reset the filter, then we want to ignore any messages\n    // that arrive with an older timestamp\n    if (msg->header.stamp <= lastSetPoseTime_)\n    {\n      std::stringstream stream;\n      stream << \"The \" << topicName << \" message has a timestamp equal to or before the last filter reset, \" <<\n                \"this message will be ignored. This may indicate an empty or bad timestamp. (message time: \" <<\n                msg->header.stamp.toSec() << \")\";\n      addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                    topicName + \"_timestamp\",\n                    stream.str(),\n                    false);\n      return;\n    }\n\n    RF_DEBUG(\"------ RosFilter::twistCallback (\" << topicName << \") ------\\n\"\n             \"Twist message:\\n\" << *msg);\n\n    if (lastMessageTimes_.count(topicName) == 0)\n    {\n      lastMessageTimes_.insert(std::pair<std::string, ros::Time>(topicName, msg->header.stamp));\n    }\n\n    // Make sure this message is newer than the last one\n    if (msg->header.stamp >= lastMessageTimes_[topicName])\n    {\n      RF_DEBUG(\"Update vector for \" << topicName << \" is:\\n\" << callbackData.updateVector_);\n\n      Eigen::VectorXd measurement(STATE_SIZE);\n      Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);\n\n      measurement.setZero();\n      measurementCovariance.setZero();\n\n      // Make sure we're actually updating at least one of these variables\n      std::vector<int> updateVectorCorrected = callbackData.updateVector_;\n\n      // Prepare the twist data for inclusion in the filter\n      if (prepareTwist(msg, topicName, targetFrame, updateVectorCorrected, measurement, measurementCovariance))\n      {\n        // Store the measurement. Add a \"twist\" suffix so we know what kind of measurement\n        // we're dealing with when we debug the core filter logic.\n        enqueueMeasurement(topicName,\n                           measurement,\n                           measurementCovariance,\n                           updateVectorCorrected,\n                           callbackData.rejectionThreshold_,\n                           msg->header.stamp);\n\n        RF_DEBUG(\"Enqueued new measurement for \" << topicName << \"_twist\\n\");\n      }\n      else\n      {\n        RF_DEBUG(\"Did *not* enqueue measurement for \" << topicName << \"_twist\\n\");\n      }\n\n      lastMessageTimes_[topicName] = msg->header.stamp;\n\n      RF_DEBUG(\"Last message time for \" << topicName << \" is now \" <<\n        lastMessageTimes_[topicName] << \"\\n\");\n    }\n    else if (resetOnTimeJump_ && ros::Time::isSimTime())\n    {\n      reset();\n    }\n    else\n    {\n      std::stringstream stream;\n      stream << \"The \" << topicName << \" message has a timestamp before that of the previous message received,\" <<\n                \" this message will be ignored. This may indicate a bad timestamp. (message time: \" <<\n                msg->header.stamp.toSec() << \")\";\n      addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                    topicName + \"_timestamp\",\n                    stream.str(),\n                    false);\n\n      RF_DEBUG(\"Message is too old. Last message time for \" << topicName << \" is \" << lastMessageTimes_[topicName] <<\n        \", current message time is \" << msg->header.stamp << \".\\n\");\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::twistCallback (\" << topicName << \") ------\\n\");\n  }\n\n  template<typename T>\n  void RosFilter<T>::addDiagnostic(const int errLevel,\n                                   const std::string &topicAndClass,\n                                   const std::string &message,\n                                   const bool staticDiag)\n  {\n    if (staticDiag)\n    {\n      staticDiagnostics_[topicAndClass] = message;\n      staticDiagErrorLevel_ = std::max(staticDiagErrorLevel_, errLevel);\n    }\n    else\n    {\n      dynamicDiagnostics_[topicAndClass] = message;\n      dynamicDiagErrorLevel_ = std::max(dynamicDiagErrorLevel_, errLevel);\n    }\n  }\n\n  template<typename T>\n  void RosFilter<T>::aggregateDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &wrapper)\n  {\n    wrapper.clear();\n    wrapper.clearSummary();\n\n    int maxErrLevel = std::max(staticDiagErrorLevel_, dynamicDiagErrorLevel_);\n\n    // Report the overall status\n    switch (maxErrLevel)\n    {\n      case diagnostic_msgs::DiagnosticStatus::ERROR:\n        wrapper.summary(maxErrLevel,\n                        \"Erroneous data or settings detected for a robot_localization state estimation node.\");\n        break;\n      case diagnostic_msgs::DiagnosticStatus::WARN:\n        wrapper.summary(maxErrLevel,\n                        \"Potentially erroneous data or settings detected for \"\n                        \"a robot_localization state estimation node.\");\n        break;\n      case diagnostic_msgs::DiagnosticStatus::STALE:\n        wrapper.summary(maxErrLevel,\n                        \"The state of the robot_localization state estimation node is stale.\");\n        break;\n      case diagnostic_msgs::DiagnosticStatus::OK:\n        wrapper.summary(maxErrLevel,\n                        \"The robot_localization state estimation node appears to be functioning properly.\");\n        break;\n      default:\n        break;\n    }\n\n    // Aggregate all the static messages\n    for (std::map<std::string, std::string>::iterator diagIt = staticDiagnostics_.begin();\n        diagIt != staticDiagnostics_.end();\n        ++diagIt)\n    {\n      wrapper.add(diagIt->first, diagIt->second);\n    }\n\n    // Aggregate all the dynamic messages, then clear them\n    for (std::map<std::string, std::string>::iterator diagIt = dynamicDiagnostics_.begin();\n        diagIt != dynamicDiagnostics_.end();\n        ++diagIt)\n    {\n      wrapper.add(diagIt->first, diagIt->second);\n    }\n    dynamicDiagnostics_.clear();\n\n    // Reset the warning level for the dynamic diagnostic messages\n    dynamicDiagErrorLevel_ = diagnostic_msgs::DiagnosticStatus::OK;\n  }\n\n  template<typename T>\n  void RosFilter<T>::copyCovariance(const double *arr,\n                                    Eigen::MatrixXd &covariance,\n                                    const std::string &topicName,\n                                    const std::vector<int> &updateVector,\n                                    const size_t offset,\n                                    const size_t dimension)\n  {\n    for (size_t i = 0; i < dimension; i++)\n    {\n      for (size_t j = 0; j < dimension; j++)\n      {\n        covariance(i, j) = arr[dimension * i + j];\n\n        if (printDiagnostics_)\n        {\n          std::string iVar = stateVariableNames_[offset + i];\n\n          if (covariance(i, j) > 1e3 && (updateVector[offset  + i] || updateVector[offset  + j]))\n          {\n            std::string jVar = stateVariableNames_[offset + j];\n\n            std::stringstream stream;\n            stream << \"The covariance at position (\" << dimension * i + j << \"), which corresponds to \" <<\n                (i == j ? iVar + \" variance\" : iVar + \" and \" + jVar + \" covariance\") <<\n                \", the value is extremely large (\" << covariance(i, j) << \"), but the update vector for \" <<\n                (i == j ? iVar : iVar + \" and/or \" + jVar) << \" is set to true. This may produce undesirable results.\";\n\n            addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                          topicName + \"_covariance\",\n                          stream.str(),\n                          false);\n          }\n          else if (updateVector[i] && i == j && covariance(i, j) == 0)\n          {\n            std::stringstream stream;\n            stream << \"The covariance at position (\" << dimension * i + j << \"), which corresponds to \" <<\n                       iVar << \" variance, was zero. This will be replaced with a small value to maintain filter \"\n                       \"stability, but should be corrected at the message origin node.\";\n\n            addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                          topicName + \"_covariance\",\n                          stream.str(),\n                          false);\n          }\n          else if (updateVector[i] && i == j && covariance(i, j) < 0)\n          {\n            std::stringstream stream;\n            stream << \"The covariance at position (\" << dimension * i + j <<\n                      \"), which corresponds to \" << iVar << \" variance, was negative. This will be replaced with a \"\n                      \"small positive value to maintain filter stability, but should be corrected at the message \"\n                      \"origin node.\";\n\n            addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                          topicName + \"_covariance\",\n                          stream.str(),\n                          false);\n          }\n        }\n      }\n    }\n  }\n\n  template<typename T>\n  void RosFilter<T>::copyCovariance(const Eigen::MatrixXd &covariance,\n                                 double *arr,\n                                 const size_t dimension)\n  {\n    for (size_t i = 0; i < dimension; i++)\n    {\n      for (size_t j = 0; j < dimension; j++)\n      {\n        arr[dimension * i + j] = covariance(i, j);\n      }\n    }\n  }\n\n  template<typename T>\n  std::vector<int> RosFilter<T>::loadUpdateConfig(const std::string &topicName)\n  {\n    XmlRpc::XmlRpcValue topicConfig;\n    std::vector<int> updateVector(STATE_SIZE, 0);\n    std::string topicConfigName = topicName + \"_config\";\n\n    try\n    {\n      nhLocal_.getParam(topicConfigName, topicConfig);\n\n      ROS_ASSERT(topicConfig.getType() == XmlRpc::XmlRpcValue::TypeArray);\n\n      if (topicConfig.size() != STATE_SIZE)\n      {\n        ROS_WARN_STREAM(\"Configuration vector for \" << topicConfigName << \" should have 15 entries.\");\n      }\n\n      for (int i = 0; i < topicConfig.size(); i++)\n      {\n        // The double cast looks strange, but we'll get exceptions if we\n        // remove the cast to bool. vector<bool> is discouraged, so updateVector\n        // uses integers.\n        updateVector[i] = static_cast<int>(static_cast<bool>(topicConfig[i]));\n      }\n    }\n    catch (XmlRpc::XmlRpcException &e)\n    {\n      ROS_FATAL_STREAM(\"Could not read sensor update configuration for topic \" << topicName <<\n                       \" (type: \" << topicConfig.getType() << \", expected: \" << XmlRpc::XmlRpcValue::TypeArray\n                       << \"). Error was \" << e.getMessage() << \"\\n\");\n    }\n\n    return updateVector;\n  }\n\n  template<typename T>\n  bool RosFilter<T>::prepareAcceleration(const sensor_msgs::Imu::ConstPtr &msg,\n                           const std::string &topicName,\n                           const std::string &targetFrame,\n                           std::vector<int> &updateVector,\n                           Eigen::VectorXd &measurement,\n                           Eigen::MatrixXd &measurementCovariance)\n  {\n    RF_DEBUG(\"------ RosFilter::prepareAcceleration (\" << topicName << \") ------\\n\");\n\n    // 1. Get the measurement into a vector\n    tf2::Vector3 accTmp(msg->linear_acceleration.x,\n                        msg->linear_acceleration.y,\n                        msg->linear_acceleration.z);\n\n    // Set relevant header info\n    std::string msgFrame = (msg->header.frame_id == \"\" ? baseLinkFrameId_ : msg->header.frame_id);\n\n    // 2. robot_localization lets users configure which variables from the sensor should be\n    //    fused with the filter. This is specified at the sensor level. However, the data\n    //    may go through transforms before being fused with the state estimate. In that case,\n    //    we need to know which of the transformed variables came from the pre-transformed\n    //    \"approved\" variables (i.e., the ones that had \"true\" in their xxx_config parameter).\n    //    To do this, we create a pose from the original upate vector, which contains only\n    //    zeros and ones. This pose goes through the same transforms as the measurement. The\n    //    non-zero values that result will be used to modify the updateVector.\n    tf2::Matrix3x3 maskAcc(updateVector[StateMemberAx], 0, 0,\n                           0, updateVector[StateMemberAy], 0,\n                           0, 0, updateVector[StateMemberAz]);\n\n    // 3. We'll need to rotate the covariance as well\n    Eigen::MatrixXd covarianceRotated(ACCELERATION_SIZE, ACCELERATION_SIZE);\n    covarianceRotated.setZero();\n\n    this->copyCovariance(&(msg->linear_acceleration_covariance[0]),\n                         covarianceRotated,\n                         topicName,\n                         updateVector,\n                         POSITION_A_OFFSET,\n                         ACCELERATION_SIZE);\n\n    RF_DEBUG(\"Original measurement as tf object: \" << accTmp <<\n             \"\\nOriginal update vector:\\n\" << updateVector <<\n             \"\\nOriginal covariance matrix:\\n\" << covarianceRotated << \"\\n\");\n\n    // 4. We need to transform this into the target frame (probably base_link)\n    // It's unlikely that we'll get a velocity measurement in another frame, but\n    // we have to handle the situation.\n    tf2::Transform targetFrameTrans;\n    bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_,\n                                                                targetFrame,\n                                                                msgFrame,\n                                                                msg->header.stamp,\n                                                                tfTimeout_,\n                                                                targetFrameTrans);\n\n    if (canTransform)\n    {\n      // We don't know if the user has already handled the removal\n      // of normal forces, so we use a parameter\n      if (removeGravitationalAcc_[topicName])\n      {\n        tf2::Vector3 normAcc(0, 0, gravitationalAcc_);\n        tf2::Quaternion curAttitude;\n        tf2::Transform trans;\n\n        if (::fabs(msg->orientation_covariance[0] + 1) < 1e-9)\n        {\n          // Imu message contains no orientation, so we should use orientation\n          // from filter state to transform and remove acceleration\n          const Eigen::VectorXd &state = filter_.getState();\n          tf2::Vector3 stateTmp(state(StateMemberRoll),\n                                state(StateMemberPitch),\n                                state(StateMemberYaw));\n          // transform state orientation to IMU frame\n          tf2::Transform imuFrameTrans;\n          RosFilterUtilities::lookupTransformSafe(tfBuffer_,\n                                                  msgFrame,\n                                                  targetFrame,\n                                                  msg->header.stamp,\n                                                  tfTimeout_,\n                                                  imuFrameTrans);\n          stateTmp = imuFrameTrans.getBasis() * stateTmp;\n          curAttitude.setRPY(stateTmp.getX(), stateTmp.getY(), stateTmp.getZ());\n        }\n        else\n        {\n          tf2::fromMsg(msg->orientation, curAttitude);\n          if (fabs(curAttitude.length() - 1.0) > 0.01)\n          {\n            ROS_WARN_ONCE(\"An input was not normalized, this should NOT happen, but will normalize.\");\n            curAttitude.normalize();\n          }\n        }\n        trans.setRotation(curAttitude);\n        tf2::Vector3 rotNorm = trans.getBasis().inverse() * normAcc;\n        accTmp.setX(accTmp.getX() - rotNorm.getX());\n        accTmp.setY(accTmp.getY() - rotNorm.getY());\n        accTmp.setZ(accTmp.getZ() - rotNorm.getZ());\n\n        RF_DEBUG(\"Orientation is \" << curAttitude <<\n                 \"Acceleration due to gravity is \" << rotNorm <<\n                 \"After removing acceleration due to gravity, acceleration is \" << accTmp << \"\\n\");\n      }\n\n      // Transform to correct frame\n      // @todo: This needs to take into account offsets from the origin. Right now,\n      // it assumes that if the sensor is placed at some non-zero offset from the\n      // vehicle's center, that the vehicle turns with constant velocity. This needs\n      // to be something like\n      // accTmp = targetFrameTrans.getBasis() * accTmp - targetFrameTrans.getOrigin().cross(rotation_acceleration);\n      // We can get rotational acceleration by differentiating the rotational velocity\n      // (if it's available)\n      accTmp = targetFrameTrans.getBasis() * accTmp;\n      maskAcc = targetFrameTrans.getBasis() * maskAcc;\n\n      // Now use the mask values to determine which update vector values should be true\n      updateVector[StateMemberAx] = static_cast<int>(\n        maskAcc.getRow(StateMemberAx - POSITION_A_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberAy] = static_cast<int>(\n        maskAcc.getRow(StateMemberAy - POSITION_A_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberAz] = static_cast<int>(\n        maskAcc.getRow(StateMemberAz - POSITION_A_OFFSET).length() >= 1e-6);\n\n      RF_DEBUG(msg->header.frame_id << \"->\" << targetFrame << \" transform:\\n\" << targetFrameTrans <<\n               \"\\nAfter applying transform to \" << targetFrame << \", update vector is:\\n\" << updateVector <<\n               \"\\nAfter applying transform to \" << targetFrame << \", measurement is:\\n\" << accTmp << \"\\n\");\n\n      // 5. Now rotate the covariance: create an augmented\n      // matrix that contains a 3D rotation matrix in the\n      // upper-left and lower-right quadrants, and zeros\n      // elsewhere\n      tf2::Matrix3x3 rot(targetFrameTrans.getRotation());\n      Eigen::MatrixXd rot3d(ACCELERATION_SIZE, ACCELERATION_SIZE);\n      rot3d.setIdentity();\n\n      for (size_t rInd = 0; rInd < ACCELERATION_SIZE; ++rInd)\n      {\n        rot3d(rInd, 0) = rot.getRow(rInd).getX();\n        rot3d(rInd, 1) = rot.getRow(rInd).getY();\n        rot3d(rInd, 2) = rot.getRow(rInd).getZ();\n      }\n\n      // Carry out the rotation\n      covarianceRotated = rot3d * covarianceRotated.eval() * rot3d.transpose();\n\n      RF_DEBUG(\"Transformed covariance is \\n\" << covarianceRotated << \"\\n\");\n\n      // 6. Store our corrected measurement and covariance\n      measurement(StateMemberAx) = accTmp.getX();\n      measurement(StateMemberAy) = accTmp.getY();\n      measurement(StateMemberAz) = accTmp.getZ();\n\n      // Copy the covariances\n      measurementCovariance.block(POSITION_A_OFFSET, POSITION_A_OFFSET, ACCELERATION_SIZE, ACCELERATION_SIZE) =\n        covarianceRotated.block(0, 0, ACCELERATION_SIZE, ACCELERATION_SIZE);\n\n      // 7. Handle 2D mode\n      if (twoDMode_)\n      {\n        forceTwoD(measurement, measurementCovariance, updateVector);\n      }\n    }\n    else\n    {\n      RF_DEBUG(\"Could not transform measurement into \" << targetFrame << \". Ignoring...\\n\");\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::prepareAcceleration(\" << topicName << \") ------\\n\");\n\n    return canTransform;\n  }\n\n  template<typename T>\n  bool RosFilter<T>::preparePose(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg,\n                                 const std::string &topicName,\n                                 const std::string &targetFrame,\n                                 const bool differential,\n                                 const bool relative,\n                                 const bool imuData,\n                                 std::vector<int> &updateVector,\n                                 Eigen::VectorXd &measurement,\n                                 Eigen::MatrixXd &measurementCovariance)\n  {\n    bool retVal = false;\n\n    RF_DEBUG(\"------ RosFilter::preparePose (\" << topicName << \") ------\\n\");\n\n    // 1. Get the measurement into a tf-friendly transform (pose) object\n    tf2::Stamped<tf2::Transform> poseTmp;\n\n    // We'll need this later for storing this measurement for differential integration\n    tf2::Transform curMeasurement;\n\n    // Handle issues where frame_id data is not filled out properly\n    // @todo: verify that this is necessary still. New IMU handling may\n    // have rendered this obsolete.\n    std::string finalTargetFrame;\n    if (targetFrame == \"\" && msg->header.frame_id == \"\")\n    {\n      // Blank target and message frames mean we can just\n      // use our world_frame\n      finalTargetFrame = worldFrameId_;\n      poseTmp.frame_id_ = finalTargetFrame;\n    }\n    else if (targetFrame == \"\")\n    {\n      // A blank target frame means we shouldn't bother\n      // transforming the data\n      finalTargetFrame = msg->header.frame_id;\n      poseTmp.frame_id_ = finalTargetFrame;\n    }\n    else\n    {\n      // Otherwise, we should use our target frame\n      finalTargetFrame = targetFrame;\n      poseTmp.frame_id_ = (differential ? finalTargetFrame : msg->header.frame_id);\n    }\n\n    RF_DEBUG(\"Final target frame for \" << topicName << \" is \" << finalTargetFrame << \"\\n\");\n\n    poseTmp.stamp_ = msg->header.stamp;\n\n    // Fill out the position data\n    poseTmp.setOrigin(tf2::Vector3(msg->pose.pose.position.x,\n                                   msg->pose.pose.position.y,\n                                   msg->pose.pose.position.z));\n\n    tf2::Quaternion orientation;\n\n    // Handle bad (empty) quaternions\n    if (msg->pose.pose.orientation.x == 0 && msg->pose.pose.orientation.y == 0 &&\n       msg->pose.pose.orientation.z == 0 && msg->pose.pose.orientation.w == 0)\n    {\n      orientation.setValue(0.0, 0.0, 0.0, 1.0);\n\n      if (updateVector[StateMemberRoll] || updateVector[StateMemberPitch] || updateVector[StateMemberYaw])\n      {\n        std::stringstream stream;\n        stream << \"The \" << topicName << \" message contains an invalid orientation quaternion, \" <<\n                  \"but its configuration is such that orientation data is being used. Correcting...\";\n\n        addDiagnostic(diagnostic_msgs::DiagnosticStatus::WARN,\n                      topicName + \"_orientation\",\n                      stream.str(),\n                      false);\n      }\n    }\n    else\n    {\n      tf2::fromMsg(msg->pose.pose.orientation, orientation);\n      if (fabs(orientation.length() - 1.0) > 0.01)\n      {\n        ROS_WARN_ONCE(\"An input was not normalized, this should NOT happen, but will normalize.\");\n        orientation.normalize();\n      }\n    }\n\n    // Fill out the orientation data\n    poseTmp.setRotation(orientation);\n\n    // 2. Get the target frame transformation\n    tf2::Transform targetFrameTrans;\n    bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_,\n                                                                finalTargetFrame,\n                                                                poseTmp.frame_id_,\n                                                                poseTmp.stamp_,\n                                                                tfTimeout_,\n                                                                targetFrameTrans);\n\n    // 3. Make sure we can work with this data before carrying on\n    if (canTransform)\n    {\n      /* 4. robot_localization lets users configure which variables from the sensor should be\n       *    fused with the filter. This is specified at the sensor level. However, the data\n       *    may go through transforms before being fused with the state estimate. In that case,\n       *    we need to know which of the transformed variables came from the pre-transformed\n       *    \"approved\" variables (i.e., the ones that had \"true\" in their xxx_config parameter).\n       *    To do this, we construct matrices using the update vector values on the diagonals,\n       *    pass this matrix through the rotation, and use the length of each row to determine\n       *    the transformed update vector. The process is slightly different for IMUs, as the\n       *    coordinate frame transform is really the base_link->imu_frame transform, and not\n       *    a transform from some other world-fixed frame (even though the IMU data itself *is*\n       *    reported in a world fixed frame). */\n      tf2::Matrix3x3 maskPosition(updateVector[StateMemberX], 0, 0,\n                                  0, updateVector[StateMemberY], 0,\n                                  0, 0, updateVector[StateMemberZ]);\n\n      tf2::Matrix3x3 maskOrientation(updateVector[StateMemberRoll], 0, 0,\n                                     0, updateVector[StateMemberPitch], 0,\n                                     0, 0, updateVector[StateMemberYaw]);\n\n      if (imuData)\n      {\n        /* We have to treat IMU orientation data differently. Even though we are dealing with pose\n         * data when we work with orientations, for IMUs, the frame_id is the frame in which the\n         * sensor is mounted, and not the coordinate frame of the IMU. Imagine an IMU that is mounted\n         * facing sideways. The pitch in the IMU frame becomes roll for the vehicle. This means that\n         * we need to rotate roll and pitch angles by the IMU's mounting yaw offset, and we must apply\n         * similar treatment to its update mask and covariance. */\n\n        double dummy, yaw;\n        targetFrameTrans.getBasis().getRPY(dummy, dummy, yaw);\n        tf2::Matrix3x3 transTmp;\n        transTmp.setRPY(0.0, 0.0, yaw);\n\n        maskPosition = transTmp * maskPosition;\n        maskOrientation = transTmp * maskOrientation;\n      }\n      else\n      {\n        maskPosition = targetFrameTrans.getBasis() * maskPosition;\n        maskOrientation = targetFrameTrans.getBasis() * maskOrientation;\n      }\n\n      // Now copy the mask values back into the update vector: any row with a significant vector length\n      // indicates that we want to set that variable to true in the update vector.\n      updateVector[StateMemberX] = static_cast<int>(\n        maskPosition.getRow(StateMemberX - POSITION_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberY] = static_cast<int>(\n        maskPosition.getRow(StateMemberY - POSITION_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberZ] = static_cast<int>(\n        maskPosition.getRow(StateMemberZ - POSITION_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberRoll] = static_cast<int>(\n        maskOrientation.getRow(StateMemberRoll - ORIENTATION_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberPitch] = static_cast<int>(\n        maskOrientation.getRow(StateMemberPitch - ORIENTATION_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberYaw] = static_cast<int>(\n        maskOrientation.getRow(StateMemberYaw - ORIENTATION_OFFSET).length() >= 1e-6);\n\n      // 5a. We'll need to rotate the covariance as well. Create a container and copy over the\n      // covariance data\n      Eigen::MatrixXd covariance(POSE_SIZE, POSE_SIZE);\n      covariance.setZero();\n      copyCovariance(&(msg->pose.covariance[0]), covariance, topicName, updateVector, POSITION_OFFSET, POSE_SIZE);\n\n      // 5b. Now rotate the covariance: create an augmented matrix that\n      // contains a 3D rotation matrix in the upper-left and lower-right\n      // quadrants, with zeros elsewhere.\n      tf2::Matrix3x3 rot;\n      Eigen::MatrixXd rot6d(POSE_SIZE, POSE_SIZE);\n      rot6d.setIdentity();\n      Eigen::MatrixXd covarianceRotated;\n\n      if (imuData)\n      {\n        // Apply the same special logic to the IMU covariance rotation\n        double dummy, yaw;\n        targetFrameTrans.getBasis().getRPY(dummy, dummy, yaw);\n        rot.setRPY(0.0, 0.0, yaw);\n      }\n      else\n      {\n        rot.setRotation(targetFrameTrans.getRotation());\n      }\n\n      for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd)\n      {\n        rot6d(rInd, 0) = rot.getRow(rInd).getX();\n        rot6d(rInd, 1) = rot.getRow(rInd).getY();\n        rot6d(rInd, 2) = rot.getRow(rInd).getZ();\n        rot6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX();\n        rot6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY();\n        rot6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ();\n      }\n\n      // Now carry out the rotation\n      covarianceRotated = rot6d * covariance * rot6d.transpose();\n\n      RF_DEBUG(\"After rotating into the \" << finalTargetFrame <<\n               \" frame, covariance is \\n\" << covarianceRotated <<  \"\\n\");\n\n      /* 6a. For IMU data, the transform that we get is the transform from the body\n       * frame of the robot (e.g., base_link) to the mounting frame of the robot. It\n       * is *not* the coordinate frame in which the IMU orientation data is reported.\n       * If the IMU is mounted in a non-neutral orientation, we need to remove those\n       * offsets, and then we need to potentially \"swap\" roll and pitch.\n       * Note that this transform does NOT handle NED->ENU conversions. Data is assumed\n       * to be in the ENU frame when it is received.\n       * */\n      if (imuData)\n      {\n        // First, convert the transform and measurement rotation to RPY\n        // @todo: There must be a way to handle this with quaternions. Need to look into it.\n        double rollOffset = 0;\n        double pitchOffset = 0;\n        double yawOffset = 0;\n        double roll = 0;\n        double pitch = 0;\n        double yaw = 0;\n        RosFilterUtilities::quatToRPY(targetFrameTrans.getRotation(), rollOffset, pitchOffset, yawOffset);\n        RosFilterUtilities::quatToRPY(poseTmp.getRotation(), roll, pitch, yaw);\n\n        // 6b. Apply the offset (making sure to bound them), and throw them in a vector\n        tf2::Vector3 rpyAngles(FilterUtilities::clampRotation(roll - rollOffset),\n                               FilterUtilities::clampRotation(pitch - pitchOffset),\n                               FilterUtilities::clampRotation(yaw - yawOffset));\n\n        // 6c. Now we need to rotate the roll and pitch by the yaw offset value.\n        // Imagine a case where an IMU is mounted facing sideways. In that case\n        // pitch for the IMU's world frame is roll for the robot.\n        tf2::Matrix3x3 mat;\n        mat.setRPY(0.0, 0.0, yawOffset);\n        rpyAngles = mat * rpyAngles;\n        poseTmp.getBasis().setRPY(rpyAngles.getX(), rpyAngles.getY(), rpyAngles.getZ());\n\n        // We will use this target transformation later on, but\n        // we've already transformed this data as if the IMU\n        // were mounted neutrall on the robot, so we can just\n        // make the transform the identity.\n        targetFrameTrans.setIdentity();\n      }\n\n      // 7. Two cases: if we're in differential mode, we need to generate a twist\n      // message. Otherwise, we just transform it to the target frame.\n      if (differential)\n      {\n        bool success = false;\n\n        // We're going to be playing with poseTmp, so store it,\n        // as we'll need to save its current value for the next\n        // measurement.\n        curMeasurement = poseTmp;\n\n        // Make sure we have previous measurements to work with\n        if (previousMeasurements_.count(topicName) > 0 && previousMeasurementCovariances_.count(topicName) > 0)\n        {\n          // 7a. If we are carrying out differential integration and\n          // we have a previous measurement for this sensor,then we\n          // need to apply the inverse of that measurement to this new\n          // measurement to produce a \"delta\" measurement between the two.\n          // Even if we're not using all of the variables from this sensor,\n          // we need to use the whole measurement to determine the delta\n          // to the new measurement\n          tf2::Transform prevMeasurement = previousMeasurements_[topicName];\n          poseTmp.setData(prevMeasurement.inverseTimes(poseTmp));\n\n          RF_DEBUG(\"Previous measurement:\\n\" << previousMeasurements_[topicName] <<\n                   \"\\nAfter removing previous measurement, measurement delta is:\\n\" << poseTmp << \"\\n\");\n\n          // 7b. Now we we have a measurement delta in the frame_id of the\n          // message, but we want that delta to be in the target frame, so\n          // we need to apply the rotation of the target frame transform.\n          targetFrameTrans.setOrigin(tf2::Vector3(0.0, 0.0, 0.0));\n          poseTmp.mult(targetFrameTrans, poseTmp);\n\n          RF_DEBUG(\"After rotating to the target frame, measurement delta is:\\n\" << poseTmp << \"\\n\");\n\n          // 7c. Now use the time difference from the last message to compute\n          // translational and rotational velocities\n          double dt = msg->header.stamp.toSec() - lastMessageTimes_[topicName].toSec();\n          double xVel = poseTmp.getOrigin().getX() / dt;\n          double yVel = poseTmp.getOrigin().getY() / dt;\n          double zVel = poseTmp.getOrigin().getZ() / dt;\n\n          double rollVel = 0;\n          double pitchVel = 0;\n          double yawVel = 0;\n\n          RosFilterUtilities::quatToRPY(poseTmp.getRotation(), rollVel, pitchVel, yawVel);\n          rollVel /= dt;\n          pitchVel /= dt;\n          yawVel /= dt;\n\n          RF_DEBUG(\"Previous message time was \" << lastMessageTimes_[topicName].toSec() <<\n                   \", current message time is \" << msg->header.stamp.toSec() << \", delta is \" <<\n                   dt << \", velocity is (vX, vY, vZ): (\" << xVel << \", \" << yVel << \", \" << zVel <<\n                   \")\\n\" << \"(vRoll, vPitch, vYaw): (\" << rollVel << \", \" << pitchVel << \", \" <<\n                   yawVel << \")\\n\");\n\n          // 7d. Fill out the velocity data in the message\n          geometry_msgs::TwistWithCovarianceStamped *twistPtr = new geometry_msgs::TwistWithCovarianceStamped();\n          twistPtr->header = msg->header;\n          twistPtr->header.frame_id = baseLinkFrameId_;\n          twistPtr->twist.twist.linear.x = xVel;\n          twistPtr->twist.twist.linear.y = yVel;\n          twistPtr->twist.twist.linear.z = zVel;\n          twistPtr->twist.twist.angular.x = rollVel;\n          twistPtr->twist.twist.angular.y = pitchVel;\n          twistPtr->twist.twist.angular.z = yawVel;\n          std::vector<int> twistUpdateVec(STATE_SIZE, false);\n          std::copy(updateVector.begin() + POSITION_OFFSET,\n                    updateVector.begin() + POSE_SIZE,\n                    twistUpdateVec.begin() + POSITION_V_OFFSET);\n          std::copy(twistUpdateVec.begin(), twistUpdateVec.end(), updateVector.begin());\n          geometry_msgs::TwistWithCovarianceStampedConstPtr ptr(twistPtr);\n\n          // 7e. Now rotate the previous covariance for this measurement to get it\n          // into the target frame, and add the current measurement's rotated covariance\n          // to the previous measurement's rotated covariance, and multiply by the time delta.\n          Eigen::MatrixXd prevCovarRotated = rot6d * previousMeasurementCovariances_[topicName] * rot6d.transpose();\n          covarianceRotated = (covarianceRotated.eval() + prevCovarRotated) * dt;\n          copyCovariance(covarianceRotated, &(twistPtr->twist.covariance[0]), POSE_SIZE);\n\n          RF_DEBUG(\"Previous measurement covariance:\\n\" << previousMeasurementCovariances_[topicName] <<\n                   \"\\nPrevious measurement covariance rotated:\\n\" << prevCovarRotated <<\n                   \"\\nFinal twist covariance:\\n\" << covarianceRotated << \"\\n\");\n\n          // Now pass this on to prepareTwist, which will convert it to the required frame\n          success = prepareTwist(ptr,\n                                 topicName + \"_twist\",\n                                 twistPtr->header.frame_id,\n                                 updateVector,\n                                 measurement,\n                                 measurementCovariance);\n        }\n\n        // 7f. Update the previous measurement and measurement covariance\n        previousMeasurements_[topicName] = curMeasurement;\n        previousMeasurementCovariances_[topicName] = covariance;\n\n        retVal = success;\n      }\n      else\n      {\n        // 7g. If we're in relative mode, remove the initial measurement\n        if (relative)\n        {\n          if (initialMeasurements_.count(topicName) == 0)\n          {\n            initialMeasurements_.insert(std::pair<std::string, tf2::Transform>(topicName, poseTmp));\n          }\n\n          tf2::Transform initialMeasurement = initialMeasurements_[topicName];\n          poseTmp.setData(initialMeasurement.inverseTimes(poseTmp));\n        }\n\n        // 7h. Apply the target frame transformation to the pose object.\n        poseTmp.mult(targetFrameTrans, poseTmp);\n        poseTmp.frame_id_ = finalTargetFrame;\n\n        // 7i. Finally, copy everything into our measurement and covariance objects\n        measurement(StateMemberX) = poseTmp.getOrigin().x();\n        measurement(StateMemberY) = poseTmp.getOrigin().y();\n        measurement(StateMemberZ) = poseTmp.getOrigin().z();\n\n        // The filter needs roll, pitch, and yaw values instead of quaternions\n        double roll, pitch, yaw;\n        RosFilterUtilities::quatToRPY(poseTmp.getRotation(), roll, pitch, yaw);\n        measurement(StateMemberRoll) = roll;\n        measurement(StateMemberPitch) = pitch;\n        measurement(StateMemberYaw) = yaw;\n\n        measurementCovariance.block(0, 0, POSE_SIZE, POSE_SIZE) = covarianceRotated.block(0, 0, POSE_SIZE, POSE_SIZE);\n\n        // 8. Handle 2D mode\n        if (twoDMode_)\n        {\n          forceTwoD(measurement, measurementCovariance, updateVector);\n        }\n\n        retVal = true;\n      }\n    }\n    else\n    {\n      retVal = false;\n\n      RF_DEBUG(\"Could not transform measurement into \" << finalTargetFrame << \". Ignoring...\");\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::preparePose (\" << topicName << \") ------\\n\");\n\n    return retVal;\n  }\n\n  template<typename T>\n  bool RosFilter<T>::prepareTwist(const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg,\n                               const std::string &topicName,\n                               const std::string &targetFrame,\n                               std::vector<int> &updateVector,\n                               Eigen::VectorXd &measurement,\n                               Eigen::MatrixXd &measurementCovariance)\n  {\n    RF_DEBUG(\"------ RosFilter::prepareTwist (\" << topicName << \") ------\\n\");\n\n    // 1. Get the measurement into two separate vector objects.\n    tf2::Vector3 twistLin(msg->twist.twist.linear.x,\n                          msg->twist.twist.linear.y,\n                          msg->twist.twist.linear.z);\n    tf2::Vector3 measTwistRot(msg->twist.twist.angular.x,\n                              msg->twist.twist.angular.y,\n                              msg->twist.twist.angular.z);\n\n    // 1a. This sensor may or may not measure rotational velocity. Regardless,\n    // if it measures linear velocity, then later on, we'll need to remove \"false\"\n    // linear velocity resulting from angular velocity and the translational offset\n    // of the sensor from the vehicle origin.\n    const Eigen::VectorXd &state = filter_.getState();\n    tf2::Vector3 stateTwistRot(state(StateMemberVroll),\n                               state(StateMemberVpitch),\n                               state(StateMemberVyaw));\n\n    // Determine the frame_id of the data\n    std::string msgFrame = (msg->header.frame_id == \"\" ? targetFrame : msg->header.frame_id);\n\n    // 2. robot_localization lets users configure which variables from the sensor should be\n    //    fused with the filter. This is specified at the sensor level. However, the data\n    //    may go through transforms before being fused with the state estimate. In that case,\n    //    we need to know which of the transformed variables came from the pre-transformed\n    //    \"approved\" variables (i.e., the ones that had \"true\" in their xxx_config parameter).\n    //    To do this, we construct matrices using the update vector values on the diagonals,\n    //    pass this matrix through the rotation, and use the length of each row to determine\n    //    the transformed update vector.\n    tf2::Matrix3x3 maskLin(updateVector[StateMemberVx], 0, 0,\n                           0, updateVector[StateMemberVy], 0,\n                           0, 0, updateVector[StateMemberVz]);\n\n    tf2::Matrix3x3 maskRot(updateVector[StateMemberVroll], 0, 0,\n                           0, updateVector[StateMemberVpitch], 0,\n                           0, 0, updateVector[StateMemberVyaw]);\n\n    // 3. We'll need to rotate the covariance as well\n    Eigen::MatrixXd covarianceRotated(TWIST_SIZE, TWIST_SIZE);\n    covarianceRotated.setZero();\n\n    copyCovariance(&(msg->twist.covariance[0]),\n                   covarianceRotated,\n                   topicName,\n                   updateVector,\n                   POSITION_V_OFFSET,\n                   TWIST_SIZE);\n\n    RF_DEBUG(\"Original measurement as tf object:\\nLinear: \" << twistLin <<\n             \"Rotational: \" << measTwistRot <<\n             \"\\nOriginal update vector:\\n\" << updateVector <<\n             \"\\nOriginal covariance matrix:\\n\" << covarianceRotated << \"\\n\");\n\n    // 4. We need to transform this into the target frame (probably base_link)\n    tf2::Transform targetFrameTrans;\n    bool canTransform = RosFilterUtilities::lookupTransformSafe(tfBuffer_,\n                                                                targetFrame,\n                                                                msgFrame,\n                                                                msg->header.stamp,\n                                                                tfTimeout_,\n                                                                targetFrameTrans);\n\n    if (canTransform)\n    {\n      // Transform to correct frame. Note that we can get linear velocity\n      // as a result of the sensor offset and rotational velocity\n      measTwistRot = targetFrameTrans.getBasis() * measTwistRot;\n      twistLin = targetFrameTrans.getBasis() * twistLin + targetFrameTrans.getOrigin().cross(stateTwistRot);\n      maskLin = targetFrameTrans.getBasis() * maskLin;\n      maskRot = targetFrameTrans.getBasis() * maskRot;\n\n      // Now copy the mask values back into the update vector\n      updateVector[StateMemberVx] = static_cast<int>(\n        maskLin.getRow(StateMemberVx - POSITION_V_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberVy] = static_cast<int>(\n        maskLin.getRow(StateMemberVy - POSITION_V_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberVz] = static_cast<int>(\n        maskLin.getRow(StateMemberVz - POSITION_V_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberVroll] = static_cast<int>(\n        maskRot.getRow(StateMemberVroll - ORIENTATION_V_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberVpitch] = static_cast<int>(\n        maskRot.getRow(StateMemberVpitch - ORIENTATION_V_OFFSET).length() >= 1e-6);\n      updateVector[StateMemberVyaw] = static_cast<int>(\n        maskRot.getRow(StateMemberVyaw - ORIENTATION_V_OFFSET).length() >= 1e-6);\n\n      RF_DEBUG(msg->header.frame_id << \"->\" << targetFrame << \" transform:\\n\" << targetFrameTrans <<\n               \"\\nAfter applying transform to \" << targetFrame << \", update vector is:\\n\" << updateVector <<\n               \"\\nAfter applying transform to \" << targetFrame << \", measurement is:\\n\" <<\n               \"Linear: \" << twistLin << \"Rotational: \" << measTwistRot << \"\\n\");\n\n      // 5. Now rotate the covariance: create an augmented\n      // matrix that contains a 3D rotation matrix in the\n      // upper-left and lower-right quadrants, and zeros\n      // elsewhere\n      tf2::Matrix3x3 rot(targetFrameTrans.getRotation());\n      Eigen::MatrixXd rot6d(TWIST_SIZE, TWIST_SIZE);\n      rot6d.setIdentity();\n\n      for (size_t rInd = 0; rInd < POSITION_SIZE; ++rInd)\n      {\n        rot6d(rInd, 0) = rot.getRow(rInd).getX();\n        rot6d(rInd, 1) = rot.getRow(rInd).getY();\n        rot6d(rInd, 2) = rot.getRow(rInd).getZ();\n        rot6d(rInd+POSITION_SIZE, 3) = rot.getRow(rInd).getX();\n        rot6d(rInd+POSITION_SIZE, 4) = rot.getRow(rInd).getY();\n        rot6d(rInd+POSITION_SIZE, 5) = rot.getRow(rInd).getZ();\n      }\n\n      // Carry out the rotation\n      covarianceRotated = rot6d * covarianceRotated.eval() * rot6d.transpose();\n\n      RF_DEBUG(\"Transformed covariance is \\n\" << covarianceRotated << \"\\n\");\n\n      // 6. Store our corrected measurement and covariance\n      measurement(StateMemberVx) = twistLin.getX();\n      measurement(StateMemberVy) = twistLin.getY();\n      measurement(StateMemberVz) = twistLin.getZ();\n      measurement(StateMemberVroll) = measTwistRot.getX();\n      measurement(StateMemberVpitch) = measTwistRot.getY();\n      measurement(StateMemberVyaw) = measTwistRot.getZ();\n\n      // Copy the covariances\n      measurementCovariance.block(POSITION_V_OFFSET, POSITION_V_OFFSET, TWIST_SIZE, TWIST_SIZE) =\n        covarianceRotated.block(0, 0, TWIST_SIZE, TWIST_SIZE);\n\n      // 7. Handle 2D mode\n      if (twoDMode_)\n      {\n        forceTwoD(measurement, measurementCovariance, updateVector);\n      }\n    }\n    else\n    {\n      RF_DEBUG(\"Could not transform measurement into \" << targetFrame << \". Ignoring...\");\n    }\n\n    RF_DEBUG(\"\\n----- /RosFilter::prepareTwist (\" << topicName << \") ------\\n\");\n\n    return canTransform;\n  }\n\n  template<typename T>\n  void RosFilter<T>::saveFilterState(FilterBase& filter)\n  {\n    FilterStatePtr state = FilterStatePtr(new FilterState());\n    state->state_ = Eigen::VectorXd(filter.getState());\n    state->estimateErrorCovariance_ = Eigen::MatrixXd(filter.getEstimateErrorCovariance());\n    state->lastMeasurementTime_ = filter.getLastMeasurementTime();\n    state->latestControl_ = Eigen::VectorXd(filter.getControl());\n    state->latestControlTime_ = filter.getControlTime();\n    filterStateHistory_.push_back(state);\n    RF_DEBUG(\"Saved state with timestamp \" << std::setprecision(20) << state->lastMeasurementTime_ <<\n             \" to history. \" << filterStateHistory_.size() << \" measurements are in the queue.\\n\");\n  }\n\n  template<typename T>\n  bool RosFilter<T>::revertTo(const double time)\n  {\n    RF_DEBUG(\"\\n----- RosFilter::revertTo -----\\n\");\n    RF_DEBUG(\"\\nRequested time was \" << std::setprecision(20) << time << \"\\n\")\n\n    // Walk back through the queue until we reach a filter state whose time stamp is less than or equal to the\n    // requested time. Since every saved state after that time will be overwritten/corrected, we can pop from\n    // the queue. If the history is insufficiently short, we just take the oldest state we have.\n    FilterStatePtr lastHistoryState;\n    while (!filterStateHistory_.empty() && filterStateHistory_.back()->lastMeasurementTime_ > time)\n    {\n      lastHistoryState = filterStateHistory_.back();\n      filterStateHistory_.pop_back();\n    }\n\n    // If the state history is not empty at this point, it means that our history was large enough, and we\n    // should revert to the state at the back of the history deque.\n    bool retVal = false;\n    if (!filterStateHistory_.empty())\n    {\n      retVal = true;\n      lastHistoryState = filterStateHistory_.back();\n    }\n    else\n    {\n      RF_DEBUG(\"Insufficient history to revert to time \" << time << \"\\n\");\n\n      if (lastHistoryState.get() != NULL)\n      {\n        RF_DEBUG(\"Will revert to oldest state at \" << lastHistoryState->latestControlTime_ << \".\\n\");\n      }\n    }\n\n    // If we have a valid reversion state, revert\n    if (lastHistoryState.get() != NULL)\n    {\n      // Reset filter to the latest state from the queue.\n      const FilterStatePtr &state = lastHistoryState;\n      filter_.setState(state->state_);\n      filter_.setEstimateErrorCovariance(state->estimateErrorCovariance_);\n      filter_.setLastMeasurementTime(state->lastMeasurementTime_);\n\n      RF_DEBUG(\"Reverted to state with time \" << std::setprecision(20) << state->lastMeasurementTime_ << \"\\n\");\n    }\n\n    // Repeat for measurements, but push every measurement onto the measurement queue as we go\n    int restored_measurements = 0;\n    while (!measurementHistory_.empty() && measurementHistory_.back()->time_ > time)\n    {\n      measurementQueue_.push(measurementHistory_.back());\n      measurementHistory_.pop_back();\n      restored_measurements++;\n    }\n\n    RF_DEBUG(\"Restored \" << restored_measurements << \" to measurement queue.\\n\");\n\n    RF_DEBUG(\"\\n----- /RosFilter::revertTo\\n\");\n\n    return retVal;\n  }\n\n  template<typename T>\n  bool RosFilter<T>::validateFilterOutput(const nav_msgs::Odometry &message)\n  {\n    return !std::isnan(message.pose.pose.position.x) && !std::isinf(message.pose.pose.position.x) &&\n           !std::isnan(message.pose.pose.position.y) && !std::isinf(message.pose.pose.position.y) &&\n           !std::isnan(message.pose.pose.position.z) && !std::isinf(message.pose.pose.position.z) &&\n           !std::isnan(message.pose.pose.orientation.x) && !std::isinf(message.pose.pose.orientation.x) &&\n           !std::isnan(message.pose.pose.orientation.y) && !std::isinf(message.pose.pose.orientation.y) &&\n           !std::isnan(message.pose.pose.orientation.z) && !std::isinf(message.pose.pose.orientation.z) &&\n           !std::isnan(message.pose.pose.orientation.w) && !std::isinf(message.pose.pose.orientation.w) &&\n           !std::isnan(message.twist.twist.linear.x) && !std::isinf(message.twist.twist.linear.x) &&\n           !std::isnan(message.twist.twist.linear.y) && !std::isinf(message.twist.twist.linear.y) &&\n           !std::isnan(message.twist.twist.linear.z) && !std::isinf(message.twist.twist.linear.z) &&\n           !std::isnan(message.twist.twist.angular.x) && !std::isinf(message.twist.twist.angular.x) &&\n           !std::isnan(message.twist.twist.angular.y) && !std::isinf(message.twist.twist.angular.y) &&\n           !std::isnan(message.twist.twist.angular.z) && !std::isinf(message.twist.twist.angular.z);\n  }\n\n  template<typename T>\n  void RosFilter<T>::clearExpiredHistory(const double cutOffTime)\n  {\n    RF_DEBUG(\"\\n----- RosFilter::clearExpiredHistory -----\" <<\n             \"\\nCutoff time is \" << cutOffTime << \"\\n\");\n\n    int poppedMeasurements = 0;\n    int poppedStates = 0;\n\n    while (!measurementHistory_.empty() && measurementHistory_.front()->time_ < cutOffTime)\n    {\n      measurementHistory_.pop_front();\n      poppedMeasurements++;\n    }\n\n    while (!filterStateHistory_.empty() && filterStateHistory_.front()->lastMeasurementTime_ < cutOffTime)\n    {\n      filterStateHistory_.pop_front();\n      poppedStates++;\n    }\n\n    RF_DEBUG(\"\\nPopped \" << poppedMeasurements << \" measurements and \" <<\n             poppedStates << \" states from their respective queues.\" <<\n             \"\\n---- /RosFilter::clearExpiredHistory ----\\n\");\n  }\n}  // namespace RobotLocalization\n\n// Instantiations of classes is required when template class code\n// is placed in a .cpp file.\ntemplate class RobotLocalization::RosFilter<RobotLocalization::Ekf>;\ntemplate class RobotLocalization::RosFilter<RobotLocalization::Ukf>;\n"
  },
  {
    "path": "src/robot_localization/src/ros_filter_utilities.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_filter_utilities.h\"\n#include \"robot_localization/filter_common.h\"\n\n#include <tf2_geometry_msgs/tf2_geometry_msgs.h>\n#include <ros/console.h>\n\n#include <string>\n#include <vector>\n\nstd::ostream& operator<<(std::ostream& os, const tf2::Vector3 &vec)\n{\n  os << \"(\" << std::setprecision(20) << vec.getX() << \" \" << vec.getY() << \" \" << vec.getZ() << \")\\n\";\n\n  return os;\n}\n\nstd::ostream& operator<<(std::ostream& os, const tf2::Quaternion &quat)\n{\n  double roll, pitch, yaw;\n  tf2::Matrix3x3 orTmp(quat);\n  orTmp.getRPY(roll, pitch, yaw);\n\n  os << \"(\" << std::setprecision(20) << roll << \", \" << pitch << \", \" << yaw << \")\\n\";\n\n  return os;\n}\n\nstd::ostream& operator<<(std::ostream& os, const tf2::Transform &trans)\n{\n  os << \"Origin: \" << trans.getOrigin() <<\n        \"Rotation (RPY): \" << trans.getRotation();\n\n  return os;\n}\n\nstd::ostream& operator<<(std::ostream& os, const std::vector<double> &vec)\n{\n  os << \"(\" << std::setprecision(20);\n\n  for (size_t i = 0; i < vec.size(); ++i)\n  {\n    os << vec[i] << \" \";\n  }\n\n  os << \")\\n\";\n\n  return os;\n}\n\nnamespace RobotLocalization\n{\nnamespace RosFilterUtilities\n{\n\n  double getYaw(const tf2::Quaternion quat)\n  {\n    tf2::Matrix3x3 mat(quat);\n\n    double dummy;\n    double yaw;\n    mat.getRPY(dummy, dummy, yaw);\n\n    return yaw;\n  }\n\n  bool lookupTransformSafe(const tf2_ros::Buffer &buffer,\n                           const std::string &targetFrame,\n                           const std::string &sourceFrame,\n                           const ros::Time &time,\n                           const ros::Duration &timeout,\n                           tf2::Transform &targetFrameTrans,\n                           const bool silent)\n  {\n    bool retVal = true;\n\n    // First try to transform the data at the requested time\n    try\n    {\n      tf2::fromMsg(buffer.lookupTransform(targetFrame, sourceFrame, time, timeout).transform,\n                   targetFrameTrans);\n    }\n    catch (tf2::TransformException &ex)\n    {\n      // The issue might be that the transforms that are available are not close\n      // enough temporally to be used. In that case, just use the latest available\n      // transform and warn the user.\n      try\n      {\n        tf2::fromMsg(buffer.lookupTransform(targetFrame, sourceFrame, ros::Time(0)).transform,\n                     targetFrameTrans);\n\n        if (!silent)\n        {\n          ROS_WARN_STREAM_THROTTLE(2.0, \"Transform from \" << sourceFrame << \" to \" << targetFrame <<\n                                        \" was unavailable for the time requested. Using latest instead.\\n\");\n        }\n      }\n      catch(tf2::TransformException &ex)\n      {\n        if (!silent)\n        {\n          ROS_WARN_STREAM_THROTTLE(2.0, \"Could not obtain transform from \" << sourceFrame <<\n                                        \" to \" << targetFrame << \". Error was \" << ex.what() << \"\\n\");\n        }\n\n        retVal = false;\n      }\n    }\n\n    // Transforming from a frame id to itself can fail when the tf tree isn't\n    // being broadcast (e.g., for some bag files). This is the only failure that\n    // would throw an exception, so check for this situation before giving up.\n    if (!retVal)\n    {\n      if (targetFrame == sourceFrame)\n      {\n        targetFrameTrans.setIdentity();\n        retVal = true;\n      }\n    }\n\n    return retVal;\n  }\n\n  bool lookupTransformSafe(const tf2_ros::Buffer &buffer,\n                           const std::string &targetFrame,\n                           const std::string &sourceFrame,\n                           const ros::Time &time,\n                           tf2::Transform &targetFrameTrans,\n                           const bool silent)\n  {\n    return lookupTransformSafe(buffer, targetFrame, sourceFrame, time, ros::Duration(0), targetFrameTrans, silent);\n  }\n\n  void quatToRPY(const tf2::Quaternion &quat, double &roll, double &pitch, double &yaw)\n  {\n    tf2::Matrix3x3 orTmp(quat);\n    orTmp.getRPY(roll, pitch, yaw);\n  }\n\n  void stateToTF(const Eigen::VectorXd &state, tf2::Transform &stateTF)\n  {\n    stateTF.setOrigin(tf2::Vector3(state(StateMemberX),\n                                   state(StateMemberY),\n                                   state(StateMemberZ)));\n    tf2::Quaternion quat;\n    quat.setRPY(state(StateMemberRoll),\n                state(StateMemberPitch),\n                state(StateMemberYaw));\n\n    stateTF.setRotation(quat);\n  }\n\n  void TFtoState(const tf2::Transform &stateTF, Eigen::VectorXd &state)\n  {\n    state(StateMemberX) = stateTF.getOrigin().getX();\n    state(StateMemberY) = stateTF.getOrigin().getY();\n    state(StateMemberZ) = stateTF.getOrigin().getZ();\n    quatToRPY(stateTF.getRotation(), state(StateMemberRoll), state(StateMemberPitch), state(StateMemberYaw));\n  }\n\n}  // namespace RosFilterUtilities\n}  // namespace RobotLocalization\n"
  },
  {
    "path": "src/robot_localization/src/ros_robot_localization_listener.cpp",
    "content": "/*\n * Copyright (c) 2016, TNO IVS Helmond.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_robot_localization_listener.h\"\n#include \"robot_localization/ros_filter_utilities.h\"\n\n#include <string>\n#include <vector>\n\n#include <Eigen/Dense>\n#include <tf2/LinearMath/Matrix3x3.h>\n#include <tf2/LinearMath/Quaternion.h>\n#include <tf2_geometry_msgs/tf2_geometry_msgs.h>\n#include <yaml-cpp/yaml.h>\n#include <eigen_conversions/eigen_msg.h>\n\n#include <XmlRpcException.h>\n\nnamespace RobotLocalization\n{\n\nFilterType filterTypeFromString(const std::string& filter_type_str)\n{\n  if ( filter_type_str == \"ekf\" )\n  {\n    return FilterTypes::EKF;\n  }\n  else if ( filter_type_str == \"ukf\" )\n  {\n    return FilterTypes::UKF;\n  }\n  else\n  {\n    return FilterTypes::NotDefined;\n  }\n}\n\nRosRobotLocalizationListener::RosRobotLocalizationListener():\n  nh_p_(\"robot_localization\"),\n  odom_sub_(nh_, \"odometry/filtered\", 1),\n  accel_sub_(nh_, \"accel/filtered\", 1),\n  sync_(odom_sub_, accel_sub_, 10),\n  tf_listener_(tf_buffer_),\n  base_frame_id_(\"\"),\n  world_frame_id_(\"\")\n{\n  int buffer_size;\n  nh_p_.param(\"buffer_size\", buffer_size, 10);\n\n  std::string param_ns;\n  nh_p_.param(\"parameter_namespace\", param_ns, nh_p_.getNamespace());\n\n  ros::NodeHandle nh_param(param_ns);\n\n  std::string filter_type_str;\n  nh_param.param(\"filter_type\", filter_type_str, std::string(\"ekf\"));\n  FilterType filter_type = filterTypeFromString(filter_type_str);\n  if ( filter_type == FilterTypes::NotDefined )\n  {\n    ROS_ERROR(\"RosRobotLocalizationListener: Parameter filter_type invalid\");\n    return;\n  }\n\n  // Load up the process noise covariance (from the launch file/parameter server)\n  // todo: this code is copied from ros_filter. In a refactor, this could be moved to a function in ros_filter_utilities\n  Eigen::MatrixXd process_noise_covariance(STATE_SIZE, STATE_SIZE);\n  process_noise_covariance.setZero();\n  XmlRpc::XmlRpcValue process_noise_covar_config;\n\n  if (!nh_param.hasParam(\"process_noise_covariance\"))\n  {\n    ROS_FATAL_STREAM(\"Process noise covariance not found in the robot localization listener config (namespace \" <<\n                     nh_param.getNamespace() << \")! Use the ~parameter_namespace to specify the parameter namespace.\");\n  }\n  else\n  {\n    try\n    {\n      nh_param.getParam(\"process_noise_covariance\", process_noise_covar_config);\n\n      ROS_ASSERT(process_noise_covar_config.getType() == XmlRpc::XmlRpcValue::TypeArray);\n\n      int mat_size = process_noise_covariance.rows();\n\n      for (int i = 0; i < mat_size; i++)\n      {\n        for (int j = 0; j < mat_size; j++)\n        {\n          try\n          {\n            // These matrices can cause problems if all the types\n            // aren't specified with decimal points. Handle that\n            // using string streams.\n            std::ostringstream ostr;\n            process_noise_covar_config[mat_size * i + j].write(ostr);\n            std::istringstream istr(ostr.str());\n            istr >> process_noise_covariance(i, j);\n          }\n          catch(XmlRpc::XmlRpcException &e)\n          {\n            throw e;\n          }\n          catch(...)\n          {\n            throw;\n          }\n        }\n      }\n\n      ROS_DEBUG_STREAM(\"Process noise covariance is:\\n\" << process_noise_covariance << \"\\n\");\n    }\n    catch (XmlRpc::XmlRpcException &e)\n    {\n      ROS_ERROR_STREAM(\"ERROR reading robot localization listener config: \" <<\n                       e.getMessage() <<\n                       \" for process_noise_covariance (type: \" <<\n                       process_noise_covar_config.getType() << \")\");\n    }\n  }\n\n  std::vector<double> filter_args;\n  nh_param.param(\"filter_args\", filter_args, std::vector<double>());\n\n  estimator_ = new RobotLocalizationEstimator(buffer_size, filter_type, process_noise_covariance, filter_args);\n\n  sync_.registerCallback(&RosRobotLocalizationListener::odomAndAccelCallback, this);\n\n  ROS_INFO_STREAM(\"Ros Robot Localization Listener: Listening to topics \" <<\n                  odom_sub_.getTopic() << \" and \" << accel_sub_.getTopic());\n\n  // Wait until the base and world frames are set by the incoming messages\n  while (ros::ok() && base_frame_id_.empty())\n  {\n    ros::spinOnce();\n    ROS_INFO_STREAM_THROTTLE(1.0, \"Ros Robot Localization Listener: Waiting for incoming messages on topics \" <<\n                             odom_sub_.getTopic() << \" and \" << accel_sub_.getTopic());\n    ros::Duration(0.1).sleep();\n  }\n}\n\nRosRobotLocalizationListener::~RosRobotLocalizationListener()\n{\n  delete estimator_;\n}\n\nvoid RosRobotLocalizationListener::odomAndAccelCallback(const nav_msgs::Odometry& odom,\n                                                        const geometry_msgs::AccelWithCovarianceStamped& accel)\n{\n  // Instantiate a state that can be added to the robot localization estimator\n  EstimatorState state;\n\n  // Set its time stamp and the state received from the messages\n  state.time_stamp = odom.header.stamp.toSec();\n\n  // Get the base frame id from the odom message\n  if ( base_frame_id_.empty() )\n    base_frame_id_ = odom.child_frame_id;\n\n  // Get the world frame id from the odom message\n  if ( world_frame_id_.empty() )\n    world_frame_id_ = odom.header.frame_id;\n\n  // Pose: Position\n  state.state(StateMemberX) = odom.pose.pose.position.x;\n  state.state(StateMemberY) = odom.pose.pose.position.y;\n  state.state(StateMemberZ) = odom.pose.pose.position.z;\n\n  // Pose: Orientation\n  tf2::Quaternion orientation_quat;\n  tf2::fromMsg(odom.pose.pose.orientation, orientation_quat);\n  double roll, pitch, yaw;\n  RosFilterUtilities::quatToRPY(orientation_quat, roll, pitch, yaw);\n\n  state.state(StateMemberRoll) = roll;\n  state.state(StateMemberPitch) = pitch;\n  state.state(StateMemberYaw) = yaw;\n\n  // Pose: Covariance\n  for ( unsigned int i = 0; i < POSE_SIZE; i++ )\n  {\n    for ( unsigned int j = 0; j < POSE_SIZE; j++ )\n    {\n      state.covariance(POSITION_OFFSET + i, POSITION_OFFSET + j) = odom.pose.covariance[i*POSE_SIZE + j];\n    }\n  }\n\n  // Velocity: Linear\n  state.state(StateMemberVx) = odom.twist.twist.linear.x;\n  state.state(StateMemberVy) = odom.twist.twist.linear.y;\n  state.state(StateMemberVz) = odom.twist.twist.linear.z;\n\n  // Velocity: Angular\n  state.state(StateMemberVroll) = odom.twist.twist.angular.x;\n  state.state(StateMemberVpitch) = odom.twist.twist.angular.y;\n  state.state(StateMemberVyaw) = odom.twist.twist.angular.z;\n\n  // Velocity: Covariance\n  for ( unsigned int i = 0; i < TWIST_SIZE; i++ )\n  {\n    for ( unsigned int j = 0; j < TWIST_SIZE; j++ )\n    {\n      state.covariance(POSITION_V_OFFSET + i, POSITION_V_OFFSET + j) = odom.twist.covariance[i*TWIST_SIZE + j];\n    }\n  }\n\n  // Acceleration: Linear\n  state.state(StateMemberAx) = accel.accel.accel.linear.x;\n  state.state(StateMemberAy) = accel.accel.accel.linear.y;\n  state.state(StateMemberAz) = accel.accel.accel.linear.z;\n\n  // Acceleration: Angular is not available in state\n\n  // Acceleration: Covariance\n  for ( unsigned int i = 0; i < ACCELERATION_SIZE; i++ )\n  {\n    for ( unsigned int j = 0; j < ACCELERATION_SIZE; j++ )\n    {\n      state.covariance(POSITION_A_OFFSET + i, POSITION_A_OFFSET + j) = accel.accel.covariance[i*TWIST_SIZE + j];\n    }\n  }\n\n  // Add the state to the buffer, so that we can later interpolate between this and earlier states\n  estimator_->setState(state);\n\n  return;\n}\n\nbool findAncestorRecursiveYAML(YAML::Node& tree, const std::string& source_frame, const std::string& target_frame)\n{\n  if ( source_frame == target_frame )\n  {\n    return true;\n  }\n\n  std::string parent_frame = tree[source_frame][\"parent\"].Scalar();\n\n  if ( parent_frame.empty() )\n  {\n    return false;\n  }\n\n  return findAncestorRecursiveYAML(tree, parent_frame, target_frame);\n}\n\n// Cache, assumption that the tree parent child order does not change over time\nstatic std::map<std::string, std::vector<std::string> > ancestor_map;\nstatic std::map<std::string, std::vector<std::string> > descendant_map;\nbool findAncestor(const tf2_ros::Buffer& buffer, const std::string& source_frame, const std::string& target_frame)\n{\n  // Check cache\n  const std::vector<std::string>& ancestors = ancestor_map[source_frame];\n  if (std::find(ancestors.begin(), ancestors.end(), target_frame) != ancestors.end())\n  {\n    return true;\n  }\n  const std::vector<std::string>& descendants = descendant_map[source_frame];\n  if (std::find(descendants.begin(), descendants.end(), target_frame) != descendants.end())\n  {\n    return false;\n  }\n\n  std::stringstream frames_stream(buffer.allFramesAsYAML());\n  YAML::Node frames_yaml = YAML::Load(frames_stream);\n\n  bool target_frame_is_ancestor = findAncestorRecursiveYAML(frames_yaml, source_frame, target_frame);\n  bool target_frame_is_descendant = findAncestorRecursiveYAML(frames_yaml, target_frame, source_frame);\n\n  // Caching\n  if (target_frame_is_ancestor)\n  {\n    ancestor_map[source_frame].push_back(target_frame);\n  }\n  if (target_frame_is_descendant)\n  {\n    descendant_map[source_frame].push_back(target_frame);\n  }\n\n  return target_frame_is_ancestor;\n}\n\n\nbool RosRobotLocalizationListener::getState(const double time,\n                                            const std::string& frame_id,\n                                            Eigen::VectorXd& state,\n                                            Eigen::MatrixXd& covariance,\n                                            std::string world_frame_id) const\n{\n  EstimatorState estimator_state;\n  state.resize(STATE_SIZE);\n  state.setZero();\n  covariance.resize(STATE_SIZE, STATE_SIZE);\n  covariance.setZero();\n\n  if ( base_frame_id_.empty() || world_frame_id_.empty()  )\n  {\n    if ( estimator_->getSize() == 0 )\n    {\n      ROS_WARN(\"Ros Robot Localization Listener: The base or world frame id is not set. \"\n               \"No odom/accel messages have come in.\");\n    }\n    else\n    {\n      ROS_ERROR(\"Ros Robot Localization Listener: The base or world frame id is not set. \"\n                \"Are the child_frame_id and the header.frame_id in the odom messages set?\");\n    }\n\n    return false;\n  }\n\n  if ( estimator_->getState(time, estimator_state) == EstimatorResults::ExtrapolationIntoPast )\n  {\n    ROS_WARN(\"Ros Robot Localization Listener: A state is requested at a time stamp older than the oldest in the \"\n             \"estimator buffer. The result is an extrapolation into the past. Maybe you should increase the buffer \"\n             \"size?\");\n  }\n\n  // If no world_frame_id is specified, we will default to the world frame_id of the received odometry message\n  if (world_frame_id.empty())\n  {\n    world_frame_id = world_frame_id_;\n  }\n\n  if ( frame_id == base_frame_id_ && world_frame_id == world_frame_id_ )\n  {\n    // If the state of the base frame is requested and the world frame equals the world frame of the robot_localization\n    // estimator, we can simply return the state we got from the state estimator\n    state = estimator_state.state;\n    covariance = estimator_state.covariance;\n    return true;\n  }\n\n  // - - - - - - - - - - - - - - - - - -\n  // Get the transformation between the requested world frame and the world_frame of the estimator\n  // - - - - - - - - - - - - - - - - - -\n  Eigen::Affine3d world_pose_requested_frame;\n\n  // If the requested frame is the same as the tracker, set to identity\n  if (world_frame_id == world_frame_id_)\n  {\n    world_pose_requested_frame.setIdentity();\n  }\n  else\n  {\n    geometry_msgs::TransformStamped world_requested_to_world_transform;\n    try\n    {\n      world_requested_to_world_transform = tf_buffer_.lookupTransform(world_frame_id,\n                                                                      world_frame_id_,\n                                                                      ros::Time(time),\n                                                                      ros::Duration(0.1));  // TODO: magic number\n\n      if ( findAncestor(tf_buffer_, world_frame_id, base_frame_id_) )\n      {\n        ROS_ERROR_STREAM(\"You are trying to get the state with respect to world frame \" << world_frame_id <<\n                         \", but this frame is a child of robot base frame \" << base_frame_id_ <<\n                         \", so this doesn't make sense.\");\n        return false;\n      }\n    }\n    catch ( tf2::TransformException e )\n    {\n      ROS_WARN_STREAM(\"Ros Robot Localization Listener: Could not look up transform: \" << e.what());\n      return false;\n    }\n\n    // Convert to pose\n    tf::transformMsgToEigen(world_requested_to_world_transform.transform, world_pose_requested_frame);\n  }\n\n  // - - - - - - - - - - - - - - - - - -\n  // Calculate the state of the requested frame from the state of the base frame.\n  // - - - - - - - - - - - - - - - - - -\n\n  // First get the transform from base to target\n  geometry_msgs::TransformStamped base_to_target_transform;\n  try\n  {\n    base_to_target_transform = tf_buffer_.lookupTransform(base_frame_id_,\n                                                          frame_id,\n                                                          ros::Time(time),\n                                                          ros::Duration(0.1));  // TODO: magic number\n\n    // Check that frame_id is a child of the base frame. If it is not, it does not make sense to request its state.\n    // Do this after tf lookup, so we know that there is a connection.\n    if ( ! findAncestor(tf_buffer_, frame_id, base_frame_id_) )\n    {\n      ROS_ERROR_STREAM(\"You are trying to get the state of \" << frame_id << \", but this frame is not a child of the \"\n                                                                            \"base frame: \" << base_frame_id_ << \".\");\n      return false;\n    }\n  }\n  catch ( tf2::TransformException e )\n  {\n    ROS_WARN_STREAM(\"Ros Robot Localization Listener: Could not look up transform: \" << e.what());\n    return false;\n  }\n\n  // And convert it to an eigen Affine transformation\n  Eigen::Affine3d target_pose_base;\n  tf::transformMsgToEigen(base_to_target_transform.transform, target_pose_base);\n\n  // Then convert the base pose to an Eigen Affine transformation\n  Eigen::Vector3d base_position(estimator_state.state(StateMemberX),\n                                estimator_state.state(StateMemberY),\n                                estimator_state.state(StateMemberZ));\n\n  Eigen::AngleAxisd roll_angle(estimator_state.state(StateMemberRoll), Eigen::Vector3d::UnitX());\n  Eigen::AngleAxisd pitch_angle(estimator_state.state(StateMemberPitch), Eigen::Vector3d::UnitY());\n  Eigen::AngleAxisd yaw_angle(estimator_state.state(StateMemberYaw), Eigen::Vector3d::UnitZ());\n\n  Eigen::Quaterniond base_orientation(yaw_angle * pitch_angle * roll_angle);\n\n  Eigen::Affine3d base_pose(Eigen::Translation3d(base_position) * base_orientation);\n\n  // Now we can calculate the transform from odom to the requested frame (target)...\n  Eigen::Affine3d target_pose_odom = world_pose_requested_frame * base_pose * target_pose_base;\n\n  // ... and put it in the output state\n  state(StateMemberX) = target_pose_odom.translation().x();\n  state(StateMemberY) = target_pose_odom.translation().y();\n  state(StateMemberZ) = target_pose_odom.translation().z();\n\n  Eigen::Vector3d ypr = target_pose_odom.rotation().eulerAngles(2, 1, 0);\n\n  state(StateMemberRoll)  = ypr[2];\n  state(StateMemberPitch) = ypr[1];\n  state(StateMemberYaw)   = ypr[0];\n\n  // Now let's calculate the twist of the target frame\n  // First get the base's twist\n  Twist base_velocity;\n  Twist target_velocity_base;\n  base_velocity.linear = Eigen::Vector3d(estimator_state.state(StateMemberVx),\n                                         estimator_state.state(StateMemberVy),\n                                         estimator_state.state(StateMemberVz));\n  base_velocity.angular = Eigen::Vector3d(estimator_state.state(StateMemberVroll),\n                                          estimator_state.state(StateMemberVpitch),\n                                          estimator_state.state(StateMemberVyaw));\n\n  // Then calculate the target frame's twist as a result of the base's twist.\n  /*\n   * We first calculate the coordinates of the velocity vectors (linear and angular) in the base frame. We have to keep\n   * in mind that a rotation of the base frame, together with the translational offset of the target frame from the base\n   * frame, induces a translational velocity of the target frame.\n   */\n  target_velocity_base.linear = base_velocity.linear + base_velocity.angular.cross(target_pose_base.translation());\n  target_velocity_base.angular = base_velocity.angular;\n\n  // Now we can transform that to the target frame\n  Twist target_velocity;\n  target_velocity.linear = target_pose_base.rotation().transpose() * target_velocity_base.linear;\n  target_velocity.angular = target_pose_base.rotation().transpose() * target_velocity_base.angular;\n\n  state(StateMemberVx) = target_velocity.linear(0);\n  state(StateMemberVy) = target_velocity.linear(1);\n  state(StateMemberVz) = target_velocity.linear(2);\n\n  state(StateMemberVroll) = target_velocity.angular(0);\n  state(StateMemberVpitch) = target_velocity.angular(1);\n  state(StateMemberVyaw) = target_velocity.angular(2);\n\n  // Rotate the covariance as well\n  Eigen::MatrixXd rot_6d(POSE_SIZE, POSE_SIZE);\n  rot_6d.setIdentity();\n\n  rot_6d.block<POSITION_SIZE, POSITION_SIZE>(POSITION_OFFSET, POSITION_OFFSET) = target_pose_base.rotation();\n  rot_6d.block<ORIENTATION_SIZE, ORIENTATION_SIZE>(ORIENTATION_OFFSET, ORIENTATION_OFFSET) = target_pose_base.rotation();\n\n  // Rotate the covariance\n  covariance.block<POSE_SIZE, POSE_SIZE>(POSITION_OFFSET, POSITION_OFFSET) =\n      rot_6d * estimator_state.covariance.eval() * rot_6d.transpose();\n\n  return true;\n}\n\nbool RosRobotLocalizationListener::getState(const ros::Time& ros_time, const std::string& frame_id,\n                                            Eigen::VectorXd& state, Eigen::MatrixXd& covariance,\n                                            const std::string& world_frame_id) const\n{\n  double time;\n  if ( ros_time.isZero() )\n  {\n    ROS_INFO(\"Ros Robot Localization Listener: State requested at time = zero, returning state at current time\");\n    time = ros::Time::now().toSec();\n  }\n  else\n  {\n    time = ros_time.toSec();\n  }\n\n  return getState(time, frame_id, state, covariance, world_frame_id);\n}\n\nconst std::string& RosRobotLocalizationListener::getBaseFrameId() const\n{\n  return base_frame_id_;\n}\n\nconst std::string& RosRobotLocalizationListener::getWorldFrameId() const\n{\n  return world_frame_id_;\n}\n\n}  // namespace RobotLocalization\n\n"
  },
  {
    "path": "src/robot_localization/src/ukf.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ukf.h\"\n#include \"robot_localization/filter_common.h\"\n\n#include <XmlRpcException.h>\n\n#include <sstream>\n#include <iomanip>\n#include <limits>\n\n#include <Eigen/Cholesky>\n\n#include <iostream>\n#include <vector>\n\n#include <assert.h>\n\nnamespace RobotLocalization\n{\n  Ukf::Ukf(std::vector<double> args) :\n    FilterBase(),  // Must initialize filter base!\n    uncorrected_(true)\n  {\n    assert(args.size() == 3);\n\n    double alpha = args[0];\n    double kappa = args[1];\n    double beta = args[2];\n\n    size_t sigmaCount = (STATE_SIZE << 1) + 1;\n    sigmaPoints_.resize(sigmaCount, Eigen::VectorXd(STATE_SIZE));\n\n    // Prepare constants\n    lambda_ = alpha * alpha * (STATE_SIZE + kappa) - STATE_SIZE;\n\n    stateWeights_.resize(sigmaCount);\n    covarWeights_.resize(sigmaCount);\n\n    stateWeights_[0] = lambda_ / (STATE_SIZE + lambda_);\n    covarWeights_[0] = stateWeights_[0] + (1 - (alpha * alpha) + beta);\n    sigmaPoints_[0].setZero();\n    for (size_t i = 1; i < sigmaCount; ++i)\n    {\n      sigmaPoints_[i].setZero();\n      stateWeights_[i] =  1 / (2 * (STATE_SIZE + lambda_));\n      covarWeights_[i] = stateWeights_[i];\n    }\n  }\n\n  Ukf::~Ukf()\n  {\n  }\n\n  void Ukf::correct(const Measurement &measurement)\n  {\n    FB_DEBUG(\"---------------------- Ukf::correct ----------------------\\n\" <<\n             \"State is:\\n\" << state_ <<\n             \"\\nMeasurement is:\\n\" << measurement.measurement_ <<\n             \"\\nMeasurement covariance is:\\n\" << measurement.covariance_ << \"\\n\");\n\n    // In our implementation, it may be that after we call predict once, we call correct\n    // several times in succession (multiple measurements with different time stamps). In\n    // that event, the sigma points need to be updated to reflect the current state.\n    // Throughout prediction and correction, we attempt to maximize efficiency in Eigen.\n    if (!uncorrected_)\n    {\n      // Take the square root of a small fraction of the estimateErrorCovariance_ using LL' decomposition\n      weightedCovarSqrt_ = ((STATE_SIZE + lambda_) * estimateErrorCovariance_).llt().matrixL();\n\n      // Compute sigma points\n\n      // First sigma point is the current state\n      sigmaPoints_[0] = state_;\n\n      // Next STATE_SIZE sigma points are state + weightedCovarSqrt_[ith column]\n      // STATE_SIZE sigma points after that are state - weightedCovarSqrt_[ith column]\n      for (size_t sigmaInd = 0; sigmaInd < STATE_SIZE; ++sigmaInd)\n      {\n        sigmaPoints_[sigmaInd + 1] = state_ + weightedCovarSqrt_.col(sigmaInd);\n        sigmaPoints_[sigmaInd + 1 + STATE_SIZE] = state_ - weightedCovarSqrt_.col(sigmaInd);\n      }\n    }\n\n    // We don't want to update everything, so we need to build matrices that only update\n    // the measured parts of our state vector\n\n    // First, determine how many state vector values we're updating\n    std::vector<size_t> updateIndices;\n    for (size_t i = 0; i < measurement.updateVector_.size(); ++i)\n    {\n      if (measurement.updateVector_[i])\n      {\n        // Handle nan and inf values in measurements\n        if (std::isnan(measurement.measurement_(i)))\n        {\n          FB_DEBUG(\"Value at index \" << i << \" was nan. Excluding from update.\\n\");\n        }\n        else if (std::isinf(measurement.measurement_(i)))\n        {\n          FB_DEBUG(\"Value at index \" << i << \" was inf. Excluding from update.\\n\");\n        }\n        else\n        {\n          updateIndices.push_back(i);\n        }\n      }\n    }\n\n    FB_DEBUG(\"Update indices are:\\n\" << updateIndices << \"\\n\");\n\n    size_t updateSize = updateIndices.size();\n\n    // Now set up the relevant matrices\n    Eigen::VectorXd stateSubset(updateSize);                              // x (in most literature)\n    Eigen::VectorXd measurementSubset(updateSize);                        // z\n    Eigen::MatrixXd measurementCovarianceSubset(updateSize, updateSize);  // R\n    Eigen::MatrixXd stateToMeasurementSubset(updateSize, STATE_SIZE);     // H\n    Eigen::MatrixXd kalmanGainSubset(STATE_SIZE, updateSize);             // K\n    Eigen::VectorXd innovationSubset(updateSize);                         // z - Hx\n    Eigen::VectorXd predictedMeasurement(updateSize);\n    Eigen::VectorXd sigmaDiff(updateSize);\n    Eigen::MatrixXd predictedMeasCovar(updateSize, updateSize);\n    Eigen::MatrixXd crossCovar(STATE_SIZE, updateSize);\n\n    std::vector<Eigen::VectorXd> sigmaPointMeasurements(sigmaPoints_.size(), Eigen::VectorXd(updateSize));\n\n    stateSubset.setZero();\n    measurementSubset.setZero();\n    measurementCovarianceSubset.setZero();\n    stateToMeasurementSubset.setZero();\n    kalmanGainSubset.setZero();\n    innovationSubset.setZero();\n    predictedMeasurement.setZero();\n    predictedMeasCovar.setZero();\n    crossCovar.setZero();\n\n    // Now build the sub-matrices from the full-sized matrices\n    for (size_t i = 0; i < updateSize; ++i)\n    {\n      measurementSubset(i) = measurement.measurement_(updateIndices[i]);\n      stateSubset(i) = state_(updateIndices[i]);\n\n      for (size_t j = 0; j < updateSize; ++j)\n      {\n        measurementCovarianceSubset(i, j) = measurement.covariance_(updateIndices[i], updateIndices[j]);\n      }\n\n      // Handle negative (read: bad) covariances in the measurement. Rather\n      // than exclude the measurement or make up a covariance, just take\n      // the absolute value.\n      if (measurementCovarianceSubset(i, i) < 0)\n      {\n        FB_DEBUG(\"WARNING: Negative covariance for index \" << i <<\n                 \" of measurement (value is\" << measurementCovarianceSubset(i, i) <<\n                 \"). Using absolute value...\\n\");\n\n        measurementCovarianceSubset(i, i) = ::fabs(measurementCovarianceSubset(i, i));\n      }\n\n      // If the measurement variance for a given variable is very\n      // near 0 (as in e-50 or so) and the variance for that\n      // variable in the covariance matrix is also near zero, then\n      // the Kalman gain computation will blow up. Really, no\n      // measurement can be completely without error, so add a small\n      // amount in that case.\n      if (measurementCovarianceSubset(i, i) < 1e-9)\n      {\n        measurementCovarianceSubset(i, i) = 1e-9;\n\n        FB_DEBUG(\"WARNING: measurement had very small error covariance for index \" <<\n                 updateIndices[i] <<\n                 \". Adding some noise to maintain filter stability.\\n\");\n      }\n    }\n\n    // The state-to-measurement function, h, will now be a measurement_size x full_state_size\n    // matrix, with ones in the (i, i) locations of the values to be updated\n    for (size_t i = 0; i < updateSize; ++i)\n    {\n      stateToMeasurementSubset(i, updateIndices[i]) = 1;\n    }\n\n    FB_DEBUG(\"Current state subset is:\\n\" << stateSubset <<\n             \"\\nMeasurement subset is:\\n\" << measurementSubset <<\n             \"\\nMeasurement covariance subset is:\\n\" << measurementCovarianceSubset <<\n             \"\\nState-to-measurement subset is:\\n\" << stateToMeasurementSubset << \"\\n\");\n\n    // (1) Generate sigma points, use them to generate a predicted measurement\n    for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd)\n    {\n      sigmaPointMeasurements[sigmaInd] = stateToMeasurementSubset * sigmaPoints_[sigmaInd];\n      predictedMeasurement.noalias() += stateWeights_[sigmaInd] * sigmaPointMeasurements[sigmaInd];\n    }\n\n    // (2) Use the sigma point measurements and predicted measurement to compute a predicted\n    // measurement covariance matrix P_zz and a state/measurement cross-covariance matrix P_xz.\n    for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd)\n    {\n      sigmaDiff = sigmaPointMeasurements[sigmaInd] - predictedMeasurement;\n      predictedMeasCovar.noalias() += covarWeights_[sigmaInd] * (sigmaDiff * sigmaDiff.transpose());\n      crossCovar.noalias() += covarWeights_[sigmaInd] * ((sigmaPoints_[sigmaInd] - state_) * sigmaDiff.transpose());\n    }\n\n    // (3) Compute the Kalman gain, making sure to use the actual measurement covariance: K = P_xz * (P_zz + R)^-1\n    Eigen::MatrixXd invInnovCov = (predictedMeasCovar + measurementCovarianceSubset).inverse();\n    kalmanGainSubset = crossCovar * invInnovCov;\n\n    // (4) Apply the gain to the difference between the actual and predicted measurements: x = x + K(z - z_hat)\n    innovationSubset = (measurementSubset - predictedMeasurement);\n\n    // Wrap angles in the innovation\n    for (size_t i = 0; i < updateSize; ++i)\n    {\n      if (updateIndices[i] == StateMemberRoll  ||\n          updateIndices[i] == StateMemberPitch ||\n          updateIndices[i] == StateMemberYaw)\n      {\n        while (innovationSubset(i) < -PI)\n        {\n          innovationSubset(i) += TAU;\n        }\n\n        while (innovationSubset(i) > PI)\n        {\n          innovationSubset(i) -= TAU;\n        }\n      }\n    }\n\n    // (5) Check Mahalanobis distance of innovation\n    if (checkMahalanobisThreshold(innovationSubset, invInnovCov, measurement.mahalanobisThresh_))\n    {\n      state_.noalias() += kalmanGainSubset * innovationSubset;\n\n      // (6) Compute the new estimate error covariance P = P - (K * P_zz * K')\n      estimateErrorCovariance_.noalias() -= (kalmanGainSubset * predictedMeasCovar * kalmanGainSubset.transpose());\n\n      wrapStateAngles();\n\n      // Mark that we need to re-compute sigma points for successive corrections\n      uncorrected_ = false;\n\n      FB_DEBUG(\"Predicated measurement covariance is:\\n\" << predictedMeasCovar <<\n               \"\\nCross covariance is:\\n\" << crossCovar <<\n               \"\\nKalman gain subset is:\\n\" << kalmanGainSubset <<\n               \"\\nInnovation:\\n\" << innovationSubset <<\n               \"\\nCorrected full state is:\\n\" << state_ <<\n               \"\\nCorrected full estimate error covariance is:\\n\" << estimateErrorCovariance_ <<\n               \"\\n\\n---------------------- /Ukf::correct ----------------------\\n\");\n    }\n  }\n\n  void Ukf::predict(const double referenceTime, const double delta)\n  {\n    FB_DEBUG(\"---------------------- Ukf::predict ----------------------\\n\" <<\n             \"delta is \" << delta <<\n             \"\\nstate is \" << state_ << \"\\n\");\n\n    double roll = state_(StateMemberRoll);\n    double pitch = state_(StateMemberPitch);\n    double yaw = state_(StateMemberYaw);\n\n    // We'll need these trig calculations a lot.\n    double sp = ::sin(pitch);\n    double cp = ::cos(pitch);\n\n    double sr = ::sin(roll);\n    double cr = ::cos(roll);\n\n    double sy = ::sin(yaw);\n    double cy = ::cos(yaw);\n\n    prepareControl(referenceTime, delta);\n\n    // Prepare the transfer function\n    transferFunction_(StateMemberX, StateMemberVx) = cy * cp * delta;\n    transferFunction_(StateMemberX, StateMemberVy) = (cy * sp * sr - sy * cr) * delta;\n    transferFunction_(StateMemberX, StateMemberVz) = (cy * sp * cr + sy * sr) * delta;\n    transferFunction_(StateMemberX, StateMemberAx) = 0.5 * transferFunction_(StateMemberX, StateMemberVx) * delta;\n    transferFunction_(StateMemberX, StateMemberAy) = 0.5 * transferFunction_(StateMemberX, StateMemberVy) * delta;\n    transferFunction_(StateMemberX, StateMemberAz) = 0.5 * transferFunction_(StateMemberX, StateMemberVz) * delta;\n    transferFunction_(StateMemberY, StateMemberVx) = sy * cp * delta;\n    transferFunction_(StateMemberY, StateMemberVy) = (sy * sp * sr + cy * cr) * delta;\n    transferFunction_(StateMemberY, StateMemberVz) = (sy * sp * cr - cy * sr) * delta;\n    transferFunction_(StateMemberY, StateMemberAx) = 0.5 * transferFunction_(StateMemberY, StateMemberVx) * delta;\n    transferFunction_(StateMemberY, StateMemberAy) = 0.5 * transferFunction_(StateMemberY, StateMemberVy) * delta;\n    transferFunction_(StateMemberY, StateMemberAz) = 0.5 * transferFunction_(StateMemberY, StateMemberVz) * delta;\n    transferFunction_(StateMemberZ, StateMemberVx) = -sp * delta;\n    transferFunction_(StateMemberZ, StateMemberVy) = cp * sr * delta;\n    transferFunction_(StateMemberZ, StateMemberVz) = cp * cr * delta;\n    transferFunction_(StateMemberZ, StateMemberAx) = 0.5 * transferFunction_(StateMemberZ, StateMemberVx) * delta;\n    transferFunction_(StateMemberZ, StateMemberAy) = 0.5 * transferFunction_(StateMemberZ, StateMemberVy) * delta;\n    transferFunction_(StateMemberZ, StateMemberAz) = 0.5 * transferFunction_(StateMemberZ, StateMemberVz) * delta;\n    transferFunction_(StateMemberRoll, StateMemberVroll) = transferFunction_(StateMemberX, StateMemberVx);\n    transferFunction_(StateMemberRoll, StateMemberVpitch) = transferFunction_(StateMemberX, StateMemberVy);\n    transferFunction_(StateMemberRoll, StateMemberVyaw) = transferFunction_(StateMemberX, StateMemberVz);\n    transferFunction_(StateMemberPitch, StateMemberVroll) = transferFunction_(StateMemberY, StateMemberVx);\n    transferFunction_(StateMemberPitch, StateMemberVpitch) = transferFunction_(StateMemberY, StateMemberVy);\n    transferFunction_(StateMemberPitch, StateMemberVyaw) = transferFunction_(StateMemberY, StateMemberVz);\n    transferFunction_(StateMemberYaw, StateMemberVroll) = transferFunction_(StateMemberZ, StateMemberVx);\n    transferFunction_(StateMemberYaw, StateMemberVpitch) = transferFunction_(StateMemberZ, StateMemberVy);\n    transferFunction_(StateMemberYaw, StateMemberVyaw) = transferFunction_(StateMemberZ, StateMemberVz);\n    transferFunction_(StateMemberVx, StateMemberAx) = delta;\n    transferFunction_(StateMemberVy, StateMemberAy) = delta;\n    transferFunction_(StateMemberVz, StateMemberAz) = delta;\n\n    // (1) Take the square root of a small fraction of the estimateErrorCovariance_ using LL' decomposition\n    weightedCovarSqrt_ = ((STATE_SIZE + lambda_) * estimateErrorCovariance_).llt().matrixL();\n\n    // (2) Compute sigma points *and* pass them through the transfer function to save\n    // the extra loop\n\n    // First sigma point is the current state\n    sigmaPoints_[0] = transferFunction_ * state_;\n\n    // Next STATE_SIZE sigma points are state + weightedCovarSqrt_[ith column]\n    // STATE_SIZE sigma points after that are state - weightedCovarSqrt_[ith column]\n    for (size_t sigmaInd = 0; sigmaInd < STATE_SIZE; ++sigmaInd)\n    {\n      sigmaPoints_[sigmaInd + 1] = transferFunction_ * (state_ + weightedCovarSqrt_.col(sigmaInd));\n      sigmaPoints_[sigmaInd + 1 + STATE_SIZE] = transferFunction_ * (state_ - weightedCovarSqrt_.col(sigmaInd));\n    }\n\n    // (3) Sum the weighted sigma points to generate a new state prediction\n    state_.setZero();\n    for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd)\n    {\n      state_.noalias() += stateWeights_[sigmaInd] * sigmaPoints_[sigmaInd];\n    }\n\n    // (4) Now us the sigma points and the predicted state to compute a predicted covariance\n    estimateErrorCovariance_.setZero();\n    Eigen::VectorXd sigmaDiff(STATE_SIZE);\n    for (size_t sigmaInd = 0; sigmaInd < sigmaPoints_.size(); ++sigmaInd)\n    {\n      sigmaDiff = (sigmaPoints_[sigmaInd] - state_);\n      estimateErrorCovariance_.noalias() += covarWeights_[sigmaInd] * (sigmaDiff * sigmaDiff.transpose());\n    }\n\n    // (5) Not strictly in the theoretical UKF formulation, but necessary here\n    // to ensure that we actually incorporate the processNoiseCovariance_\n    Eigen::MatrixXd *processNoiseCovariance = &processNoiseCovariance_;\n\n    if (useDynamicProcessNoiseCovariance_)\n    {\n      computeDynamicProcessNoiseCovariance(state_, delta);\n      processNoiseCovariance = &dynamicProcessNoiseCovariance_;\n    }\n\n    estimateErrorCovariance_.noalias() += delta * (*processNoiseCovariance);\n\n    // Keep the angles bounded\n    wrapStateAngles();\n\n    // Mark that we can keep these sigma points\n    uncorrected_ = true;\n\n    FB_DEBUG(\"Predicted state is:\\n\" << state_ <<\n             \"\\nPredicted estimate error covariance is:\\n\" << estimateErrorCovariance_ <<\n             \"\\n\\n--------------------- /Ukf::predict ----------------------\\n\");\n  }\n\n}  // namespace RobotLocalization\n"
  },
  {
    "path": "src/robot_localization/src/ukf_localization_node.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_filter_types.h\"\n\n#include <ros/ros.h>\n\n#include <vector>\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"ukf_navigation_node\");\n  ros::NodeHandle nhLocal(\"~\");\n\n  std::vector<double> args(3, 0);\n\n  nhLocal.param(\"alpha\", args[0], 0.001);\n  nhLocal.param(\"kappa\", args[1], 0.0);\n  nhLocal.param(\"beta\", args[2], 2.0);\n\n  RobotLocalization::RosUkf ukf(args);\n\n  ukf.run();\n\n  return EXIT_SUCCESS;\n}\n"
  },
  {
    "path": "src/robot_localization/srv/GetState.srv",
    "content": "time time_stamp\nstring frame_id\n---\n# State vector: x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az\nfloat64[15] state\n\n# Covariance matrix in row-major order\nfloat64[225] covariance\n"
  },
  {
    "path": "src/robot_localization/srv/SetDatum.srv",
    "content": "geographic_msgs/GeoPose geo_pose\n---\n"
  },
  {
    "path": "src/robot_localization/srv/SetPose.srv",
    "content": "geometry_msgs/PoseWithCovarianceStamped pose\n---\n"
  },
  {
    "path": "src/robot_localization/test/record_all_stats.sh",
    "content": "#!/bin/bash\n\n./stat_recorder.sh test_ekf_localization_node_bag1.test $1/ekf1.txt\n./stat_recorder.sh test_ekf_localization_node_bag2.test $1/ekf2.txt\n./stat_recorder.sh test_ekf_localization_node_bag3.test $1/ekf3.txt\n\n./stat_recorder.sh test_ukf_localization_node_bag1.test $1/ukf1.txt\n./stat_recorder.sh test_ukf_localization_node_bag2.test $1/ukf2.txt\n./stat_recorder.sh test_ukf_localization_node_bag3.test $1/ukf3.txt\n"
  },
  {
    "path": "src/robot_localization/test/stat_recorder.sh",
    "content": "#!/bin/bash\n\nrm $2\necho \"x = [\" > $2\n\ni=\"0\"\n\nwhile [ $i -lt 30 ]\ndo\nrostest robot_localization $1 output_final_position:=true output_location:=$2\ni=$[$i+1]\nsleep 3\ndone\n\necho \"]\" >> $2\necho \"mean(x)\" >> $2\necho \"sqrt(sum((4 * std(x)).^2))\" >> $2\n\n"
  },
  {
    "path": "src/robot_localization/test/test_ekf.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_filter_types.h\"\n\n#include <gtest/gtest.h>\n\n#include <limits>\n#include <vector>\n\nusing RobotLocalization::Ekf;\nusing RobotLocalization::RosEkf;\nusing RobotLocalization::STATE_SIZE;\n\nclass RosEkfPassThrough : public RosEkf\n{\n  public:\n    RosEkfPassThrough()\n    {\n    }\n\n    Ekf &getFilter()\n    {\n      return filter_;\n    }\n};\n\nTEST(EkfTest, Measurements)\n{\n  RosEkfPassThrough ekf;\n\n  Eigen::MatrixXd initialCovar(15, 15);\n  initialCovar.setIdentity();\n  initialCovar *= 0.5;\n  ekf.getFilter().setEstimateErrorCovariance(initialCovar);\n\n  Eigen::VectorXd measurement(STATE_SIZE);\n  measurement.setIdentity();\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    measurement[i] = i * 0.01 * STATE_SIZE;\n  }\n\n  Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);\n  measurementCovariance.setIdentity();\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    measurementCovariance(i, i) = 1e-9;\n  }\n\n  std::vector<int> updateVector(STATE_SIZE, true);\n\n  // Ensure that measurements are being placed in the queue correctly\n  ros::Time time;\n  time.fromSec(1000);\n  ekf.enqueueMeasurement(\"odom0\",\n                         measurement,\n                         measurementCovariance,\n                         updateVector,\n                         std::numeric_limits<double>::max(),\n                         time);\n\n  ekf.integrateMeasurements(ros::Time(1001));\n\n  EXPECT_EQ(ekf.getFilter().getState(), measurement);\n  EXPECT_EQ(ekf.getFilter().getEstimateErrorCovariance(), measurementCovariance);\n\n  ekf.getFilter().setEstimateErrorCovariance(initialCovar);\n\n  // Now fuse another measurement and check the output.\n  // We know what the filter's state should be when\n  // this is complete, so we'll check the difference and\n  // make sure it's suitably small.\n  Eigen::VectorXd measurement2 = measurement;\n\n  measurement2 *= 2.0;\n\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    measurementCovariance(i, i) = 1e-9;\n  }\n\n  time.fromSec(1002);\n  ekf.enqueueMeasurement(\"odom0\",\n                         measurement2,\n                         measurementCovariance,\n                         updateVector,\n                         std::numeric_limits<double>::max(),\n                         time);\n\n  ekf.integrateMeasurements(ros::Time(1003));\n\n  measurement = measurement2.eval() - ekf.getFilter().getState();\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    EXPECT_LT(::fabs(measurement[i]), 0.001);\n  }\n}\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"ekf\");\n\n  testing::InitGoogleTest(&argc, argv);\n  return RUN_ALL_TESTS();\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_ekf.test",
    "content": "<!-- Launch file for ekf_test -->\n\n<launch>\n\n    <test test-name=\"test_ekf\" pkg=\"robot_localization\" type=\"test_ekf\" clear_params=\"true\" time-limit=\"100.0\" />\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ekf_localization_node_bag1.test",
    "content": "<!-- Launch file for test_ekf_localization_node_bag1 -->\n\n<!-- In this run, we ran a Clearpath Husky with a slightly broken Microstrain 3DM-GX2 IMU\n     around a parking lot. The IMU was intentionally rotated +90 degrees about the X axis,\n     then rotated (extrinsically) -90 degrees about the Z axis. -->\n\n<launch>\n    <arg name=\"output_final_position\" default=\"false\" />\n    <arg name=\"output_location\" default=\"test.txt\" />\n\n    <param name=\"/use_sim_time\" value=\"true\" />\n\n    <node pkg=\"tf2_ros\" type=\"static_transform_publisher\" name=\"bl_imu\" args=\"0 -0.3 0.52 -1.570796327 0 1.570796327 base_link imu_link\" />\n\n    <node pkg=\"rosbag\" type=\"play\" name=\"rosbagplay\" args=\"$(find robot_localization)/test/test1.bag --clock -d 5\" required=\"true\"/>\n\n    <node name=\"test_ekf_localization_node_bag1_ekf\" pkg=\"robot_localization\" type=\"ekf_localization_node\" clear_params=\"true\">\n\n      <param name=\"frequency\" value=\"30\"/>\n      <param name=\"sensor_timeout\" value=\"0.1\"/>\n      <param name=\"two_d_mode\" value=\"false\"/>\n\n      <param name=\"map_frame\" value=\"map\"/>\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n      <param name=\"world_frame\" value=\"odom\"/>\n\n      <param name=\"transform_time_offset\" value=\"0.0\"/>\n      <param name=\"transform_timeout\" value=\"0.0\"/>\n\n      <param name=\"odom0\" value=\"/husky_velocity_controller/odom\"/>\n      <param name=\"imu0\" value=\"/imu/data\"/>\n\n      <rosparam param=\"odom0_config\">[false, false, false,\n                                      false, false, false,\n                                      true,  true,  true,\n                                      false, false, false,\n                                      false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false,\n                                     true,  true,  true,\n                                     false, false, false,\n                                     true,  true,  false,\n                                     true,  true,  true]</rosparam>\n\n      <param name=\"odom0_differential\" value=\"false\"/>\n      <param name=\"imu0_differential\" value=\"false\"/>\n\n      <param name=\"odom0_relative\" value=\"false\"/>\n      <param name=\"imu0_relative\" value=\"false\"/>\n\n      <param name=\"imu0_remove_gravitational_acceleration\" value=\"true\"/>\n\n      <param name=\"print_diagnostics\" value=\"true\"/>\n\n      <param name=\"odom0_queue_size\" value=\"10\"/>\n      <param name=\"imu0_queue_size\" value=\"10\"/>\n\n      <param name=\"debug\"           value=\"false\"/>\n      <param name=\"debug_out_file\"  value=\"debug_ekf_localization.txt\"/>\n\n      <rosparam param=\"process_noise_covariance\">[0.05, 0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0.05, 0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0.06, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0.03, 0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0.03, 0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0.06, 0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0.025, 0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0.025, 0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0.04, 0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0.01, 0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.01, 0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.02, 0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.01, 0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.01, 0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.015]</rosparam>\n\n      <rosparam param=\"initial_estimate_covariance\">[1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    1e-9, 0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    1e-9, 0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    1e-9, 0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    1e-9,  0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1e-9,  0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1e-9,  0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1e-9, 0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1e-9, 0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1e-9]</rosparam>\n\n    </node>\n\n    <test test-name=\"test_ekf_localization_node_bag1_pose\" pkg=\"robot_localization\" type=\"test_ekf_localization_node_bag1\" clear_params=\"true\" time-limit=\"1000.0\">\n      <param name=\"final_x\" value=\"-40.0454\"/>\n      <param name=\"final_y\" value=\"-76.9988\"/>\n      <param name=\"final_z\" value=\"-2.6974\"/>\n      <param name=\"tolerance\" value=\"1.0452\"/>\n      <param name=\"output_final_position\" value=\"$(arg output_final_position)\"/>\n      <param name=\"output_location\" value=\"$(arg output_location)\"/>\n    </test>\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ekf_localization_node_bag2.test",
    "content": "<!-- Launch file for test_ekf_localization_node_bag2 -->\n\n<launch>\n    <arg name=\"output_final_position\" default=\"false\" />\n    <arg name=\"output_location\" default=\"test.txt\" />\n\n    <param name=\"/use_sim_time\" value=\"true\" />\n\n    <node pkg=\"rosbag\" type=\"play\" name=\"rosbagplay\" args=\"$(find robot_localization)/test/test2.bag --clock -d 5\" required=\"true\"/>\n\n    <node name=\"test_ekf_localization_node_bag2_ekf\" pkg=\"robot_localization\" type=\"ekf_localization_node\" clear_params=\"true\" >\n\n      <param name=\"frequency\" value=\"50\"/>\n\n      <param name=\"sensor_timeout\" value=\"0.1\"/>\n\n      <param name=\"odom0\" value=\"/jackal_velocity_controller/odom\"/>\n      <param name=\"imu0\" value=\"/imu/data\"/>\n\n      <param name=\"map_frame\" value=\"map\"/>\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n      <param name=\"world_frame\" value=\"odom\"/>\n\n      <rosparam param=\"odom0_config\">[false, false, false,\n                                      false, false, false,\n                                      true,  true, true,\n                                      false, false, true,\n                                      false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false,\n                                     true, true, true,\n                                     false, false, false,\n                                     true, true, true,\n                                     true, true, true]</rosparam>\n\n      <param name=\"odom0_queue_size\" value=\"10\"/>\n      <param name=\"imu0_queue_size\" value=\"10\"/>\n\n      <param name=\"imu0_remove_gravitational_acceleration\" value=\"true\"/>\n\n      <rosparam param=\"process_noise_covariance\">[0.03, 0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0.03, 0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0.4, 0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0.03, 0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0.03, 0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0.06, 0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0.025, 0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0.025, 0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0.05, 0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0.002, 0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0.002, 0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0.004, 0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0.01, 0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0.01, 0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0.01]</rosparam>\n\n      <rosparam param=\"initial_estimate_covariance\">[1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    1e-9, 0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    1e-9, 0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    1e-9, 0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    1e-9,  0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1e-9,  0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1e-9,  0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1e-9, 0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1e-9, 0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1e-9]</rosparam>\n\n    </node>\n\n    <test test-name=\"test_ekf_localization_node_bag2_pose\" pkg=\"robot_localization\" type=\"test_ekf_localization_node_bag2\" clear_params=\"true\" time-limit=\"1000.0\">\n      <param name=\"final_x\" value=\"1.0206\"/>\n      <param name=\"final_y\" value=\"3.4292\"/>\n      <param name=\"final_z\" value=\"0.7419\"/>\n      <param name=\"tolerance\" value=\"0.1383\"/>\n      <param name=\"output_final_position\" value=\"$(arg output_final_position)\"/>\n      <param name=\"output_location\" value=\"$(arg output_location)\"/>\n    </test>\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ekf_localization_node_bag3.test",
    "content": "<!-- Launch file for test_ekf_localization_node_bag3_ekf\" -->\n\n<launch>\n    <arg name=\"output_final_position\" default=\"false\"/>\n    <arg name=\"output_location\" default=\"test.txt\" />\n\n    <param name=\"/use_sim_time\" value=\"true\" />\n\n    <node pkg=\"rosbag\" type=\"play\" name=\"rosbagplay\" args=\"$(find robot_localization)/test/test3.bag --clock -d 5\" required=\"true\"/>\n\n    <node name=\"test_ekf_localization_node_bag3_ekf\" pkg=\"robot_localization\" type=\"ekf_localization_node\" clear_params=\"true\">\n\n      <param name=\"frequency\" value=\"30\"/>  \n\n      <param name=\"sensor_timeout\" value=\"0.1\"/>\n\n      <param name=\"odom0\" value=\"/ardrone/odometry/raw\"/>\n      <param name=\"imu0\" value=\"/ardrone/imu\"/> \n\n      <param name=\"map_frame\" value=\"map\"/>\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n      <param name=\"world_frame\" value=\"odom\"/>\n\n      <rosparam param=\"odom0_config\">[false, false, true,\n                                     false, false, false,\n                                     true,  true, false,\n                                     false, false, true,\n                                     false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false,\n                                     true, true, true,\n                                     false, false, false,\n                                     true, true, true,\n                                     false, false, false]</rosparam>\n\n      <param name=\"odom0_queue_size\" value=\"10\"/>\n      <param name=\"imu0_queue_size\" value=\"10\"/>\n\n      <param name=\"imu0_remove_gravitational_acceleration\" value=\"true\"/>\n\n      <rosparam param=\"process_noise_covariance\">[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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  0.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,\n                                                  0.0, 0.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,\n                                                  0.0, 0.0, 0.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]</rosparam> \n\n    </node>\n\n    <test test-name=\"test_ekf_localization_node_bag3_pose\" pkg=\"robot_localization\" type=\"test_ekf_localization_node_bag3\" clear_params=\"true\" time-limit=\"1000.0\">\n      <param name=\"final_x\" value=\"-0.4859\"/>\n      <param name=\"final_y\" value=\"-0.2412\"/>\n      <param name=\"final_z\" value=\"2.9883\"/>\n      <param name=\"tolerance\" value=\"0.1290\"/>\n      <param name=\"output_final_position\" value=\"$(arg output_final_position)\"/>\n      <param name=\"output_location\" value=\"$(arg output_location)\"/>\n    </test>\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ekf_localization_node_interfaces.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/SetPose.h\"\n\n#include <ros/ros.h>\n#include <nav_msgs/Odometry.h>\n#include <geometry_msgs/PoseWithCovarianceStamped.h>\n#include <geometry_msgs/TwistWithCovarianceStamped.h>\n#include <sensor_msgs/Imu.h>\n\n#include <gtest/gtest.h>\n#include <iostream>\n\n#include <tf2/LinearMath/Quaternion.h>\n#include <tf2_geometry_msgs/tf2_geometry_msgs.h>\n\nnav_msgs::Odometry filtered_;\n\nbool stateUpdated_;\n\nvoid resetFilter()\n{\n  ros::NodeHandle nh;\n  ros::ServiceClient client = nh.serviceClient<robot_localization::SetPose>(\"/set_pose\");\n\n  robot_localization::SetPose setPose;\n  setPose.request.pose.pose.pose.orientation.w = 1;\n  setPose.request.pose.header.frame_id = \"odom\";\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    setPose.request.pose.pose.covariance[ind] = 1e-6;\n  }\n\n  setPose.request.pose.header.stamp = ros::Time::now();\n  client.call(setPose);\n  setPose.request.pose.header.seq++;\n  ros::spinOnce();\n  ros::Duration(0.01).sleep();\n  stateUpdated_ = false;\n\n  double deltaX = 0.0;\n  double deltaY = 0.0;\n  double deltaZ = 0.0;\n\n  while (!stateUpdated_ || ::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ) > 0.1)\n  {\n    ros::spinOnce();\n    ros::Duration(0.01).sleep();\n\n    deltaX = filtered_.pose.pose.position.x - setPose.request.pose.pose.pose.position.x;\n    deltaY = filtered_.pose.pose.position.y - setPose.request.pose.pose.pose.position.y;\n    deltaZ = filtered_.pose.pose.position.z - setPose.request.pose.pose.pose.position.z;\n  }\n\n  EXPECT_LT(::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ), 0.1);\n}\n\nvoid filterCallback(const nav_msgs::OdometryConstPtr &msg)\n{\n  filtered_ = *msg;\n  stateUpdated_ = true;\n}\n\nTEST(InterfacesTest, OdomPoseBasicIO)\n{\n  stateUpdated_ = false;\n\n  ros::NodeHandle nh;\n  ros::Publisher odomPub = nh.advertise<nav_msgs::Odometry>(\"/odom_input0\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  nav_msgs::Odometry odom;\n  odom.pose.pose.position.x = 20.0;\n  odom.pose.pose.position.y = 10.0;\n  odom.pose.pose.position.z = -40.0;\n\n  odom.pose.covariance[0] = 2.0;\n  odom.pose.covariance[7] = 2.0;\n  odom.pose.covariance[14] = 2.0;\n\n  odom.header.frame_id = \"odom\";\n  odom.child_frame_id = \"base_link\";\n\n  ros::Rate loopRate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n\n  // Now check the values from the callback\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - odom.pose.pose.position.x), 0.01);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01);  // Configuration for this variable for this sensor is false\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - odom.pose.pose.position.z), 0.01);\n\n  EXPECT_LT(filtered_.pose.covariance[0], 0.5);\n  EXPECT_LT(filtered_.pose.covariance[7], 0.25);  // Configuration for this variable for this sensor is false\n  EXPECT_LT(filtered_.pose.covariance[14], 0.5);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, OdomTwistBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher odomPub = nh.advertise<nav_msgs::Odometry>(\"/odom_input2\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  nav_msgs::Odometry odom;\n  odom.twist.twist.linear.x = 5.0;\n  odom.twist.twist.linear.y = 0.0;\n  odom.twist.twist.linear.z = 0.0;\n  odom.twist.twist.angular.x = 0.0;\n  odom.twist.twist.angular.y = 0.0;\n  odom.twist.twist.angular.z = 0.0;\n\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    odom.twist.covariance[ind] = 1e-6;\n  }\n\n  odom.header.frame_id = \"odom\";\n  odom.child_frame_id = \"base_link\";\n\n  ros::Rate loopRate(20);\n  for (size_t i = 0; i < 400; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0);\n\n  resetFilter();\n\n  odom.twist.twist.linear.x = 0.0;\n  odom.twist.twist.linear.y = 5.0;\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 200; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - odom.twist.twist.linear.y), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0);\n\n  resetFilter();\n\n  odom.twist.twist.linear.y = 0.0;\n  odom.twist.twist.linear.z = 5.0;\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - odom.twist.twist.linear.z), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0);\n\n  resetFilter();\n\n  odom.twist.twist.linear.z = 0.0;\n  odom.twist.twist.linear.x = 1.0;\n  odom.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05);\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - odom.twist.twist.angular.z), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5);\n\n  resetFilter();\n\n  odom.twist.twist.linear.x = 0.0;\n  odom.twist.twist.angular.z = 0.0;\n  odom.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05);\n\n  // First, roll the vehicle on its side\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  odom.twist.twist.angular.x = 0.0;\n  odom.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05);\n\n  // Now, pitch it down (positive pitch velocity in vehicle frame)\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  odom.twist.twist.angular.y = 0.0;\n  odom.twist.twist.linear.x = 3.0;\n\n  // We should now be on our side and facing -Y. Move forward in\n  // the vehicle frame X direction, and make sure Y decreases in\n  // the world frame.\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, PoseBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher posePub = nh.advertise<geometry_msgs::PoseWithCovarianceStamped>(\"/pose_input0\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  geometry_msgs::PoseWithCovarianceStamped pose;\n  pose.pose.pose.position.x = 20.0;\n  pose.pose.pose.position.y = 10.0;\n  pose.pose.pose.position.z = -40.0;\n  pose.pose.pose.orientation.x = 0;\n  pose.pose.pose.orientation.y = 0;\n  pose.pose.pose.orientation.z = 0;\n  pose.pose.pose.orientation.w = 1;\n\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    pose.pose.covariance[ind] = 1e-6;\n  }\n\n  pose.header.frame_id = \"odom\";\n\n  ros::Rate loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    pose.header.stamp = ros::Time::now();\n    posePub.publish(pose);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    pose.header.seq++;\n  }\n\n  // Now check the values from the callback\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - pose.pose.pose.position.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.1);  // Configuration for this variable for this sensor is false\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - pose.pose.pose.position.z), 0.1);\n\n  EXPECT_LT(filtered_.pose.covariance[0], 0.5);\n  EXPECT_LT(filtered_.pose.covariance[7], 0.25);  // Configuration for this variable for this sensor is false\n  EXPECT_LT(filtered_.pose.covariance[14], 0.5);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, TwistBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher twistPub = nh.advertise<geometry_msgs::TwistWithCovarianceStamped>(\"/twist_input0\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  geometry_msgs::TwistWithCovarianceStamped twist;\n  twist.twist.twist.linear.x = 5.0;\n  twist.twist.twist.linear.y = 0;\n  twist.twist.twist.linear.z = 0;\n  twist.twist.twist.angular.x = 0;\n  twist.twist.twist.angular.y = 0;\n  twist.twist.twist.angular.z = 0;\n\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    twist.twist.covariance[ind] = 1e-6;\n  }\n\n  twist.header.frame_id = \"base_link\";\n\n  ros::Rate loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 400; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0);\n\n  resetFilter();\n\n  twist.twist.twist.linear.x = 0.0;\n  twist.twist.twist.linear.y = 5.0;\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 200; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - twist.twist.twist.linear.y), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0);\n\n  resetFilter();\n\n  twist.twist.twist.linear.y = 0.0;\n  twist.twist.twist.linear.z = 5.0;\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - twist.twist.twist.linear.z), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0);\n\n  resetFilter();\n\n  twist.twist.twist.linear.z = 0.0;\n  twist.twist.twist.linear.x = 1.0;\n  twist.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05);\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - twist.twist.twist.angular.z), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5);\n\n  resetFilter();\n\n  twist.twist.twist.linear.x = 0.0;\n  twist.twist.twist.angular.z = 0.0;\n  twist.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05);\n\n  // First, roll the vehicle on its side\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  twist.twist.twist.angular.x = 0.0;\n  twist.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05);\n\n  // Now, pitch it down (positive pitch velocity in vehicle frame)\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  twist.twist.twist.angular.y = 0.0;\n  twist.twist.twist.linear.x = 3.0;\n\n  // We should now be on our side and facing -Y. Move forward in\n  // the vehicle frame X direction, and make sure Y decreases in\n  // the world frame.\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, ImuPoseBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher imuPub = nh.advertise<sensor_msgs::Imu>(\"/imu_input0\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  sensor_msgs::Imu imu;\n  tf2::Quaternion quat;\n  quat.setRPY(M_PI/4, -M_PI/4, M_PI/2);\n  imu.orientation = tf2::toMsg(quat);\n\n  for (size_t ind = 0; ind < 9; ind+=4)\n  {\n    imu.orientation_covariance[ind] = 1e-6;\n  }\n\n  imu.header.frame_id = \"base_link\";\n\n  // Make sure the pose reset worked. Test will timeout\n  // if this fails.\n  ros::Rate loopRate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    imu.header.seq++;\n  }\n\n  // Now check the values from the callback\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  tf2::Matrix3x3 mat(quat);\n  double r, p, y;\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r - M_PI/4), 0.1);\n  EXPECT_LT(::fabs(p + M_PI/4), 0.1);\n  EXPECT_LT(::fabs(y - M_PI/2), 0.1);\n\n  EXPECT_LT(filtered_.pose.covariance[21], 0.5);\n  EXPECT_LT(filtered_.pose.covariance[28], 0.25);\n  EXPECT_LT(filtered_.pose.covariance[35], 0.5);\n\n  resetFilter();\n\n  // Test to see if the orientation data is ignored when we set the\n  // first covariance value to -1\n  sensor_msgs::Imu imuIgnore;\n  imuIgnore.orientation.x = 0.1;\n  imuIgnore.orientation.y = 0.2;\n  imuIgnore.orientation.z = 0.3;\n  imuIgnore.orientation.w = 0.4;\n  imuIgnore.orientation_covariance[0] = -1;\n\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imuIgnore.header.stamp = ros::Time::now();\n    imuPub.publish(imuIgnore);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imuIgnore.header.seq++;\n  }\n\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  mat.setRotation(quat);\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r), 1e-3);\n  EXPECT_LT(::fabs(p), 1e-3);\n  EXPECT_LT(::fabs(y), 1e-3);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, ImuTwistBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher imuPub = nh.advertise<sensor_msgs::Imu>(\"/imu_input1\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  sensor_msgs::Imu imu;\n  tf2::Quaternion quat;\n  imu.angular_velocity.x = (M_PI / 2.0);\n\n  for (size_t ind = 0; ind < 9; ind+=4)\n  {\n    imu.angular_velocity_covariance[ind] = 1e-6;\n  }\n\n  imu.header.frame_id = \"base_link\";\n\n  ros::Rate loopRate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  // Now check the values from the callback\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  tf2::Matrix3x3 mat(quat);\n  double r, p, y;\n  mat.getRPY(r, p, y);\n\n  // Tolerances may seem loose, but the initial state covariances\n  // are tiny, so the filter is sluggish to accept velocity data\n  EXPECT_LT(::fabs(r - M_PI / 2.0), 0.7);\n  EXPECT_LT(::fabs(p), 0.1);\n  EXPECT_LT(::fabs(y), 0.1);\n\n  EXPECT_LT(filtered_.twist.covariance[21], 1e-3);\n  EXPECT_LT(filtered_.pose.covariance[21], 0.1);\n\n  resetFilter();\n\n  imu.angular_velocity.x = 0.0;\n  imu.angular_velocity.y = -(M_PI / 2.0);\n\n  // Make sure the pose reset worked. Test will timeout\n  // if this fails.\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  // Now check the values from the callback\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  mat.setRotation(quat);\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r), 0.1);\n  EXPECT_LT(::fabs(p + M_PI / 2.0), 0.7);\n  EXPECT_LT(::fabs(y), 0.1);\n\n  EXPECT_LT(filtered_.twist.covariance[28], 1e-3);\n  EXPECT_LT(filtered_.pose.covariance[28], 0.1);\n\n  resetFilter();\n\n  imu.angular_velocity.y = 0;\n  imu.angular_velocity.z = M_PI / 4.0;\n\n  // Make sure the pose reset worked. Test will timeout\n  // if this fails.\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  // Now check the values from the callback\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  mat.setRotation(quat);\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r), 0.1);\n  EXPECT_LT(::fabs(p), 0.1);\n  EXPECT_LT(::fabs(y - M_PI / 4.0), 0.7);\n\n  EXPECT_LT(filtered_.twist.covariance[35], 1e-3);\n  EXPECT_LT(filtered_.pose.covariance[35], 0.1);\n\n  resetFilter();\n\n  // Test to see if the angular velocity data is ignored when we set the\n  // first covariance value to -1\n  sensor_msgs::Imu imuIgnore;\n  imuIgnore.angular_velocity.x = 100;\n  imuIgnore.angular_velocity.y = 100;\n  imuIgnore.angular_velocity.z = 100;\n  imuIgnore.angular_velocity_covariance[0] = -1;\n\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imuIgnore.header.stamp = ros::Time::now();\n    imuPub.publish(imuIgnore);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imuIgnore.header.seq++;\n  }\n\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  mat.setRotation(quat);\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r), 1e-3);\n  EXPECT_LT(::fabs(p), 1e-3);\n  EXPECT_LT(::fabs(y), 1e-3);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, ImuAccBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher imuPub = nh.advertise<sensor_msgs::Imu>(\"/imu_input2\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  sensor_msgs::Imu imu;\n  imu.header.frame_id = \"base_link\";\n  imu.linear_acceleration_covariance[0] = 1e-6;\n  imu.linear_acceleration_covariance[4] = 1e-6;\n  imu.linear_acceleration_covariance[8] = 1e-6;\n\n  imu.linear_acceleration.x = 1;\n  imu.linear_acceleration.y = -1;\n  imu.linear_acceleration.z = 1;\n\n  // Move with constant acceleration for 1 second,\n  // then check our velocity.\n  ros::Rate loopRate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - 1.0), 0.4);\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.y + 1.0), 0.4);\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - 1.0), 0.4);\n\n  imu.linear_acceleration.x = 0.0;\n  imu.linear_acceleration.y = 0.0;\n  imu.linear_acceleration.z = 0.0;\n\n  // Now move for another second, and see where we\n  // end up\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1.2), 0.4);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 1.2), 0.4);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 1.2), 0.4);\n\n  resetFilter();\n\n  // Test to see if the linear acceleration data is ignored when we set the\n  // first covariance value to -1\n  sensor_msgs::Imu imuIgnore;\n  imuIgnore.linear_acceleration.x = 1000;\n  imuIgnore.linear_acceleration.y = 1000;\n  imuIgnore.linear_acceleration.z = 1000;\n  imuIgnore.linear_acceleration_covariance[0] = -1;\n\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imuIgnore.header.stamp = ros::Time::now();\n    imuPub.publish(imuIgnore);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imuIgnore.header.seq++;\n  }\n\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 1e-3);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 1e-3);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 1e-3);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, OdomDifferentialIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher odomPub = nh.advertise<nav_msgs::Odometry>(\"/odom_input1\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  nav_msgs::Odometry odom;\n  odom.pose.pose.position.x = 20.0;\n  odom.pose.pose.position.y = 10.0;\n  odom.pose.pose.position.z = -40.0;\n\n  odom.pose.pose.orientation.w = 1;\n\n  odom.pose.covariance[0] = 2.0;\n  odom.pose.covariance[7] = 2.0;\n  odom.pose.covariance[14] = 2.0;\n  odom.pose.covariance[21] = 0.2;\n  odom.pose.covariance[28] = 0.2;\n  odom.pose.covariance[35] = 0.2;\n\n  odom.header.frame_id = \"odom\";\n  odom.child_frame_id = \"base_link\";\n\n  // No guaranteeing that the zero state\n  // we're expecting to see here isn't just\n  // a result of zeroing it out previously,\n  // so check 10 times in succession.\n  size_t zeroCount = 0;\n  while (zeroCount++ < 10)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01);\n\n    ros::Duration(0.1).sleep();\n\n    odom.header.seq++;\n  }\n\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    odom.pose.covariance[ind] = 1e-6;\n  }\n\n  // Slowly move the position, and hope that the\n  // differential position keeps up\n  ros::Rate loopRate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.pose.pose.position.x += 0.01;\n    odom.pose.pose.position.y += 0.02;\n    odom.pose.pose.position.z -= 0.03;\n\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, PoseDifferentialIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher posePub = nh.advertise<geometry_msgs::PoseWithCovarianceStamped>(\"/pose_input1\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  geometry_msgs::PoseWithCovarianceStamped pose;\n  pose.pose.pose.position.x = 20.0;\n  pose.pose.pose.position.y = 10.0;\n  pose.pose.pose.position.z = -40.0;\n\n  pose.pose.pose.orientation.w = 1;\n\n  pose.pose.covariance[0] = 2.0;\n  pose.pose.covariance[7] = 2.0;\n  pose.pose.covariance[14] = 2.0;\n  pose.pose.covariance[21] = 0.2;\n  pose.pose.covariance[28] = 0.2;\n  pose.pose.covariance[35] = 0.2;\n\n  pose.header.frame_id = \"odom\";\n\n  // No guaranteeing that the zero state\n  // we're expecting to see here isn't just\n  // a result of zeroing it out previously,\n  // so check 10 times in succession.\n  size_t zeroCount = 0;\n  while (zeroCount++ < 10)\n  {\n    pose.header.stamp = ros::Time::now();\n    posePub.publish(pose);\n    ros::spinOnce();\n\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01);\n\n    ros::Duration(0.1).sleep();\n\n    pose.header.seq++;\n  }\n\n  // ...but only if we give the measurement a tiny covariance\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    pose.pose.covariance[ind] = 1e-6;\n  }\n\n  // Issue this location repeatedly, and see if we get\n  // a final reported position of (1, 2, -3)\n  ros::Rate loopRate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    pose.pose.pose.position.x += 0.01;\n    pose.pose.pose.position.y += 0.02;\n    pose.pose.pose.position.z -= 0.03;\n\n    pose.header.stamp = ros::Time::now();\n    posePub.publish(pose);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    pose.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, ImuDifferentialIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher imu0Pub = nh.advertise<sensor_msgs::Imu>(\"/imu_input0\", 5);\n  ros::Publisher imu1Pub = nh.advertise<sensor_msgs::Imu>(\"/imu_input1\", 5);\n  ros::Publisher imuPub = nh.advertise<sensor_msgs::Imu>(\"/imu_input3\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  sensor_msgs::Imu imu;\n  imu.header.frame_id = \"base_link\";\n  tf2::Quaternion quat;\n  const double roll = M_PI/2.0;\n  const double pitch = -M_PI;\n  const double yaw = -M_PI/4.0;\n  quat.setRPY(roll, pitch, yaw);\n  imu.orientation = tf2::toMsg(quat);\n\n  imu.orientation_covariance[0] = 0.02;\n  imu.orientation_covariance[4] = 0.02;\n  imu.orientation_covariance[8] = 0.02;\n\n  imu.angular_velocity_covariance[0] = 0.02;\n  imu.angular_velocity_covariance[4] = 0.02;\n  imu.angular_velocity_covariance[8] = 0.02;\n\n  size_t setCount = 0;\n  while (setCount++ < 10)\n  {\n    imu.header.stamp = ros::Time::now();\n    imu0Pub.publish(imu);  // Use this to move the absolute orientation\n    imu1Pub.publish(imu);  // Use this to keep velocities at 0\n    ros::spinOnce();\n\n    ros::Duration(0.1).sleep();\n\n    imu.header.seq++;\n  }\n\n  size_t zeroCount = 0;\n  while (zeroCount++ < 10)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    ros::spinOnce();\n\n    ros::Duration(0.1).sleep();\n\n    imu.header.seq++;\n  }\n\n  double rollFinal = roll;\n  double pitchFinal = pitch;\n  double yawFinal = yaw;\n\n  // Move the orientation slowly, and see if we\n  // can push it to 0\n  ros::Rate loopRate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    yawFinal -= 0.01 * (3.0 * M_PI/4.0);\n\n    quat.setRPY(rollFinal, pitchFinal, yawFinal);\n\n    imu.orientation = tf2::toMsg(quat);\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    imu.header.seq++;\n  }\n  ros::spinOnce();\n\n  // Move the orientation slowly, and see if we\n  // can push it to 0\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    rollFinal += 0.01 * (M_PI/2.0);\n\n    quat.setRPY(rollFinal, pitchFinal, yawFinal);\n\n    imu.orientation = tf2::toMsg(quat);\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    imu.header.seq++;\n  }\n  ros::spinOnce();\n\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  tf2::Matrix3x3 mat(quat);\n  mat.getRPY(rollFinal, pitchFinal, yawFinal);\n  EXPECT_LT(::fabs(rollFinal), 0.2);\n  EXPECT_LT(::fabs(pitchFinal), 0.2);\n  EXPECT_LT(::fabs(yawFinal), 0.2);\n\n  resetFilter();\n}\n\nint main(int argc, char **argv)\n{\n  testing::InitGoogleTest(&argc, argv);\n\n  ros::init(argc, argv, \"ekf_navigation_node-test-interfaces\");\n  ros::Time::init();\n\n  // Give ekf_localization_node time to initialize\n  ros::Duration(2.0).sleep();\n\n  return RUN_ALL_TESTS();\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_ekf_localization_node_interfaces.test",
    "content": "<!-- Launch file for test_ekf_localization_node_interfaces-->\n\n<launch>\n\n    <node name=\"test_ekf_localization_node_interfaces_ekf\" pkg=\"robot_localization\" type=\"ekf_localization_node\" clear_params=\"true\">\n\n      <param name=\"frequency\" value=\"30\"/>  \n\n      <param name=\"sensor_timeout\" value=\"0.1\"/>  \n\n      <param name=\"odom0\" value=\"/odom_input0\"/>\n      <param name=\"odom1\" value=\"/odom_input1\"/>\n      <param name=\"odom2\" value=\"/odom_input2\"/>\n\n      <param name=\"pose0\" value=\"/pose_input0\"/>\n      <param name=\"pose1\" value=\"/pose_input1\"/>\n\n      <param name=\"twist0\" value=\"/twist_input0\"/>\n\n      <param name=\"imu0\" value=\"/imu_input0\"/>\n      <param name=\"imu1\" value=\"/imu_input1\"/>\n      <param name=\"imu2\" value=\"/imu_input2\"/>\n      <param name=\"imu3\" value=\"/imu_input3\"/>\n\n      <rosparam param=\"odom0_config\">[true, false, true, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"odom1_config\">[true, true, true, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"odom2_config\">[false, false, false, false, false, false, true, true, true, true, true, true, false, false, false]</rosparam>\n\n      <rosparam param=\"pose0_config\">[true, false, true, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"pose1_config\">[true, true, true, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n\n      <rosparam param=\"twist0_config\">[false, false, false, false, false, false, true, true, true, true, true, true, false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"imu1_config\">[false, false, false, false, false, false, false, false, false, true, true, true, false, false, false]</rosparam>\n      <rosparam param=\"imu2_config\">[false, false, false, false, false, false, false, false, false, false, false, false, true, true, true]</rosparam>\n      <rosparam param=\"imu3_config\">[false, false, false, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n\n      <param name=\"odom1_differential\" value=\"true\"/>\n      <param name=\"pose1_differential\" value=\"true\"/>\n      <param name=\"imu3_differential\" value=\"true\"/>\n\n      <param name=\"print_diagnostics\" value=\"false\"/>\n\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n\n      <rosparam param=\"process_noise_covariance\">[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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  0.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,\n                                                  0.0, 0.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,\n                                                  0.0, 0.0, 0.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]</rosparam>\n\n    </node>\n\n    <test test-name=\"test_ekf_localization_node_interfaces_int\" pkg=\"robot_localization\" type=\"test_ekf_localization_node_interfaces\" clear_params=\"true\" time-limit=\"1000.0\" />\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_filter_base.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/filter_base.h\"\n#include \"robot_localization/filter_common.h\"\n\n#include <Eigen/Dense>\n\n#include <gtest/gtest.h>\n\n#include <iostream>\n#include <queue>\n#include <string>\n\nusing RobotLocalization::STATE_SIZE;\nusing RobotLocalization::Measurement;\n\nnamespace RobotLocalization\n{\n\nclass FilterDerived : public FilterBase\n{\n  public:\n    double val;\n\n    FilterDerived() : val(0) { }\n\n    void correct(const Measurement &measurement)\n    {\n      EXPECT_EQ(val, measurement.time_);\n      EXPECT_EQ(measurement.topicName_, \"topic\");\n\n      EXPECT_EQ(measurement.updateVector_.size(), 10);\n      for (size_t i = 0; i < measurement.updateVector_.size(); ++i)\n      {\n        EXPECT_EQ(measurement.updateVector_[i], true);\n      }\n    }\n\n    void predict(const double refTime, const double delta)\n    {\n      val = delta;\n    }\n};\n\nclass FilterDerived2 : public FilterBase\n{\n  public:\n    FilterDerived2() { }\n\n    void correct(const Measurement &measurement)\n    {\n    }\n\n    void predict(const double refTime, const double delta)\n    {\n    }\n\n    void processMeasurement(const Measurement &measurement)\n    {\n      FilterBase::processMeasurement(measurement);\n    }\n};\n\n}  // namespace RobotLocalization\n\nTEST(FilterBaseTest, MeasurementStruct)\n{\n    RobotLocalization::Measurement meas1;\n    RobotLocalization::Measurement meas2;\n\n    EXPECT_EQ(meas1.topicName_, std::string(\"\"));\n    EXPECT_EQ(meas1.time_, 0);\n    EXPECT_EQ(meas2.time_, 0);\n\n    // Comparison test is true if the first\n    // argument is > the second, so should\n    // be false if they're equal.\n    EXPECT_EQ(meas1(meas1, meas2), false);\n    EXPECT_EQ(meas2(meas2, meas1), false);\n\n    meas1.time_ = 100;\n    meas2.time_ = 200;\n\n    EXPECT_EQ(meas1(meas1, meas2), false);\n    EXPECT_EQ(meas1(meas2, meas1), true);\n    EXPECT_EQ(meas2(meas1, meas2), false);\n    EXPECT_EQ(meas2(meas2, meas1), true);\n}\n\nTEST(FilterBaseTest, DerivedFilterGetSet)\n{\n    using RobotLocalization::FilterDerived;\n\n    FilterDerived derived;\n\n    // With the ostream argument as NULL,\n    // the debug flag will remain false.\n    derived.setDebug(true);\n\n    EXPECT_FALSE(derived.getDebug());\n\n    // Now set the stream and do it again\n    std::stringstream os;\n    derived.setDebug(true, &os);\n\n    EXPECT_TRUE(derived.getDebug());\n\n    // Simple get/set checks\n    double timeout = 7.4;\n    derived.setSensorTimeout(timeout);\n    EXPECT_EQ(derived.getSensorTimeout(), timeout);\n\n    double lastMeasTime = 3.83;\n    derived.setLastMeasurementTime(lastMeasTime);\n    EXPECT_EQ(derived.getLastMeasurementTime(), lastMeasTime);\n\n    Eigen::MatrixXd pnCovar(STATE_SIZE, STATE_SIZE);\n    for (size_t i = 0; i < STATE_SIZE; ++i)\n    {\n      for (size_t j = 0; j < STATE_SIZE; ++j)\n      {\n        pnCovar(i, j) = static_cast<double>(i * j);\n      }\n    }\n    derived.setProcessNoiseCovariance(pnCovar);\n    EXPECT_EQ(derived.getProcessNoiseCovariance(), pnCovar);\n\n    Eigen::VectorXd state(STATE_SIZE);\n    state.setZero();\n    derived.setState(state);\n    EXPECT_EQ(derived.getState(), state);\n\n    EXPECT_EQ(derived.getInitializedStatus(), false);\n}\n\nTEST(FilterBaseTest, MeasurementProcessing)\n{\n  using RobotLocalization::FilterDerived2;\n\n  FilterDerived2 derived;\n\n  Measurement meas;\n\n  Eigen::VectorXd measurement(STATE_SIZE);\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    measurement[i] = 0.1 * static_cast<double>(i);\n  }\n\n  Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    for (size_t j = 0; j < STATE_SIZE; ++j)\n    {\n      measurementCovariance(i, j) = 0.1 * static_cast<double>(i * j);\n    }\n  }\n\n  meas.topicName_ = \"odomTest\";\n  meas.measurement_ = measurement;\n  meas.covariance_ = measurementCovariance;\n  meas.updateVector_.resize(STATE_SIZE, true);\n  meas.time_ = 1000;\n\n  // The filter shouldn't be initializedyet\n  EXPECT_FALSE(derived.getInitializedStatus());\n\n  derived.processMeasurement(meas);\n\n  // Now it's initialized, and the entire filter state\n  // should be equal to the first state\n  EXPECT_TRUE(derived.getInitializedStatus());\n  EXPECT_EQ(derived.getState(), measurement);\n\n  // Process a measurement and make sure it updates the\n  // lastMeasurementTime variable\n  meas.time_ = 1002;\n  derived.processMeasurement(meas);\n  EXPECT_EQ(derived.getLastMeasurementTime(), meas.time_);\n}\n\nint main(int argc, char **argv)\n{\n  testing::InitGoogleTest(&argc, argv);\n  return RUN_ALL_TESTS();\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_filter_base_diagnostics_timestamps.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include <ros/ros.h>\n#include <nav_msgs/Odometry.h>\n#include <geometry_msgs/PoseWithCovarianceStamped.h>\n#include <geometry_msgs/TwistWithCovarianceStamped.h>\n#include <sensor_msgs/Imu.h>\n\n#include \"robot_localization/filter_base.h\"\n#include \"robot_localization/filter_common.h\"\n#include \"robot_localization/SetPose.h\"\n\n\n#include <diagnostic_msgs/DiagnosticArray.h>\n\n#include <gtest/gtest.h>\n\n#include <vector>\n\nnamespace RobotLocalization\n{\n\n/*\n  Convenience functions to get valid messages.\n*/\n\ngeometry_msgs::PoseWithCovarianceStamped getValidPose()\n{\n  geometry_msgs::PoseWithCovarianceStamped pose_msg;\n  pose_msg.header.frame_id = \"base_link\";\n  pose_msg.pose.pose.position.x = 1;\n  pose_msg.pose.pose.orientation.w = 1;\n  for (size_t i = 0; i < 6 ; i++)\n  {\n    pose_msg.pose.covariance[i*6 + i] = 1;\n  }\n  return pose_msg;\n}\n\ngeometry_msgs::TwistWithCovarianceStamped getValidTwist()\n{\n  geometry_msgs::TwistWithCovarianceStamped twist_msg;\n  twist_msg.header.frame_id = \"base_link\";\n  for (size_t i = 0; i < 6 ; i++)\n  {\n    twist_msg.twist.covariance[i*6 + i] = 1;\n  }\n  return twist_msg;\n}\n\n\nsensor_msgs::Imu getValidImu()\n{\n  sensor_msgs::Imu imu_msg;\n  imu_msg.header.frame_id = \"base_link\";\n  imu_msg.orientation.w = 1;\n  for (size_t i = 0; i < 3 ; i++)\n  {\n    imu_msg.orientation_covariance[i * 3 + i] = 1;\n    imu_msg.angular_velocity_covariance[i * 3 + i] = 1;\n    imu_msg.linear_acceleration_covariance[i * 3 + i] = 1;\n  }\n  return imu_msg;\n}\n\nnav_msgs::Odometry getValidOdometry()\n{\n  nav_msgs::Odometry odom_msg;\n  odom_msg.header.frame_id = \"odom\";\n  odom_msg.child_frame_id = \"base_link\";\n  odom_msg.pose = getValidPose().pose;\n  odom_msg.twist = getValidTwist().twist;\n  return odom_msg;\n}\n\n/*\n  Helper class to handle the setup and message publishing for the testcases.\n\n  It provides convenience to send valid messages with a specified timestamp.\n\n  All diagnostic messages are stored into the public diagnostics attribute.\n*/\nclass DiagnosticsHelper\n{\n private:\n  ros::Publisher odom_pub_;\n  ros::Publisher pose_pub_;\n  ros::Publisher twist_pub_;\n  ros::Publisher imu_pub_;\n\n  geometry_msgs::PoseWithCovarianceStamped pose_msg_;\n  geometry_msgs::TwistWithCovarianceStamped twist_msg_;\n  nav_msgs::Odometry odom_msg_;\n  sensor_msgs::Imu imu_msg_;\n\n  ros::Subscriber diagnostic_sub_;\n  ros::ServiceClient set_pose_;\n\n public:\n  std::vector< diagnostic_msgs::DiagnosticArray > diagnostics;\n\n  DiagnosticsHelper()\n  {\n    ros::NodeHandle nh;\n    ros::NodeHandle nhLocal(\"~\");\n\n    // ready the valid messages.\n    pose_msg_ = getValidPose();\n    twist_msg_ = getValidTwist();\n    odom_msg_ = getValidOdometry();\n    imu_msg_ = getValidImu();\n\n    // subscribe to diagnostics and create publishers for the odometry messages.\n    odom_pub_ = nh.advertise<nav_msgs::Odometry>(\"example/odom\", 10);\n    pose_pub_ = nh.advertise<geometry_msgs::PoseWithCovarianceStamped>(\"example/pose\", 10);\n    twist_pub_ = nh.advertise<geometry_msgs::TwistWithCovarianceStamped>(\"example/twist\", 10);\n    imu_pub_ = nh.advertise<sensor_msgs::Imu>(\"example/imu/data\", 10);\n\n    diagnostic_sub_ = nh.subscribe(\"/diagnostics\", 10, &DiagnosticsHelper::diagnosticCallback, this);\n    set_pose_ = nh.serviceClient<robot_localization::SetPose>(\"/set_pose\");\n  }\n\n  void diagnosticCallback(const diagnostic_msgs::DiagnosticArrayPtr &msg)\n  {\n    diagnostics.push_back(*msg);\n  }\n\n  void publishMessages(ros::Time t)\n  {\n    odom_msg_.header.stamp = t;\n    odom_msg_.header.seq++;\n    odom_pub_.publish(odom_msg_);\n\n    pose_msg_.header.stamp = t;\n    pose_msg_.header.seq++;\n    pose_pub_.publish(pose_msg_);\n\n    twist_msg_.header.stamp = t;\n    twist_msg_.header.seq++;\n    twist_pub_.publish(twist_msg_);\n\n    imu_msg_.header.stamp = t;\n    imu_msg_.header.seq++;\n    imu_pub_.publish(imu_msg_);\n  }\n\n  void setPose(ros::Time t)\n  {\n    robot_localization::SetPose pose_;\n    pose_.request.pose = getValidPose();\n    pose_.request.pose.header.stamp = t;\n    set_pose_.call(pose_);\n  }\n};\n\n}  // namespace RobotLocalization\n\n/*\n  First test; we run for a bit; then send messagse with an empty timestamp.\n  Then we check if the diagnostics showed a warning.\n*/\nTEST(FilterBaseDiagnosticsTest, EmptyTimestamps)\n{\n  RobotLocalization::DiagnosticsHelper dh_;\n\n  // keep track of which diagnostic messages are detected.\n  bool received_warning_imu = false;\n  bool received_warning_odom = false;\n  bool received_warning_twist = false;\n  bool received_warning_pose = false;\n\n  // For about a second, send correct messages.\n  ros::Rate loopRate(10);\n  for (size_t i = 0; i < 10; ++i)\n  {\n    ros::spinOnce();\n    dh_.publishMessages(ros::Time::now());\n    loopRate.sleep();\n  }\n\n  ros::spinOnce();\n\n  // create an empty timestamp and send all messages with this empty timestamp.\n  ros::Time empty;\n  empty.fromSec(0);\n\n  dh_.publishMessages(empty);\n\n  ros::spinOnce();\n\n  // The filter runs and sends the diagnostics every second.\n  // Just run this for two seconds to ensure we get all the diagnostic message.\n  for (size_t i = 0; i < 20; ++i)\n  {\n    ros::spinOnce();\n    loopRate.sleep();\n  }\n\n  /*\n    Now the diagnostic messages have to be investigated to see whether they contain our warning.\n  */\n  for (size_t i=0; i < dh_.diagnostics.size(); i++)\n  {\n    for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++)\n    {\n      for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++)\n      {\n        diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key];\n        // Now the keys can be checked to see whether we found our warning.\n\n        if (kv.key == \"imu0_timestamp\")\n        {\n          received_warning_imu = true;\n        }\n        if (kv.key == \"odom0_timestamp\")\n        {\n          received_warning_odom = true;\n        }\n        if (kv.key == \"twist0_timestamp\")\n        {\n          received_warning_twist = true;\n        }\n        if (kv.key == \"pose0_timestamp\")\n        {\n          received_warning_pose = true;\n        }\n      }\n    }\n  }\n  EXPECT_TRUE(received_warning_imu);\n  EXPECT_TRUE(received_warning_odom);\n  EXPECT_TRUE(received_warning_twist);\n  EXPECT_TRUE(received_warning_pose);\n}\n\nTEST(FilterBaseDiagnosticsTest, TimestampsBeforeSetPose)\n{\n  RobotLocalization::DiagnosticsHelper dh_;\n\n  // keep track of which diagnostic messages are detected.\n  bool received_warning_imu = false;\n  bool received_warning_odom = false;\n  bool received_warning_twist = false;\n  bool received_warning_pose = false;\n\n  // For about a second, send correct messages.\n  ros::Rate loopRate(10);\n  for (size_t i = 0; i < 10; ++i)\n  {\n    ros::spinOnce();\n    dh_.publishMessages(ros::Time::now());\n    loopRate.sleep();\n  }\n  ros::spinOnce();\n\n  // Set the pose to the current timestamp.\n  dh_.setPose(ros::Time::now());\n  ros::spinOnce();\n\n  // send messages from one second before that pose reset.\n  dh_.publishMessages(ros::Time::now() - ros::Duration(1));\n\n  // The filter runs and sends the diagnostics every second.\n  // Just run this for two seconds to ensure we get all the diagnostic message.\n  for (size_t i = 0; i < 20; ++i)\n  {\n    ros::spinOnce();\n    loopRate.sleep();\n  }\n\n  /*\n    Now the diagnostic messages have to be investigated to see whether they contain our warning.\n  */\n  for (size_t i=0; i < dh_.diagnostics.size(); i++)\n  {\n    for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++)\n    {\n      for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++)\n      {\n        diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key];\n        // Now the keys can be checked to see whether we found our warning.\n\n        if (kv.key == \"imu0_timestamp\")\n        {\n          received_warning_imu = true;\n        }\n        if (kv.key == \"odom0_timestamp\")\n        {\n          received_warning_odom = true;\n        }\n        if (kv.key == \"twist0_timestamp\")\n        {\n          received_warning_twist = true;\n        }\n        if (kv.key == \"pose0_timestamp\")\n        {\n          received_warning_pose = true;\n        }\n      }\n    }\n  }\n  EXPECT_TRUE(received_warning_imu);\n  EXPECT_TRUE(received_warning_odom);\n  EXPECT_TRUE(received_warning_twist);\n  EXPECT_TRUE(received_warning_pose);\n}\n\nTEST(FilterBaseDiagnosticsTest, TimestampsBeforePrevious)\n{\n  RobotLocalization::DiagnosticsHelper dh_;\n\n  // keep track of which diagnostic messages are detected.\n  // we have more things to check here because the messages get split over\n  // various callbacks if they pass the check if they predate the set_pose time.\n  bool received_warning_imu_accel = false;\n  bool received_warning_imu_pose = false;\n  bool received_warning_imu_twist = false;\n  bool received_warning_odom_twist = false;\n  bool received_warning_twist = false;\n  bool received_warning_pose = false;\n\n  // For two seconds send correct messages.\n  ros::Rate loopRate(10);\n  for (size_t i = 0; i < 20; ++i)\n  {\n    ros::spinOnce();\n    dh_.publishMessages(ros::Time::now());\n    loopRate.sleep();\n  }\n  ros::spinOnce();\n\n  // Send message that is one second in the past.\n  dh_.publishMessages(ros::Time::now() - ros::Duration(1));\n\n  // The filter runs and sends the diagnostics every second.\n  // Just run this for two seconds to ensure we get all the diagnostic message.\n  for (size_t i = 0; i < 20; ++i)\n  {\n    ros::spinOnce();\n    loopRate.sleep();\n  }\n\n  /*\n    Now the diagnostic messages have to be investigated to see whether they contain our warning.\n  */\n  for (size_t i=0; i < dh_.diagnostics.size(); i++)\n  {\n    for (size_t status_index=0; status_index < dh_.diagnostics[i].status.size(); status_index++)\n    {\n      for (size_t key=0; key < dh_.diagnostics[i].status[status_index].values.size(); key++)\n      {\n        diagnostic_msgs::KeyValue kv = dh_.diagnostics[i].status[status_index].values[key];\n        // Now the keys can be checked to see whether we found our warning.\n\n        if (kv.key == \"imu0_acceleration_timestamp\")\n        {\n          received_warning_imu_accel = true;\n        }\n        if (kv.key == \"imu0_pose_timestamp\")\n        {\n          received_warning_imu_pose = true;\n        }\n        if (kv.key == \"imu0_twist_timestamp\")\n        {\n          received_warning_imu_twist = true;\n        }\n\n        if (kv.key == \"odom0_twist_timestamp\")\n        {\n          received_warning_twist = true;\n        }\n\n        if (kv.key == \"pose0_timestamp\")\n        {\n          received_warning_pose = true;\n        }\n        if (kv.key == \"twist0_timestamp\")\n        {\n          received_warning_odom_twist = true;\n        }\n      }\n    }\n  }\n\n  EXPECT_TRUE(received_warning_imu_accel);\n  EXPECT_TRUE(received_warning_imu_pose);\n  EXPECT_TRUE(received_warning_imu_twist);\n  EXPECT_TRUE(received_warning_odom_twist);\n  EXPECT_TRUE(received_warning_pose);\n  EXPECT_TRUE(received_warning_twist);\n}\n\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"filter_base_diagnostics_timestamps-test-interfaces\");\n  ros::Time::init();\n\n  // Give ekf_localization_node time to initialize\n  ros::Duration(2.0).sleep();\n\n  testing::InitGoogleTest(&argc, argv);\n  return RUN_ALL_TESTS();\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_filter_base_diagnostics_timestamps.test",
    "content": "<!-- Launch file for test_filter_base_diagnostics -->\n\n<launch>\n    <!-- \n        Although we test the filter base we need a valid node running which sends the diagnostic messages.\n    -->\n    <node pkg=\"robot_localization\" type=\"ekf_localization_node\" name=\"ekf_localization\" clear_params=\"true\">\n        \n        <param name=\"odom0\" value=\"example/odom\"/>\n        <param name=\"pose0\" value=\"example/pose\"/>\n        <param name=\"twist0\" value=\"example/twist\"/>\n        <param name=\"imu0\" value=\"example/imu/data\"/>\n\n        <rosparam param=\"odom0_config\">[false, false, false,\n                                        false, false, false,\n                                        true,  false, false,\n                                        false, false, false,\n                                        false, false, false]</rosparam>\n\n        <rosparam param=\"pose0_config\">[true,  true,  false,\n                                        false, false, false,\n                                        false, false, false,\n                                        false, false, false,\n                                        false, false, false]</rosparam>\n\n        <rosparam param=\"twist0_config\">[false, false, false,\n                                         false, false, false,\n                                         true,  true,  true,\n                                         true,  true,  true,\n                                         false, false, false]</rosparam>\n\n        <rosparam param=\"imu0_config\">[false, false, false,\n                                       true,  true,  true,\n                                       false, false, false,\n                                       true,  true,  true,\n                                       true,  true,  true]</rosparam>\n\n        <param name=\"print_diagnostics\" value=\"true\"/>\n\n\n    </node>\n    <test test-name=\"test_filter_base_diagnostics\" pkg=\"robot_localization\" type=\"test_filter_base_diagnostics_timestamps\" clear_params=\"true\" time-limit=\"100.0\" />\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_localization_node_bag_pose_tester.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include <ros/ros.h>\n#include <nav_msgs/Odometry.h>\n\n#include <gtest/gtest.h>\n\n#include <fstream>\n#include <iostream>\n#include <string>\n\nnav_msgs::Odometry filtered_;\n\nvoid filterCallback(const nav_msgs::OdometryConstPtr &msg)\n{\n  filtered_ = *msg;\n}\n\nTEST(BagTest, PoseCheck)\n{\n  ros::NodeHandle nh;\n  ros::NodeHandle nhLocal(\"~\");\n\n  double finalX = 0;\n  double finalY = 0;\n  double finalZ = 0;\n  double tolerance = 0;\n  bool outputFinalPosition = false;\n  std::string finalPositionFile;\n\n  nhLocal.getParam(\"final_x\", finalX);\n  nhLocal.getParam(\"final_y\", finalY);\n  nhLocal.getParam(\"final_z\", finalZ);\n  nhLocal.getParam(\"tolerance\", tolerance);\n  nhLocal.param(\"output_final_position\", outputFinalPosition, false);\n  nhLocal.param(\"output_location\", finalPositionFile, std::string(\"test.txt\"));\n\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  while (ros::ok())\n  {\n    ros::spinOnce();\n    ros::Duration(0.0333333).sleep();\n  }\n\n  if (outputFinalPosition)\n  {\n    try\n    {\n      std::ofstream posOut;\n      posOut.open(finalPositionFile.c_str(), std::ofstream::app);\n      posOut << filtered_.pose.pose.position.x << \" \" << filtered_.pose.pose.position.y << \" \" <<\n                filtered_.pose.pose.position.z << std::endl;\n      posOut.close();\n    }\n    catch(...)\n    {\n      ROS_ERROR_STREAM(\"Unable to open output file.\\n\");\n    }\n  }\n\n  double xDiff = filtered_.pose.pose.position.x - finalX;\n  double yDiff = filtered_.pose.pose.position.y - finalY;\n  double zDiff = filtered_.pose.pose.position.z - finalZ;\n\n  EXPECT_LT(::sqrt(xDiff*xDiff + yDiff*yDiff + zDiff*zDiff), tolerance);\n}\n\nint main(int argc, char **argv)\n{\n  testing::InitGoogleTest(&argc, argv);\n\n  ros::init(argc, argv, \"localization_node-bag-pose-tester\");\n  ros::Time::init();\n\n  // Give ekf_localization_node time to initialize\n  ros::Duration(2.0).sleep();\n\n  return RUN_ALL_TESTS();\n}\n\n"
  },
  {
    "path": "src/robot_localization/test/test_robot_localization_estimator.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/robot_localization_estimator.h\"\n\n#include <vector>\n#include <ros/ros.h>\n\n#include <gtest/gtest.h>\n\nTEST(RLETest, StateBuffer)\n{\n  // Generate a few estimator states\n  std::vector<RobotLocalization::EstimatorState> states;\n\n  for ( int i = 0; i < 10; i++ )\n  {\n    /*\n     * t = i s;\n     * x = i m;\n     * vx = 1.0 m/s;\n     */\n    RobotLocalization::EstimatorState state;\n    state.time_stamp = i;\n    state.state(RobotLocalization::StateMemberX) = i;\n    state.state(RobotLocalization::StateMemberY) = 0;\n    state.state(RobotLocalization::StateMemberZ) = 0;\n\n    state.state(RobotLocalization::StateMemberRoll) = 0;\n    state.state(RobotLocalization::StateMemberPitch) = 0;\n    state.state(RobotLocalization::StateMemberYaw) = 0;\n\n    state.state(RobotLocalization::StateMemberVx) = 1;\n    state.state(RobotLocalization::StateMemberVy) = 0;\n    state.state(RobotLocalization::StateMemberVz) = 0;\n\n    state.state(RobotLocalization::StateMemberVroll) = 0;\n    state.state(RobotLocalization::StateMemberVpitch) = 0;\n    state.state(RobotLocalization::StateMemberVyaw) = 0;\n\n    state.state(RobotLocalization::StateMemberAx) = 0;\n    state.state(RobotLocalization::StateMemberAy) = 0;\n    state.state(RobotLocalization::StateMemberAz) = 0;\n    states.push_back(state);\n  }\n\n  // Instantiate a robot localization estimator with a buffer capacity of 5\n  int buffer_capacity = 5;\n  Eigen::MatrixXd process_noise_covariance = Eigen::MatrixXd::Identity(RobotLocalization::STATE_SIZE,\n                                                                       RobotLocalization::STATE_SIZE);\n  RobotLocalization::RobotLocalizationEstimator estimator(buffer_capacity, RobotLocalization::FilterTypes::EKF,\n                                                          process_noise_covariance);\n\n  RobotLocalization::EstimatorState state;\n\n  // Add the states in chronological order\n  for ( int i = 0; i < 6; i++ )\n  {\n    estimator.setState(states[i]);\n\n    // Check that the state is added correctly\n    estimator.getState(states[i].time_stamp, state);\n    EXPECT_EQ(state.time_stamp, states[i].time_stamp);\n  }\n\n  // We filled the buffer with more states that it can hold, so its size should now be equal to the capacity\n  EXPECT_EQ(estimator.getSize(), buffer_capacity);\n\n  // Clear the buffer and check if it's really empty afterwards\n  estimator.clearBuffer();\n  EXPECT_EQ(estimator.getSize(), 0);\n\n  // Add states at time 1 through 3 inclusive to the buffer (buffer is not yet full)\n  for ( int i = 1; i < 4; i++ )\n  {\n    estimator.setState(states[i]);\n  }\n\n  // 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\n  // correctly added to the buffer.\n  RobotLocalization::EstimatorState state_2 = states[0];\n  state_2.state(RobotLocalization::StateMemberY) = 12;\n  estimator.setState(state_2);\n  EXPECT_EQ(RobotLocalization::EstimatorResults::Exact,\n            estimator.getState(states[0].time_stamp, state));\n\n  // Check if the state is correctly added\n  EXPECT_EQ(state.state, state_2.state);\n\n  // Add some more states. State at t=0 should now be dropped, so we should get the prediction, which means y=0\n  for ( int i = 5; i < 8; i++ )\n  {\n    estimator.setState(states[i]);\n  }\n  EXPECT_EQ(RobotLocalization::EstimatorResults::ExtrapolationIntoPast,\n            estimator.getState(states[0].time_stamp, state));\n  EXPECT_EQ(states[0].state, state.state);\n\n  // Estimate a state that is not in the buffer, but can be determined by interpolation. The predicted state vector\n  // should be equal to the designed state at the requested time.\n  EXPECT_EQ(RobotLocalization::EstimatorResults::Interpolation,\n            estimator.getState(states[4].time_stamp, state));\n  EXPECT_EQ(states[4].state, state.state);\n\n  // Estimate a state that is not in the buffer, but can be determined by extrapolation into the future. The predicted\n  // state vector should be equal to the designed state at the requested time.\n  EXPECT_EQ(RobotLocalization::EstimatorResults::ExtrapolationIntoFuture,\n            estimator.getState(states[8].time_stamp, state));\n  EXPECT_EQ(states[8].state, state.state);\n\n  // Add missing state somewhere in the middle\n  estimator.setState(states[4]);\n\n  // Overwrite state at t=3 (oldest state now in the buffer) and check if it's correctly overwritten.\n  state_2 = states[3];\n  state_2.state(RobotLocalization::StateMemberVy) = -1.0;\n  estimator.setState(state_2);\n  EXPECT_EQ(RobotLocalization::EstimatorResults::Exact,\n            estimator.getState(states[3].time_stamp, state));\n  EXPECT_EQ(state_2.state, state.state);\n\n  // Add state that came too late\n  estimator.setState(states[0]);\n\n  // Check if getState needed to do extrapolation into the past\n  EXPECT_EQ(estimator.getState(states[0].time_stamp, state),\n      RobotLocalization::EstimatorResults::ExtrapolationIntoPast);\n\n  // Check state at t=0. This can only work correctly if the state at t=3 is\n  // overwritten and the state at zero is not in the buffer.\n  EXPECT_DOUBLE_EQ(3.0, state.state(RobotLocalization::StateMemberY));\n}\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"test_robot_localization_estimator\");\n\n  testing::InitGoogleTest(&argc, argv);\n  return RUN_ALL_TESTS();\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_robot_localization_estimator.test",
    "content": "<!-- Launch file for ekf_test -->\n\n<launch>\n\n    <test test-name=\"test_rle\" pkg=\"robot_localization\" type=\"test_robot_localization_estimator\" clear_params=\"true\" time-limit=\"100.0\" />\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ros_robot_localization_listener.cpp",
    "content": "/*\n * Copyright (c) 2016, TNO IVS, Helmond\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_robot_localization_listener.h\"\n#include \"robot_localization/filter_common.h\"\n\n#include <string>\n\n#include <ros/ros.h>\n#include <tf2_ros/static_transform_broadcaster.h>\n\n#include <gtest/gtest.h>\n\nRobotLocalization::RosRobotLocalizationListener* g_listener;\n\nTEST(LocalizationListenerTest, testGetStateOfBaseLink)\n{\n  ros::spinOnce();\n\n  ros::Time time2(1001);\n\n  Eigen::VectorXd state(RobotLocalization::STATE_SIZE);\n  Eigen::MatrixXd covariance(RobotLocalization::STATE_SIZE, RobotLocalization::STATE_SIZE);\n\n  std::string base_frame(\"base_link\");\n  g_listener->getState(time2, base_frame, state, covariance);\n\n  EXPECT_DOUBLE_EQ(1.0, state(RobotLocalization::StateMemberX));\n  EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberY));\n  EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberZ));\n\n  EXPECT_FLOAT_EQ(M_PI/4, state(RobotLocalization::StateMemberRoll));\n  EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberPitch));\n  EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberYaw));\n\n  EXPECT_DOUBLE_EQ(M_PI/4.0, state(RobotLocalization::StateMemberVroll));\n  EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberVpitch));\n  EXPECT_DOUBLE_EQ(0.0, state(RobotLocalization::StateMemberVyaw));\n}\n\nTEST(LocalizationListenerTest, GetStateOfRelatedFrame)\n{\n  ros::spinOnce();\n\n  Eigen::VectorXd state(RobotLocalization::STATE_SIZE);\n  Eigen::MatrixXd covariance(RobotLocalization::STATE_SIZE, RobotLocalization::STATE_SIZE);\n\n  ros::Time time1(1000);\n  ros::Time time2(1001);\n\n  std::string sensor_frame(\"sensor\");\n\n  EXPECT_TRUE(g_listener->getState(time1, sensor_frame, state, covariance) );\n\n  EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberX));\n  EXPECT_FLOAT_EQ(1.0, state(RobotLocalization::StateMemberY));\n  EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberZ));\n\n  EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberRoll));\n  EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberPitch));\n  EXPECT_FLOAT_EQ(M_PI/2, state(RobotLocalization::StateMemberYaw));\n\n  EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVx));\n  EXPECT_FLOAT_EQ(-1.0, state(RobotLocalization::StateMemberVy));\n  EXPECT_FLOAT_EQ(M_PI/4.0, state(RobotLocalization::StateMemberVz));\n\n  EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVroll));\n  EXPECT_FLOAT_EQ(-M_PI/4.0, state(RobotLocalization::StateMemberVpitch));\n  EXPECT_FLOAT_EQ(0.0, state(RobotLocalization::StateMemberVyaw));\n\n  EXPECT_TRUE(g_listener->getState(time2, sensor_frame, state, covariance));\n\n  EXPECT_FLOAT_EQ(1.0, state(RobotLocalization::StateMemberX));\n  EXPECT_FLOAT_EQ(sqrt(2)/2.0, state(RobotLocalization::StateMemberY));\n  EXPECT_FLOAT_EQ(sqrt(2)/2.0, state(RobotLocalization::StateMemberZ));\n\n  EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberRoll));\n  EXPECT_TRUE(1e-12 > fabs(-M_PI/4.0 - state(RobotLocalization::StateMemberPitch)));\n  EXPECT_FLOAT_EQ(M_PI/2, state(RobotLocalization::StateMemberYaw));\n\n  EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVx));\n  EXPECT_FLOAT_EQ(-1.0, state(RobotLocalization::StateMemberVy));\n  EXPECT_FLOAT_EQ(M_PI/4, state(RobotLocalization::StateMemberVz));\n\n  EXPECT_TRUE(1e-12 > state(RobotLocalization::StateMemberVroll));\n  EXPECT_FLOAT_EQ(-M_PI/4.0, state(RobotLocalization::StateMemberVpitch));\n  EXPECT_FLOAT_EQ(0, state(RobotLocalization::StateMemberVyaw));\n}\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"test_robot_localization_estimator\");\n\n  g_listener = new RobotLocalization::RosRobotLocalizationListener();\n\n  testing::InitGoogleTest(&argc, argv);\n\n  int res = RUN_ALL_TESTS();\n\n  delete g_listener;\n\n  return res;\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_ros_robot_localization_listener.test",
    "content": "<!-- Launch file for ros_robot_localization_listener_test -->\n\n<launch>\n\n    <node name=\"test_estimator\" pkg=\"robot_localization\" type=\"test_ros_robot_localization_listener_publisher\" clear_params=\"true\">\n      <param name=\"frequency\" value=\"30\"/>\n\n      <param name=\"sensor_timeout\" value=\"0.1\"/>\n\n      <param name=\"odom0\" value=\"/odom_input0\"/>\n      <param name=\"odom1\" value=\"/odom_input1\"/>\n      <param name=\"odom2\" value=\"/odom_input2\"/>\n\n      <param name=\"pose0\" value=\"/pose_input0\"/>\n      <param name=\"pose1\" value=\"/pose_input1\"/>\n\n      <param name=\"twist0\" value=\"/twist_input0\"/>\n\n      <param name=\"imu0\" value=\"/imu_input0\"/>\n      <param name=\"imu1\" value=\"/imu_input1\"/>\n      <param name=\"imu2\" value=\"/imu_input2\"/>\n      <param name=\"imu3\" value=\"/imu_input3\"/>\n\n      <rosparam param=\"odom0_config\">[true, false, true, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"odom1_config\">[true, true, true, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"odom2_config\">[false, false, false, false, false, false, true, true, true, true, true, true, false, false, false]</rosparam>\n\n      <rosparam param=\"pose0_config\">[true, false, true, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"pose1_config\">[true, true, true, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n\n      <rosparam param=\"twist0_config\">[false, false, false, false, false, false, true, true, true, true, true, true, false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"imu1_config\">[false, false, false, false, false, false, false, false, false, true, true, true, false, false, false]</rosparam>\n      <rosparam param=\"imu2_config\">[false, false, false, false, false, false, false, false, false, false, false, false, true, true, true]</rosparam>\n      <rosparam param=\"imu3_config\">[false, false, false, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n\n      <param name=\"odom1_differential\" value=\"true\"/>\n      <param name=\"pose1_differential\" value=\"true\"/>\n      <param name=\"imu3_differential\" value=\"true\"/>\n\n      <param name=\"print_diagnostics\" value=\"false\"/>\n\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n\n      <rosparam param=\"process_noise_covariance\">[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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  0.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,\n                                                  0.0, 0.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,\n                                                  0.0, 0.0, 0.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]</rosparam>\n    </node>\n\n    <test test-name=\"test_ros_robot_localization_listener\" pkg=\"robot_localization\" type=\"test_ros_robot_localization_listener\" clear_params=\"true\" time-limit=\"100.0\">\n      <remap from=\"robot_localization\" to=\"test_estimator\" />\n    </test>\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ros_robot_localization_listener_publisher.cpp",
    "content": "/*\n * Copyright (c) 2016, TNO IVS, Helmond\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include <geometry_msgs/AccelWithCovarianceStamped.h>\n#include <nav_msgs/Odometry.h>\n#include <string>\n\n#include <ros/ros.h>\n#include <tf2/utils.h>\n#include <tf2_ros/static_transform_broadcaster.h>\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"test_robot_localization_listener_publisher\");\n\n  ros::NodeHandle nh;\n  ros::Publisher odom_pub = nh.advertise<nav_msgs::Odometry>(\"odometry/filtered\", 1);\n  ros::Publisher accel_pub = nh.advertise<geometry_msgs::AccelWithCovarianceStamped>(\"accel/filtered\", 1);\n  tf2_ros::StaticTransformBroadcaster transform_broadcaster;\n\n  ros::Time end_time = ros::Time::now() + ros::Duration(10);\n  while (ros::ok() && ros::Time::now() < end_time)\n  {\n    ros::Time time1(1000);\n    double x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az;\n    x = y = z = roll = pitch = yaw = vy = vz = vroll = vpitch = vyaw = ax = ay = az = 0.0;\n    vx = 1.0;\n    vroll = M_PI/4.0;\n\n    tf2::Quaternion q;\n    q.setRPY(0, 0, 0);\n\n    nav_msgs::Odometry odom_msg;\n    odom_msg.header.stamp = time1;\n    odom_msg.header.frame_id = \"map\";\n    odom_msg.child_frame_id = \"base_link\";\n    odom_msg.pose.pose.position.x = x;\n    odom_msg.pose.pose.position.y = y;\n    odom_msg.pose.pose.position.y = z;\n    odom_msg.pose.pose.orientation.x = q.x();\n    odom_msg.pose.pose.orientation.y = q.y();\n    odom_msg.pose.pose.orientation.z = q.z();\n    odom_msg.pose.pose.orientation.w = q.w();\n\n    odom_msg.twist.twist.linear.x = vx;\n    odom_msg.twist.twist.linear.y = vy;\n    odom_msg.twist.twist.linear.z = vz;\n    odom_msg.twist.twist.angular.x = vroll;\n    odom_msg.twist.twist.angular.y = vpitch;\n    odom_msg.twist.twist.angular.z = vyaw;\n\n    geometry_msgs::AccelWithCovarianceStamped accel_msg;\n    accel_msg.header.stamp = time1;\n    accel_msg.header.frame_id = \"base_link\";\n    accel_msg.accel.accel.linear.x = ax;\n    accel_msg.accel.accel.linear.y = ay;\n    accel_msg.accel.accel.linear.z = az;\n    accel_msg.accel.accel.angular.x = 0;\n    accel_msg.accel.accel.angular.y = 0;\n    accel_msg.accel.accel.angular.z = 0;\n\n    odom_pub.publish(odom_msg);\n    accel_pub.publish(accel_msg);\n\n    geometry_msgs::TransformStamped transformStamped;\n\n    transformStamped.header.stamp = ros::Time::now();\n    transformStamped.header.frame_id = \"base_link\";\n    transformStamped.child_frame_id = \"sensor\";\n    transformStamped.transform.translation.x = 0.0;\n    transformStamped.transform.translation.y = 1.0;\n    transformStamped.transform.translation.z = 0.0;\n    {\n      tf2::Quaternion q;\n      q.setRPY(0, 0, M_PI/2);\n      transformStamped.transform.rotation.x = q.x();\n      transformStamped.transform.rotation.y = q.y();\n      transformStamped.transform.rotation.z = q.z();\n      transformStamped.transform.rotation.w = q.w();\n\n      transform_broadcaster.sendTransform(transformStamped);\n    }\n\n    ros::Duration(0.1).sleep();\n  }\n\n  return 0;\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_ukf.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/ros_filter_types.h\"\n\n#include <gtest/gtest.h>\n\n#include <limits>\n#include <vector>\n\nusing RobotLocalization::Ukf;\nusing RobotLocalization::RosUkf;\nusing RobotLocalization::STATE_SIZE;\n\nclass RosUkfPassThrough : public RosUkf\n{\n  public:\n    explicit RosUkfPassThrough(std::vector<double> &args) : RosUkf(args)\n    {\n    }\n\n    Ukf &getFilter()\n    {\n      return filter_;\n    }\n};\n\nTEST(UkfTest, Measurements)\n{\n  std::vector<double> args;\n  args.push_back(0.001);\n  args.push_back(0);\n  args.push_back(2);\n\n  RosUkfPassThrough ukf(args);\n\n  Eigen::MatrixXd initialCovar(15, 15);\n  initialCovar.setIdentity();\n  initialCovar *= 0.5;\n  ukf.getFilter().setEstimateErrorCovariance(initialCovar);\n\n  EXPECT_EQ(ukf.getFilter().getEstimateErrorCovariance(), initialCovar);\n\n  Eigen::VectorXd measurement(STATE_SIZE);\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    measurement[i] = i * 0.01 * STATE_SIZE;\n  }\n\n  Eigen::MatrixXd measurementCovariance(STATE_SIZE, STATE_SIZE);\n  measurementCovariance.setIdentity();\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    measurementCovariance(i, i) = 1e-9;\n  }\n\n  std::vector<int> updateVector(STATE_SIZE, true);\n\n  // Ensure that measurements are being placed in the queue correctly\n  ros::Time time;\n  time.fromSec(1000);\n  ukf.enqueueMeasurement(\"odom0\",\n                         measurement,\n                         measurementCovariance,\n                         updateVector,\n                         std::numeric_limits<double>::max(),\n                         time);\n\n  ukf.integrateMeasurements(ros::Time(1001));\n\n  EXPECT_EQ(ukf.getFilter().getState(), measurement);\n  EXPECT_EQ(ukf.getFilter().getEstimateErrorCovariance(), measurementCovariance);\n\n  ukf.getFilter().setEstimateErrorCovariance(initialCovar);\n\n  // Now fuse another measurement and check the output.\n  // We know what the filter's state should be when\n  // this is complete, so we'll check the difference and\n  // make sure it's suitably small.\n  Eigen::VectorXd measurement2 = measurement;\n\n  measurement2 *= 2.0;\n\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    measurementCovariance(i, i) = 1e-9;\n  }\n\n  time.fromSec(1002);\n  ukf.enqueueMeasurement(\"odom0\",\n                         measurement2,\n                         measurementCovariance,\n                         updateVector,\n                         std::numeric_limits<double>::max(),\n                         time);\n\n  ukf.integrateMeasurements(ros::Time(1003));\n\n  measurement = measurement2.eval() - ukf.getFilter().getState();\n  for (size_t i = 0; i < STATE_SIZE; ++i)\n  {\n    EXPECT_LT(::fabs(measurement[i]), 0.001);\n  }\n}\n\nint main(int argc, char **argv)\n{\n  ros::init(argc, argv, \"ukf\");\n\n  testing::InitGoogleTest(&argc, argv);\n  return RUN_ALL_TESTS();\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_ukf.test",
    "content": "<!-- Launch file for test_ukf -->\n\n<launch>\n\n    <test test-name=\"test_ukf\" pkg=\"robot_localization\" type=\"test_ukf\" clear_params=\"true\" time-limit=\"100.0\" />\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ukf_localization_node_bag1.test",
    "content": "<!-- Launch file for test_ukf_localization_node_bag1 -->\n\n<!-- In this run, we ran a Clearpath Husky with a slightly broken Microstrain 3DM-GX2 IMU\n     around a parking lot. The IMU was intentionally rotated +90 degrees about the X axis,\n     then rotated (extrinsically) -90 degrees about the Z axis. The IMU did not report 0\n     when facing east, however, but when facing north. -->\n\n<launch>\n    <arg name=\"output_final_position\" default=\"false\" />\n    <arg name=\"output_location\" default=\"test.txt\" />\n\n    <param name=\"/use_sim_time\" value=\"true\" />\n\n    <node pkg=\"tf2_ros\" type=\"static_transform_publisher\" name=\"bl_imu\" args=\"0 -0.3 0.52 -1.570796327 0 1.570796327 base_link imu_link\" />\n\n    <node pkg=\"rosbag\" type=\"play\" name=\"rosbagplay\" args=\"$(find robot_localization)/test/test1.bag --clock -d 5\" required=\"true\"/>\n\n    <node name=\"test_ukf_localization_node_bag1_ukf\" pkg=\"robot_localization\" type=\"ukf_localization_node\" clear_params=\"true\">\n\n      <param name=\"frequency\" value=\"30\"/>\n      <param name=\"sensor_timeout\" value=\"0.1\"/>\n      <param name=\"two_d_mode\" value=\"false\"/>\n\n      <param name=\"map_frame\" value=\"map\"/>\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n      <param name=\"world_frame\" value=\"odom\"/>\n\n      <param name=\"transform_time_offset\" value=\"0.0\"/>\n      <param name=\"transform_timeout\" value=\"0.0\"/>\n\n      <param name=\"odom0\" value=\"/husky_velocity_controller/odom\"/>\n      <param name=\"imu0\" value=\"/imu/data\"/>\n\n      <rosparam param=\"odom0_config\">[false, false, false,\n                                      false, false, false,\n                                      true,  true,  true,\n                                      false, false, false,\n                                      false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false,\n                                     true,  true,  true,\n                                     false, false, false,\n                                     true,  true,  false,\n                                     true,  true,  true]</rosparam>\n\n      <param name=\"odom0_differential\" value=\"false\"/>\n      <param name=\"imu0_differential\" value=\"false\"/>\n\n      <param name=\"odom0_relative\" value=\"false\"/>\n      <param name=\"imu0_relative\" value=\"false\"/>\n\n      <param name=\"imu0_remove_gravitational_acceleration\" value=\"true\"/>\n\n      <param name=\"print_diagnostics\" value=\"true\"/>\n\n      <param name=\"odom0_queue_size\" value=\"10\"/>\n      <param name=\"imu0_queue_size\" value=\"10\"/>\n\n      <param name=\"debug\"           value=\"false\"/>\n      <param name=\"debug_out_file\"  value=\"debug_ukf_localization.txt\"/>\n\n      <rosparam param=\"process_noise_covariance\">[0.05, 0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0.05, 0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0.06, 0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0.03, 0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0.03, 0,    0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0.06, 0,     0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0.025, 0,     0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0.025, 0,    0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0.04, 0,    0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0.01, 0,    0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0.01, 0,    0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0.02, 0,    0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0.01, 0,    0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0.01, 0,\n                                                  0,    0,    0,    0,    0,    0,    0,     0,     0,    0,    0,    0,    0,    0,    0.015]</rosparam>\n\n      <rosparam param=\"initial_estimate_covariance\">[1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    1e-9, 0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    1e-9, 0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    1e-9, 0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    1e-9,  0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1e-9,  0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1e-9,  0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1e-9, 0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1e-9, 0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1e-9]</rosparam>\n\n      <param name=\"alpha\" value=\"0.001\"/> \n      <param name=\"kappa\" value=\"0\"/> \n      <param name=\"beta\" value=\"2\"/>\n\n    </node>\n\n    <test test-name=\"test_ukf_localization_node_bag1_pose\" pkg=\"robot_localization\" type=\"test_ukf_localization_node_bag1\" clear_params=\"true\" time-limit=\"1000.0\">\n      <param name=\"final_x\" value=\"-39.7333\"/>\n      <param name=\"final_y\" value=\"-76.9820\"/>\n      <param name=\"final_z\" value=\"-2.4427\"/>\n      <param name=\"tolerance\" value=\"1.2910\"/>\n      <param name=\"output_final_position\" value=\"$(arg output_final_position)\"/>\n      <param name=\"output_location\" value=\"$(arg output_location)\"/>\n    </test>\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ukf_localization_node_bag2.test",
    "content": "<!-- Launch file for test_ukf_localization_node_bag2 -->\n\n<launch>\n    <arg name=\"output_final_position\" default=\"false\"/>\n    <arg name=\"output_location\" default=\"test.txt\" />\n\n    <param name=\"/use_sim_time\" value=\"true\" />\n\n    <node pkg=\"rosbag\" type=\"play\" name=\"rosbagplay\" args=\"$(find robot_localization)/test/test2.bag --clock -d 5\" required=\"true\"/>\n\n    <node name=\"test_ukf_localization_node_bag2_ukf\" pkg=\"robot_localization\" type=\"ukf_localization_node\" clear_params=\"true\" >\n\n      <param name=\"frequency\" value=\"50\"/>\n\n      <param name=\"frequency\" value=\"50\"/>\n\n      <param name=\"sensor_timeout\" value=\"0.1\"/>\n\n      <param name=\"odom0\" value=\"/jackal_velocity_controller/odom\"/>\n      <param name=\"imu0\" value=\"/imu/data\"/>\n\n      <param name=\"map_frame\" value=\"map\"/>\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n      <param name=\"world_frame\" value=\"odom\"/>\n\n      <rosparam param=\"odom0_config\">[false, false, false,\n                                      false, false, false,\n                                      true,  true, true,\n                                      false, false, true,\n                                      false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false,\n                                     true, true, true,\n                                     false, false, false,\n                                     true, true, true,\n                                     true, true, true]</rosparam>\n\n      <param name=\"odom0_queue_size\" value=\"10\"/>\n      <param name=\"imu0_queue_size\" value=\"10\"/>\n\n      <param name=\"imu0_remove_gravitational_acceleration\" value=\"true\"/>\n\n      <rosparam param=\"process_noise_covariance\">[0.03, 0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0.03, 0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0.4, 0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0.03, 0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0.03, 0,    0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0.06, 0,     0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0.025, 0,     0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0.025, 0,    0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0.05, 0,     0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0.002, 0,     0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0.002, 0,     0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0.004, 0,    0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0.01, 0,    0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0.01, 0,\n                                                  0,    0,    0,   0,    0,    0,    0,     0,     0,    0,     0,     0,     0,    0,    0.01]</rosparam>\n\n      <rosparam param=\"initial_estimate_covariance\">[1e-9, 0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    1e-9, 0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    1e-9, 0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    1e-9, 0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    1e-9, 0,    0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    1e-9, 0,    0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    1e-9, 0,    0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    1e-9, 0,    0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    1e-9, 0,     0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    1e-9,  0,     0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     1e-9,  0,     0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     1e-9,  0,    0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     1e-9, 0,    0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    1e-9, 0,\n                                                     0,    0,    0,    0,    0,    0,    0,    0,    0,    0,     0,     0,     0,    0,    1e-9]</rosparam>\n\n      <param name=\"alpha\" value=\"0.001\"/> \n      <param name=\"kappa\" value=\"0\"/> \n      <param name=\"beta\" value=\"2\"/>\n\n    </node>\n\n    <test test-name=\"test_ukf_localization_node_bag2_pose\" pkg=\"robot_localization\" type=\"test_ukf_localization_node_bag2\" clear_params=\"true\" time-limit=\"1000.0\">\n      <param name=\"final_x\" value=\"1.0438\"/>\n      <param name=\"final_y\" value=\"3.4940\"/>\n      <param name=\"final_z\" value=\"0.7260\"/>\n      <param name=\"tolerance\" value=\"0.2351\"/>\n      <param name=\"output_final_position\" value=\"$(arg output_final_position)\"/>\n      <param name=\"output_location\" value=\"$(arg output_location)\"/>\n    </test>\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ukf_localization_node_bag3.test",
    "content": "<!-- Launch file for test_ukf_localization_node_bag3 -->\n\n<launch>\n    <arg name=\"output_final_position\" default=\"false\"/>\n    <arg name=\"output_location\" default=\"test.txt\" />\n\n    <param name=\"/use_sim_time\" value=\"true\" />\n\n    <node pkg=\"rosbag\" type=\"play\" name=\"rosbagplay\" args=\"$(find robot_localization)/test/test3.bag --clock -d 5\" required=\"true\"/>\n\n    <node name=\"test_ukf_localization_node_bag3_ukf\" pkg=\"robot_localization\" type=\"ukf_localization_node\" clear_params=\"true\">\n\n      <param name=\"frequency\" value=\"30\"/>  \n\n      <param name=\"sensor_timeout\" value=\"0.1\"/>\n\n      <param name=\"two_d_mode\" value=\"false\"/>\n\n      <param name=\"odom0\" value=\"/ardrone/odometry/raw\"/>\n      <param name=\"imu0\" value=\"/ardrone/imu\"/> \n\n      <param name=\"map_frame\" value=\"map\"/>\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n      <param name=\"world_frame\" value=\"odom\"/>\n\n      <rosparam param=\"odom0_config\">[false, false, true,\n                                     false, false, false,\n                                     true,  true, false,\n                                     false, false, true,\n                                     false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false,\n                                     true, true, true,\n                                     false, false, false,\n                                     true, true, true,\n                                     false, false, false]</rosparam>\n\n      <!-- Differential setting is off for this test -->\n      <param name=\"odom0_differential\" value=\"false\"/>\n      <param name=\"imu0_differential\" value=\"false\"/>\n\n      <param name=\"odom0_queue_size\" value=\"10\"/>\n      <param name=\"imu0_queue_size\" value=\"10\"/>\n\n      <param name=\"imu0_remove_gravitational_acceleration\" value=\"true\"/>\n\n      <param name=\"alpha\" value=\"0.001\"/> \n      <param name=\"kappa\" value=\"0\"/> \n      <param name=\"beta\" value=\"2\"/>\n\n      <rosparam param=\"process_noise_covariance\">[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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  0.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,\n                                                  0.0, 0.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,\n                                                  0.0, 0.0, 0.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]</rosparam> \n\n    </node>\n\n    <test test-name=\"test_ukf_localization_node_bag3_pose\" pkg=\"robot_localization\" type=\"test_ukf_localization_node_bag3\" clear_params=\"true\" time-limit=\"1000.0\">\n      <param name=\"final_x\" value=\"-0.41148\"/>\n      <param name=\"final_y\" value=\"-0.2513\"/>\n      <param name=\"final_z\" value=\"2.990\"/>\n      <param name=\"tolerance\" value=\"0.1681\"/>\n      <param name=\"output_final_position\" value=\"$(arg output_final_position)\"/>\n      <param name=\"output_location\" value=\"$(arg output_location)\"/>\n    </test>\n\n</launch>\n"
  },
  {
    "path": "src/robot_localization/test/test_ukf_localization_node_interfaces.cpp",
    "content": "/*\n * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.\n * All rights reserved.\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions\n * are met:\n *\n * 1. Redistributions of source code must retain the above copyright\n * notice, this list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above\n * copyright notice, this list of conditions and the following\n * disclaimer in the documentation and/or other materials provided\n * with the distribution.\n * 3. Neither the name of the copyright holder nor the names of its\n * contributors may be used to endorse or promote products derived\n * from this software without specific prior written permission.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n * \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n * POSSIBILITY OF SUCH DAMAGE.\n */\n\n#include \"robot_localization/SetPose.h\"\n\n#include <ros/ros.h>\n#include <nav_msgs/Odometry.h>\n#include <geometry_msgs/PoseWithCovarianceStamped.h>\n#include <geometry_msgs/TwistWithCovarianceStamped.h>\n#include <sensor_msgs/Imu.h>\n\n#include <tf2/LinearMath/Quaternion.h>\n#include <tf2_geometry_msgs/tf2_geometry_msgs.h>\n\n#include <gtest/gtest.h>\n\n#include <iostream>\n\nnav_msgs::Odometry filtered_;\n\nbool stateUpdated_;\n\nvoid resetFilter()\n{\n  ros::NodeHandle nh;\n  ros::ServiceClient client = nh.serviceClient<robot_localization::SetPose>(\"/set_pose\");\n\n  robot_localization::SetPose setPose;\n  setPose.request.pose.pose.pose.orientation.w = 1;\n  setPose.request.pose.header.frame_id = \"odom\";\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    setPose.request.pose.pose.covariance[ind] = 1e-6;\n  }\n\n  setPose.request.pose.header.stamp = ros::Time::now();\n  client.call(setPose);\n  setPose.request.pose.header.seq++;\n  ros::spinOnce();\n  ros::Duration(0.01).sleep();\n  stateUpdated_ = false;\n\n  double deltaX = 0.0;\n  double deltaY = 0.0;\n  double deltaZ = 0.0;\n\n  while (!stateUpdated_ || ::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ) > 0.1)\n  {\n    ros::spinOnce();\n    ros::Duration(0.01).sleep();\n\n    deltaX = filtered_.pose.pose.position.x - setPose.request.pose.pose.pose.position.x;\n    deltaY = filtered_.pose.pose.position.y - setPose.request.pose.pose.pose.position.y;\n    deltaZ = filtered_.pose.pose.position.z - setPose.request.pose.pose.pose.position.z;\n  }\n\n  EXPECT_LT(::sqrt(deltaX * deltaX + deltaY * deltaY + deltaZ * deltaZ), 0.1);\n}\n\nvoid filterCallback(const nav_msgs::OdometryConstPtr &msg)\n{\n  filtered_ = *msg;\n  stateUpdated_ = true;\n}\n\nTEST(InterfacesTest, OdomPoseBasicIO)\n{\n  stateUpdated_ = false;\n\n  ros::NodeHandle nh;\n  ros::Publisher odomPub = nh.advertise<nav_msgs::Odometry>(\"/odom_input0\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  nav_msgs::Odometry odom;\n  odom.pose.pose.position.x = 20.0;\n  odom.pose.pose.position.y = 10.0;\n  odom.pose.pose.position.z = -40.0;\n\n  odom.pose.covariance[0] = 2.0;\n  odom.pose.covariance[7] = 2.0;\n  odom.pose.covariance[14] = 2.0;\n\n  odom.header.frame_id = \"odom\";\n  odom.child_frame_id = \"base_link\";\n\n  ros::Rate loopRate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n\n  // Now check the values from the callback\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - odom.pose.pose.position.x), 0.01);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01);  // Configuration for this variable for this sensor is false\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - odom.pose.pose.position.z), 0.01);\n\n  EXPECT_LT(filtered_.pose.covariance[0], 0.5);\n  EXPECT_LT(filtered_.pose.covariance[7], 0.25);  // Configuration for this variable for this sensor is false\n  EXPECT_LT(filtered_.pose.covariance[14], 0.6);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, OdomTwistBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher odomPub = nh.advertise<nav_msgs::Odometry>(\"/odom_input2\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  nav_msgs::Odometry odom;\n  odom.twist.twist.linear.x = 5.0;\n  odom.twist.twist.linear.y = 0.0;\n  odom.twist.twist.linear.z = 0.0;\n  odom.twist.twist.angular.x = 0.0;\n  odom.twist.twist.angular.y = 0.0;\n  odom.twist.twist.angular.z = 0.0;\n\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    odom.twist.covariance[ind] = 1e-6;\n  }\n\n  odom.header.frame_id = \"odom\";\n  odom.child_frame_id = \"base_link\";\n\n  ros::Rate loopRate(20);\n  for (size_t i = 0; i < 400; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0);\n\n  resetFilter();\n\n  odom.twist.twist.linear.x = 0.0;\n  odom.twist.twist.linear.y = 5.0;\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 200; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - odom.twist.twist.linear.y), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0);\n\n  resetFilter();\n\n  odom.twist.twist.linear.y = 0.0;\n  odom.twist.twist.linear.z = 5.0;\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - odom.twist.twist.linear.z), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0);\n\n  resetFilter();\n\n  odom.twist.twist.linear.z = 0.0;\n  odom.twist.twist.linear.x = 1.0;\n  odom.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05);\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - odom.twist.twist.angular.z), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5);\n\n  resetFilter();\n\n  odom.twist.twist.linear.x = 0.0;\n  odom.twist.twist.angular.z = 0.0;\n  odom.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05);\n\n  // First, roll the vehicle on its side\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  odom.twist.twist.angular.x = 0.0;\n  odom.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05);\n\n  // Now, pitch it down (positive pitch velocity in vehicle frame)\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  odom.twist.twist.angular.y = 0.0;\n  odom.twist.twist.linear.x = 3.0;\n\n  // We should now be on our side and facing -Y. Move forward in\n  // the vehicle frame X direction, and make sure Y decreases in\n  // the world frame.\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - odom.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, PoseBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher posePub = nh.advertise<geometry_msgs::PoseWithCovarianceStamped>(\"/pose_input0\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  geometry_msgs::PoseWithCovarianceStamped pose;\n  pose.pose.pose.position.x = 20.0;\n  pose.pose.pose.position.y = 10.0;\n  pose.pose.pose.position.z = -40.0;\n  pose.pose.pose.orientation.x = 0;\n  pose.pose.pose.orientation.y = 0;\n  pose.pose.pose.orientation.z = 0;\n  pose.pose.pose.orientation.w = 1;\n\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    pose.pose.covariance[ind] = 1e-6;\n  }\n\n  pose.header.frame_id = \"odom\";\n\n  ros::Rate loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    pose.header.stamp = ros::Time::now();\n    posePub.publish(pose);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    pose.header.seq++;\n  }\n\n  // Now check the values from the callback\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - pose.pose.pose.position.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.1);  // Configuration for this variable for this sensor is false\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - pose.pose.pose.position.z), 0.1);\n\n  EXPECT_LT(filtered_.pose.covariance[0], 0.5);\n  EXPECT_LT(filtered_.pose.covariance[7], 0.25);  // Configuration for this variable for this sensor is false\n  EXPECT_LT(filtered_.pose.covariance[14], 0.5);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, TwistBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher twistPub = nh.advertise<geometry_msgs::TwistWithCovarianceStamped>(\"/twist_input0\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  geometry_msgs::TwistWithCovarianceStamped twist;\n  twist.twist.twist.linear.x = 5.0;\n  twist.twist.twist.linear.y = 0;\n  twist.twist.twist.linear.z = 0;\n  twist.twist.twist.angular.x = 0;\n  twist.twist.twist.angular.y = 0;\n  twist.twist.twist.angular.z = 0;\n\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    twist.twist.covariance[ind] = 1e-6;\n  }\n\n  twist.header.frame_id = \"base_link\";\n\n  ros::Rate loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 400; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 100.0), 2.0);\n\n  resetFilter();\n\n  twist.twist.twist.linear.x = 0.0;\n  twist.twist.twist.linear.y = 5.0;\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 200; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.y - twist.twist.twist.linear.y), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 50.0), 1.0);\n\n  resetFilter();\n\n  twist.twist.twist.linear.y = 0.0;\n  twist.twist.twist.linear.z = 5.0;\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - twist.twist.twist.linear.z), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 25.0), 1.0);\n\n  resetFilter();\n\n  twist.twist.twist.linear.z = 0.0;\n  twist.twist.twist.linear.x = 1.0;\n  twist.twist.twist.angular.z = (M_PI/2) / (100.0 * 0.05);\n\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.twist.twist.angular.z - twist.twist.twist.angular.z), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - filtered_.pose.pose.position.y), 0.5);\n\n  resetFilter();\n\n  twist.twist.twist.linear.x = 0.0;\n  twist.twist.twist.angular.z = 0.0;\n  twist.twist.twist.angular.x = -(M_PI/2) / (100.0 * 0.05);\n\n  // First, roll the vehicle on its side\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  twist.twist.twist.angular.x = 0.0;\n  twist.twist.twist.angular.y = (M_PI/2) / (100.0 * 0.05);\n\n  // Now, pitch it down (positive pitch velocity in vehicle frame)\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  twist.twist.twist.angular.y = 0.0;\n  twist.twist.twist.linear.x = 3.0;\n\n  // We should now be on our side and facing -Y. Move forward in\n  // the vehicle frame X direction, and make sure Y decreases in\n  // the world frame.\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    twist.header.stamp = ros::Time::now();\n    twistPub.publish(twist);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    twist.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - twist.twist.twist.linear.x), 0.1);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 15), 1.0);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, ImuPoseBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher imuPub = nh.advertise<sensor_msgs::Imu>(\"/imu_input0\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  sensor_msgs::Imu imu;\n  tf2::Quaternion quat;\n  quat.setRPY(M_PI/4, -M_PI/4, M_PI/2);\n  imu.orientation = tf2::toMsg(quat);\n\n  for (size_t ind = 0; ind < 9; ind+=4)\n  {\n    imu.orientation_covariance[ind] = 1e-6;\n  }\n\n  imu.header.frame_id = \"base_link\";\n\n  // Make sure the pose reset worked. Test will timeout\n  // if this fails.\n  ros::Rate loopRate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    imu.header.seq++;\n  }\n\n  // Now check the values from the callback\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  tf2::Matrix3x3 mat(quat);\n  double r, p, y;\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r - M_PI/4), 0.1);\n  EXPECT_LT(::fabs(p + M_PI/4), 0.1);\n  EXPECT_LT(::fabs(y - M_PI/2), 0.1);\n\n  EXPECT_LT(filtered_.pose.covariance[21], 0.5);\n  EXPECT_LT(filtered_.pose.covariance[28], 0.25);\n  EXPECT_LT(filtered_.pose.covariance[35], 0.5);\n\n  resetFilter();\n\n  // Test to see if the orientation data is ignored when we set the\n  // first covariance value to -1\n  sensor_msgs::Imu imuIgnore;\n  imuIgnore.orientation.x = 0.1;\n  imuIgnore.orientation.y = 0.2;\n  imuIgnore.orientation.z = 0.3;\n  imuIgnore.orientation.w = 0.4;\n  imuIgnore.orientation_covariance[0] = -1;\n\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imuIgnore.header.stamp = ros::Time::now();\n    imuPub.publish(imuIgnore);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imuIgnore.header.seq++;\n  }\n\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  mat.setRotation(quat);\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r), 1e-3);\n  EXPECT_LT(::fabs(p), 1e-3);\n  EXPECT_LT(::fabs(y), 1e-3);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, ImuTwistBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher imuPub = nh.advertise<sensor_msgs::Imu>(\"/imu_input1\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  sensor_msgs::Imu imu;\n  tf2::Quaternion quat;\n  imu.angular_velocity.x = (M_PI / 2.0);\n\n  for (size_t ind = 0; ind < 9; ind+=4)\n  {\n    imu.angular_velocity_covariance[ind] = 1e-6;\n  }\n\n  imu.header.frame_id = \"base_link\";\n\n  ros::Rate loopRate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  // Now check the values from the callback\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  tf2::Matrix3x3 mat(quat);\n  double r, p, y;\n  mat.getRPY(r, p, y);\n\n  // Tolerances may seem loose, but the initial state covariances\n  // are tiny, so the filter is sluggish to accept velocity data\n  EXPECT_LT(::fabs(r - M_PI / 2.0), 0.7);\n  EXPECT_LT(::fabs(p), 0.1);\n  EXPECT_LT(::fabs(y), 0.1);\n\n  EXPECT_LT(filtered_.twist.covariance[21], 1e-3);\n  EXPECT_LT(filtered_.pose.covariance[21], 0.1);\n\n  resetFilter();\n\n  imu.angular_velocity.x = 0.0;\n  imu.angular_velocity.y = -(M_PI / 2.0);\n\n  // Make sure the pose reset worked. Test will timeout\n  // if this fails.\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  // Now check the values from the callback\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n\n  tf2::Quaternion expected_quat(tf2::Vector3(0., 1., 0.), -M_PI/2.0);\n\n  EXPECT_LT(std::abs(tf2Angle(expected_quat.getAxis(), quat.getAxis())), 0.1);\n  EXPECT_LT(std::abs(expected_quat.getAngle() - quat.getAngle()), 0.7);\n\n  EXPECT_LT(filtered_.twist.covariance[28], 1e-3);\n  EXPECT_LT(filtered_.pose.covariance[28], 0.1);\n\n  resetFilter();\n\n  imu.angular_velocity.y = 0;\n  imu.angular_velocity.z = M_PI / 4.0;\n\n  // Make sure the pose reset worked. Test will timeout\n  // if this fails.\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  // Now check the values from the callback\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  mat.setRotation(quat);\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r), 0.1);\n  EXPECT_LT(::fabs(p), 0.1);\n  EXPECT_LT(::fabs(y - M_PI / 4.0), 0.7);\n\n  EXPECT_LT(filtered_.twist.covariance[35], 1e-3);\n  EXPECT_LT(filtered_.pose.covariance[35], 0.1);\n\n  resetFilter();\n\n  // Test to see if the angular velocity data is ignored when we set the\n  // first covariance value to -1\n  sensor_msgs::Imu imuIgnore;\n  imuIgnore.angular_velocity.x = 100;\n  imuIgnore.angular_velocity.y = 100;\n  imuIgnore.angular_velocity.z = 100;\n  imuIgnore.angular_velocity_covariance[0] = -1;\n\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imuIgnore.header.stamp = ros::Time::now();\n    imuPub.publish(imuIgnore);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imuIgnore.header.seq++;\n  }\n\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  mat.setRotation(quat);\n  mat.getRPY(r, p, y);\n  EXPECT_LT(::fabs(r), 1e-3);\n  EXPECT_LT(::fabs(p), 1e-3);\n  EXPECT_LT(::fabs(y), 1e-3);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, ImuAccBasicIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher imuPub = nh.advertise<sensor_msgs::Imu>(\"/imu_input2\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  sensor_msgs::Imu imu;\n  imu.header.frame_id = \"base_link\";\n  imu.linear_acceleration_covariance[0] = 1e-6;\n  imu.linear_acceleration_covariance[4] = 1e-6;\n  imu.linear_acceleration_covariance[8] = 1e-6;\n\n  imu.linear_acceleration.x = 1;\n  imu.linear_acceleration.y = -1;\n  imu.linear_acceleration.z = 1;\n\n  // Move with constant acceleration for 1 second,\n  // then check our velocity.\n  ros::Rate loopRate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.x - 1.0), 0.4);\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.y + 1.0), 0.4);\n  EXPECT_LT(::fabs(filtered_.twist.twist.linear.z - 1.0), 0.4);\n\n  imu.linear_acceleration.x = 0.0;\n  imu.linear_acceleration.y = 0.0;\n  imu.linear_acceleration.z = 0.0;\n\n  // Now move for another second, and see where we\n  // end up\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imu.header.seq++;\n  }\n\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1.2), 0.4);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y + 1.2), 0.4);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z - 1.2), 0.4);\n\n  resetFilter();\n\n  // Test to see if the linear acceleration data is ignored when we set the\n  // first covariance value to -1\n  sensor_msgs::Imu imuIgnore;\n  imuIgnore.linear_acceleration.x = 1000;\n  imuIgnore.linear_acceleration.y = 1000;\n  imuIgnore.linear_acceleration.z = 1000;\n  imuIgnore.linear_acceleration_covariance[0] = -1;\n\n  loopRate = ros::Rate(50);\n  for (size_t i = 0; i < 50; ++i)\n  {\n    imuIgnore.header.stamp = ros::Time::now();\n    imuPub.publish(imuIgnore);\n    loopRate.sleep();\n    ros::spinOnce();\n\n    imuIgnore.header.seq++;\n  }\n\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 1e-3);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 1e-3);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 1e-3);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, OdomDifferentialIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher odomPub = nh.advertise<nav_msgs::Odometry>(\"/odom_input1\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  nav_msgs::Odometry odom;\n  odom.pose.pose.position.x = 20.0;\n  odom.pose.pose.position.y = 10.0;\n  odom.pose.pose.position.z = -40.0;\n\n  odom.pose.pose.orientation.w = 1;\n\n  odom.pose.covariance[0] = 2.0;\n  odom.pose.covariance[7] = 2.0;\n  odom.pose.covariance[14] = 2.0;\n  odom.pose.covariance[21] = 0.2;\n  odom.pose.covariance[28] = 0.2;\n  odom.pose.covariance[35] = 0.2;\n\n  odom.header.frame_id = \"odom\";\n  odom.child_frame_id = \"base_link\";\n\n  // No guaranteeing that the zero state\n  // we're expecting to see here isn't just\n  // a result of zeroing it out previously,\n  // so check 10 times in succession.\n  size_t zeroCount = 0;\n  while (zeroCount++ < 10)\n  {\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01);\n\n    ros::Duration(0.1).sleep();\n\n    odom.header.seq++;\n  }\n\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    odom.pose.covariance[ind] = 1e-6;\n  }\n\n  // Slowly move the position, and hope that the\n  // differential position keeps up\n  ros::Rate loopRate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    odom.pose.pose.position.x += 0.01;\n    odom.pose.pose.position.y += 0.02;\n    odom.pose.pose.position.z -= 0.03;\n\n    odom.header.stamp = ros::Time::now();\n    odomPub.publish(odom);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    odom.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, PoseDifferentialIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher posePub = nh.advertise<geometry_msgs::PoseWithCovarianceStamped>(\"/pose_input1\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  geometry_msgs::PoseWithCovarianceStamped pose;\n  pose.pose.pose.position.x = 20.0;\n  pose.pose.pose.position.y = 10.0;\n  pose.pose.pose.position.z = -40.0;\n\n  pose.pose.pose.orientation.w = 1;\n\n  pose.pose.covariance[0] = 2.0;\n  pose.pose.covariance[7] = 2.0;\n  pose.pose.covariance[14] = 2.0;\n  pose.pose.covariance[21] = 0.2;\n  pose.pose.covariance[28] = 0.2;\n  pose.pose.covariance[35] = 0.2;\n\n  pose.header.frame_id = \"odom\";\n\n  // No guaranteeing that the zero state\n  // we're expecting to see here isn't just\n  // a result of zeroing it out previously,\n  // so check 10 times in succession.\n  size_t zeroCount = 0;\n  while (zeroCount++ < 10)\n  {\n    pose.header.stamp = ros::Time::now();\n    posePub.publish(pose);\n    ros::spinOnce();\n\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.x), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.y), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.position.z), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.x), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.y), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.z), 0.01);\n    EXPECT_LT(::fabs(filtered_.pose.pose.orientation.w - 1), 0.01);\n\n    ros::Duration(0.1).sleep();\n\n    pose.header.seq++;\n  }\n\n  // ...but only if we give the measurement a tiny covariance\n  for (size_t ind = 0; ind < 36; ind+=7)\n  {\n    pose.pose.covariance[ind] = 1e-6;\n  }\n\n  // Issue this location repeatedly, and see if we get\n  // a final reported position of (1, 2, -3)\n  ros::Rate loopRate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    pose.pose.pose.position.x += 0.01;\n    pose.pose.pose.position.y += 0.02;\n    pose.pose.pose.position.z -= 0.03;\n\n    pose.header.stamp = ros::Time::now();\n    posePub.publish(pose);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    pose.header.seq++;\n  }\n  ros::spinOnce();\n\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.x - 1), 0.2);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.y - 2), 0.4);\n  EXPECT_LT(::fabs(filtered_.pose.pose.position.z + 3), 0.6);\n\n  resetFilter();\n}\n\nTEST(InterfacesTest, ImuDifferentialIO)\n{\n  ros::NodeHandle nh;\n  ros::Publisher imu0Pub = nh.advertise<sensor_msgs::Imu>(\"/imu_input0\", 5);\n  ros::Publisher imu1Pub = nh.advertise<sensor_msgs::Imu>(\"/imu_input1\", 5);\n  ros::Publisher imuPub = nh.advertise<sensor_msgs::Imu>(\"/imu_input3\", 5);\n  ros::Subscriber filteredSub = nh.subscribe(\"/odometry/filtered\", 1, &filterCallback);\n\n  sensor_msgs::Imu imu;\n  imu.header.frame_id = \"base_link\";\n  tf2::Quaternion quat;\n  const double roll = M_PI/2.0;\n  const double pitch = -M_PI;\n  const double yaw = -M_PI/4.0;\n  quat.setRPY(roll, pitch, yaw);\n  imu.orientation = tf2::toMsg(quat);\n\n  imu.orientation_covariance[0] = 0.02;\n  imu.orientation_covariance[4] = 0.02;\n  imu.orientation_covariance[8] = 0.02;\n\n  imu.angular_velocity_covariance[0] = 0.02;\n  imu.angular_velocity_covariance[4] = 0.02;\n  imu.angular_velocity_covariance[8] = 0.02;\n\n  size_t setCount = 0;\n  while (setCount++ < 10)\n  {\n    imu.header.stamp = ros::Time::now();\n    imu0Pub.publish(imu);  // Use this to move the absolute orientation\n    imu1Pub.publish(imu);  // Use this to keep velocities at 0\n    ros::spinOnce();\n\n    ros::Duration(0.1).sleep();\n\n    imu.header.seq++;\n  }\n\n  size_t zeroCount = 0;\n  while (zeroCount++ < 10)\n  {\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    ros::spinOnce();\n\n    ros::Duration(0.1).sleep();\n\n    imu.header.seq++;\n  }\n\n  double rollFinal = roll;\n  double pitchFinal = pitch;\n  double yawFinal = yaw;\n\n  // Move the orientation slowly, and see if we\n  // can push it to 0\n  ros::Rate loopRate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    yawFinal -= 0.01 * (3.0 * M_PI/4.0);\n\n    quat.setRPY(rollFinal, pitchFinal, yawFinal);\n\n    imu.orientation = tf2::toMsg(quat);\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    imu.header.seq++;\n  }\n  ros::spinOnce();\n\n  // Move the orientation slowly, and see if we\n  // can push it to 0\n  loopRate = ros::Rate(20);\n  for (size_t i = 0; i < 100; ++i)\n  {\n    rollFinal += 0.01 * (M_PI/2.0);\n\n    quat.setRPY(rollFinal, pitchFinal, yawFinal);\n\n    imu.orientation = tf2::toMsg(quat);\n    imu.header.stamp = ros::Time::now();\n    imuPub.publish(imu);\n    ros::spinOnce();\n\n    loopRate.sleep();\n\n    imu.header.seq++;\n  }\n  ros::spinOnce();\n\n  tf2::fromMsg(filtered_.pose.pose.orientation, quat);\n  tf2::Matrix3x3 mat(quat);\n  mat.getRPY(rollFinal, pitchFinal, yawFinal);\n  EXPECT_LT(::fabs(rollFinal), 0.2);\n  EXPECT_LT(::fabs(pitchFinal), 0.2);\n  EXPECT_LT(::fabs(yawFinal), 0.2);\n\n  resetFilter();\n}\n\nint main(int argc, char **argv)\n{\n  testing::InitGoogleTest(&argc, argv);\n\n  ros::init(argc, argv, \"ukf_navigation_node-test-interfaces\");\n  ros::Time::init();\n\n  // Give ukf_localization_node time to initialize\n  ros::Duration(2.0).sleep();\n\n  return RUN_ALL_TESTS();\n}\n"
  },
  {
    "path": "src/robot_localization/test/test_ukf_localization_node_interfaces.test",
    "content": "<!-- Launch file for ukf_localization_node_test-interfaces -->\n\n<launch>\n\n    <node name=\"test_ukf_localization_node_interfaces_ukf\" pkg=\"robot_localization\" type=\"ukf_localization_node\" clear_params=\"true\">\n\n      <param name=\"frequency\" value=\"30\"/>\n\n      <param name=\"sensor_timeout\" value=\"0.1\"/>\n\n      <param name=\"odom0\" value=\"/odom_input0\"/>\n      <param name=\"odom1\" value=\"/odom_input1\"/>\n      <param name=\"odom2\" value=\"/odom_input2\"/>\n\n      <param name=\"pose0\" value=\"/pose_input0\"/>\n      <param name=\"pose1\" value=\"/pose_input1\"/>\n\n      <param name=\"twist0\" value=\"/twist_input0\"/>\n\n      <param name=\"imu0\" value=\"/imu_input0\"/>\n      <param name=\"imu1\" value=\"/imu_input1\"/>\n      <param name=\"imu2\" value=\"/imu_input2\"/>\n      <param name=\"imu3\" value=\"/imu_input3\"/>\n\n      <rosparam param=\"odom0_config\">[true, false, true, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"odom1_config\">[true, true, true, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"odom2_config\">[false, false, false, false, false, false, true, true, true, true, true, true, false, false, false]</rosparam>\n\n      <rosparam param=\"pose0_config\">[true, false, true, false, false, false, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"pose1_config\">[true, true, true, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n\n      <rosparam param=\"twist0_config\">[false, false, false, false, false, false, true, true, true, true, true, true, false, false, false]</rosparam>\n\n      <rosparam param=\"imu0_config\">[false, false, false, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n      <rosparam param=\"imu1_config\">[false, false, false, false, false, false, false, false, false, true, true, true, false, false, false]</rosparam>\n      <rosparam param=\"imu2_config\">[false, false, false, false, false, false, false, false, false, false, false, false, true, true, true]</rosparam>\n      <rosparam param=\"imu3_config\">[false, false, false, true, true, true, false, false, false, false, false, false, false, false, false]</rosparam>\n\n      <!-- Differential setting is off for this test -->\n      <param name=\"odom1_differential\" value=\"true\"/>\n      <param name=\"pose1_differential\" value=\"true\"/>\n      <param name=\"imu3_differential\" value=\"true\"/>\n\n      <param name=\"print_diagnostics\" value=\"false\"/>\n\n      <param name=\"odom_frame\" value=\"odom\"/>\n      <param name=\"base_link_frame\" value=\"base_link\"/>\n\n      <rosparam param=\"process_noise_covariance\">[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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  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,\n                                                  0.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,\n                                                  0.0, 0.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,\n                                                  0.0, 0.0, 0.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]</rosparam>\n\n      <param name=\"alpha\" value=\"0.001\"/> \n      <param name=\"kappa\" value=\"0\"/> \n      <param name=\"beta\" value=\"2\"/>\n\n    </node>\n\n    <test test-name=\"test_ukf_localization_node_interfaces_int\" pkg=\"robot_localization\" type=\"test_ukf_localization_node_interfaces\" clear_params=\"true\" time-limit=\"1000.0\" />\n\n</launch>\n"
  }
]