Code Monkey home page Code Monkey logo

hdl_graph_slam's Introduction

New SLAM package is released

A new 3D SLAM package is released: https://github.com/koide3/glim.

hdl_graph_slam

hdl_graph_slam is an open source ROS package for real-time 6DOF SLAM using a 3D LIDAR. It is based on 3D Graph SLAM with NDT scan matching-based odometry estimation and loop detection. It also supports several graph constraints, such as GPS, IMU acceleration (gravity vector), IMU orientation (magnetic sensor), and floor plane (detected in a point cloud). We have tested this package with Velodyne (HDL32e, VLP16) and RoboSense (16 channels) sensors in indoor and outdoor environments.

Build on melodic & noetic

Third-party extensions

See also the following nice works built upon hdl_graph_slam. Feel free to request to include your work in the list :)

Nodelets

hdl_graph_slam consists of four nodelets.

  • prefiltering_nodelet
  • scan_matching_odometry_nodelet
  • floor_detection_nodelet
  • hdl_graph_slam_nodelet

The input point cloud is first downsampled by prefiltering_nodelet, and then passed to the next nodelets. While scan_matching_odometry_nodelet estimates the sensor pose by iteratively applying a scan matching between consecutive frames (i.e., odometry estimation), floor_detection_nodelet detects floor planes by RANSAC. The estimated odometry and the detected floor planes are sent to hdl_graph_slam. To compensate the accumulated error of the scan matching, it performs loop detection and optimizes a pose graph which takes various constraints into account.

Constraints (Edges)

You can enable/disable each constraint by changing params in the launch file, and you can also change the weight (*_stddev) and the robust kernel (*_robust_kernel) of each constraint.

  • Odometry

  • Loop closure

  • GPS

    • /gps/geopoint (geographic_msgs/GeoPointStamped)
    • /gps/navsat (sensor_msgs/NavSatFix)
    • /gpsimu_driver/nmea_sentence (nmea_msgs/Sentence)

hdl_graph_slam supports several GPS message types. All the supported types contain (latitude, longitude, and altitude). hdl_graph_slam converts them into the UTM coordinate, and adds them into the graph as 3D position constraints. If altitude is set to NaN, the GPS data is treated as a 2D constrait. GeoPoint is the most basic one, which consists of only (lat, lon, alt). Although NavSatFix provides many information, we use only (lat, lon, alt) and ignore all other data. If you're using HDL32e, you can directly connect hdl_graph_slam with velodyne_driver via /gpsimu_driver/nmea_sentence.

  • IMU acceleration (gravity vector)
    • /gpsimu_driver/imu_data (sensor_msgs/Imu)

This constraint rotates each pose node so that the acceleration vector associated with the node becomes vertical (as the gravity vector). This is useful to compensate for accumulated tilt rotation errors of the scan matching. Since we ignore acceleration by sensor motion, you should not give a big weight for this constraint.

  • IMU orientation (magnetic sensor)

    • /gpsimu_driver/imu_data (sensor_msgs/Imu)

    If your IMU has a reliable magnetic orientation sensor, you can add orientation data to the graph as 3D rotation constraints. Note that, magnetic orientation sensors can be affected by external magnetic disturbances. In such cases, this constraint should be disabled.

  • Floor plane

    • /floor_detection/floor_coeffs (hdl_graph_slam/FloorCoeffs)

This constraint optimizes the graph so that the floor planes (detected by RANSAC) of the pose nodes becomes the same. This is designed to compensate the accumulated rotation error of the scan matching in large flat indoor environments.

Parameters

All the configurable parameters are listed in launch/hdl_graph_slam.launch as ros params.

Services

  • /hdl_graph_slam/dump (hdl_graph_slam/DumpGraph)
    • save all the internal data (point clouds, floor coeffs, odoms, and pose graph) to a directory.
  • /hdl_graph_slam/save_map (hdl_graph_slam/SaveMap)
    • save the generated map as a PCD file.

Requirements

hdl_graph_slam requires the following libraries:

  • OpenMP
  • PCL
  • g2o
  • suitesparse

The following ROS packages are required:

# for melodic
sudo apt-get install ros-melodic-geodesy ros-melodic-pcl-ros ros-melodic-nmea-msgs ros-melodic-libg2o
cd catkin_ws/src
git clone https://github.com/koide3/ndt_omp.git -b melodic
git clone https://github.com/SMRT-AIST/fast_gicp.git --recursive
git clone https://github.com/koide3/hdl_graph_slam

cd .. && catkin_make -DCMAKE_BUILD_TYPE=Release

# for noetic
sudo apt-get install ros-noetic-geodesy ros-noetic-pcl-ros ros-noetic-nmea-msgs ros-noetic-libg2o

cd catkin_ws/src
git clone https://github.com/koide3/ndt_omp.git
git clone https://github.com/SMRT-AIST/fast_gicp.git --recursive
git clone https://github.com/koide3/hdl_graph_slam

cd .. && catkin_make -DCMAKE_BUILD_TYPE=Release

[optional] bag_player.py script requires ProgressBar2.

sudo pip install ProgressBar2

Example1 (Indoor)

Bag file (recorded in a small room):

rosparam set use_sim_time true
roslaunch hdl_graph_slam hdl_graph_slam_501.launch
roscd hdl_graph_slam/rviz
rviz -d hdl_graph_slam.rviz
rosbag play --clock hdl_501_filtered.bag

We also provide bag_player.py which automatically adjusts the playback speed and processes data as fast as possible.

rosrun hdl_graph_slam bag_player.py hdl_501_filtered.bag

You'll see a point cloud like:

You can save the generated map by:

rosservice call /hdl_graph_slam/save_map "resolution: 0.05
destination: '/full_path_directory/map.pcd'"

Example2 (Outdoor)

Bag file (recorded in an outdoor environment):

rosparam set use_sim_time true
roslaunch hdl_graph_slam hdl_graph_slam_400.launch
roscd hdl_graph_slam/rviz
rviz -d hdl_graph_slam.rviz
rosbag play --clock hdl_400.bag

Example with GPS

Ford Campus Vision and Lidar Data Set [URL]

The following script converts the Ford Lidar Dataset to a rosbag and plays it. In this example, hdl_graph_slam utilizes the GPS data to correct the pose graph.

cd IJRR-Dataset-2
rosrun hdl_graph_slam ford2bag.py dataset-2.bag
rosrun hdl_graph_slam bag_player.py dataset-2.bag

Use hdl_graph_slam in your system

  1. Define the transformation between your sensors (LIDAR, IMU, GPS) and base_link of your system using static_transform_publisher (see line #11, hdl_graph_slam.launch). All the sensor data will be transformed into the common base_link frame, and then fed to the SLAM algorithm.

  2. Remap the point cloud topic of prefiltering_nodelet. Like:

  <node pkg="nodelet" type="nodelet" name="prefiltering_nodelet" ...
    <remap from="/velodyne_points" to="/rslidar_points"/>
  ...

Common Problems

Parameter tuning guide

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

  • registration_method [updated] In short, use FAST_GICP for most cases and FAST_VGICP or NDT_OMP if the processing speed matters This parameter allows to change the registration method to be used for odometry estimation and loop detection. Note that GICP in PCL1.7 (ROS kinetic) or earlier has a bug in the initial guess handling. If you are on ROS kinectic or earlier, do not use GICP.

  • ndt_resolution This parameter decides the voxel size of NDT. Typically larger values are good for outdoor environements (0.5 - 2.0 [m] for indoor, 2.0 - 10.0 [m] for outdoor). If you chose NDT or NDT_OMP, tweak this parameter so you can obtain a good odometry estimation result.

  • other parameters All the configurable parameters are available in the launch file. Copy a template launch file (hdl_graph_slam_501.launch for indoor, hdl_graph_slam_400.launch for outdoor) and tweak parameters in the launch file to adapt it to your application.

License

This package is released under the BSD-2-Clause License.

Note that the cholmod solver in g2o is licensed under GPL. You may need to build g2o without cholmod dependency to avoid the GPL.

Related packages

Papers

Kenji Koide, Jun Miura, and Emanuele Menegatti, A Portable 3D LIDAR-based System for Long-term and Wide-area People Behavior Measurement, Advanced Robotic Systems, 2019 [link].

Contact

Kenji Koide, [email protected], https://staff.aist.go.jp/k.koide

Active Intelligent Systems Laboratory, Toyohashi University of Technology, Japan [URL]
Mobile Robotics Research Team, National Institute of Advanced Industrial Science and Technology (AIST), Japan [URL]

hdl_graph_slam's People

Contributors

achmadfathoni avatar err4o4 avatar jihoonl avatar jitrc avatar koide3 avatar krisklau avatar ksuszka avatar ll7 avatar naoki-mizuno avatar robustify avatar sonphambk avatar tim-fan avatar timple avatar tirelessdev avatar tkkim-robot avatar tutorgaming avatar yukkysaito avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

hdl_graph_slam's Issues

Possible mismatch between keyframe and odom in hdl_graph_slam_nodelet?

In scan_matching_odometry_nodelet, the odometry gets published between every incomming cloud from /filtered_points and its previous keyframe. When the odometry is above some specified threshold, the keyframe against which incomming pointclouds are matched is updated. The hdl_graph_slam_nodelet feeds off the same topic /filtered_points, and synchronizes the pointcloud callback with the odom topic, and then again checks if a new keyframe should be added. However, the last known keyframe from scan_matching_odometry_nodelet is not necessarily the same as the last keyframe in hdl_graph_slam_nodelet, this is because it is determined with two different thresholds (1, 2) if a new keyframe should be added and on top of that you might drop some messages if you don't have the processing power to process all incomming pointclouds. The chance these two pointclouds are the same is actually very small. This means that the odom in the cloud_callback function is not based on the same previous keyframe in hdl_graph_slam_nodelet. I would imagine this has an considerable effect on accuracy of the graph since the odom edge between the two vertices is not correct.

Might this be a bug or is this done on purpose and am I missing something? Why not just publish a custom message from scan_matching_odometry_nodelet that includes both the pointcloud and odom from keyframes only and process those messages in hdl_graph_slam_nodelet? Than you also just have to check once if you have a new keyframe.

FloorCoeffs.h

hi, @koide3 ,your code include <hdl_slam_graph/FloorCoeffs.h>,but I can't find the FloorCoeffs.h

the prefilering_nodelet.cpp

hi, @koide3 ,I want to ask baout the question about points_sub = nh.subscribe("/velodyne_points", 64, &PrefilteringNodelet::cloud_callback, this);in the prefiltering_nodelet.cpp.
void cloud_callback(const pcl::PointCloud::ConstPtr& src_cloud); the type of the parameter is sensor_msgs/PointCloud2, but in your code is pcl::PointCloud, and I could not understand it.
Thanks!

Running time?

Hi, and thank you for making this code available.
What is the latency of this system roughly?
How many scans can be processed per second in real time?
Thanks!

Failed to use my own .bag data for mapping

Hi, we can run the example *.bag data to build the map correctly, but there is something wrong when i am using my own *.bag data. (i use a velodyne-vlp16). Here are the details:

i use the command to record my own *.bag:

roslaunch velodyne_pointcloud VLP16_points.launch [calibration:=/home/smartcar/sunm/velodyne/VeloView-VLP-16-HiRes.yaml]

rosbag record -O indoor /velodyne_points

does this is right to save my own *.bag data ? thanks a lot

when i using my own *.bag data , i got the error message in the rviz:
screenshot from 2018-06-25 21-48-04

and, i got the error message ine the terminal:

screenshot from 2018-06-25 21-48-20

and in the rviz, i only get the motionless point, it seems like it only show one frame:

screenshot from 2018-06-25 22-32-54

it seems that there is something wrong in the time of the data recorded according to the error mssage in the rviz. But i don't know how to deal with it ? Would help me with it? thanks a lot!

didn't map after a keyframe

hi @koide3 ! when I run order rosbag play --clock hdl_501_filtered.bag, it always putout the infomation streams like the following .

[ INFO] [1539071090.720670900, 1503376943.796794021]: scan matching has not converged!!
[ INFO] [1539071090.720959628, 1503376943.796794021]: ignore this frame(1503376924.384562000)

as for the map, only one pose and one keyframe map can be seen in the rviz. I think the scanmatching nodelet may doesn't work. I guss cI must do something wrong. Hope you can give some suggestion and help me to figure out why such infomation streams will be putout. Thank you!!

Failed to load nodelet hdl_graph_slam_nodelet

Thank you for author greate job, I met a problem like
[ERROR] [1525081595.448920058, 1509878536.248604299]: Failed to load nodelet [/hdl_graph_slam_nodelet] of type [hdl_graph_slam/HdlGraphSlamNodelet] even after refreshing the cache: MultiLibraryClassLoader: Could not create object of class type hdl_graph_slam::HdlGraphSlamNodelet as no factory exists for it. Make sure that the library exists and was explicitly loaded through MultiLibraryClassLoader::loadLibrary()
[ERROR] [1525081595.448999330, 1509878536.248604299]: The error before refreshing the cache was: Failed to load library /home/user/Autoware/ros/devel/lib//libhdl_graph_slam_nodelet.so. Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library (Poco exception = /home/user/Autoware/ros/devel/lib//libhdl_graph_slam_nodelet.so: undefined symbol: _ZTIN3g2o16OptimizableGraph4EdgeE)
[FATAL] [1525081595.449254825, 1509878536.248604299]: Failed to load nodelet '/hdl_graph_slam_nodeletof typehdl_graph_slam/HdlGraphSlamNodeletto managerhdl_nodelet_manager'
[hdl_graph_slam_nodelet-5] process has died [pid 22601, exit code 255, cmd /opt/ros/indigo/lib/nodelet/nodelet load hdl_graph_slam/HdlGraphSlamNodelet hdl_nodelet_manager __name:=hdl_graph_slam_nodelet __log:=/home/user/.ros/log/2445a0dc-4c51-11e8-9319-0cc47a135e00/hdl_graph_slam_nodelet-5.log].
log file: /home/user/.ros/log/2445a0dc-4c51-11e8-9319-0cc47a135e00/hdl_graph_slam_nodelet-5*.log, can you give me some advice, I would be appreciated!

pose graph optimization error

Hi ,I already install g2o with hdl_graph_slam branch ,but when pose graph optimization , it has problem with [velodyne_nodelet_manager-2] process has died [pid 4467, exit code -11, cmd /opt/ros/kinetic/lib/nodelet/nodelet manager __name:=velodyne_nodelet_manager , am I need set g2o dir in cmakelist?

complain about "fail to find transform"

Hi @koide3 ,
When I turn on enable_imu_acc, I notice that hdl_graph_slam can't find the transform between keyframes #L390 I tried different ndt_nn_search_method as well as kernel types but they don't help with the problem.
I also run with your bag file hdl_400.bag and the error also appears.
Could you give any hint that might cause this problem? My guess is about the time-sync between imu readings and velodyne scans. Is it better if they are synced?

map moves instead of velodyne tf marker

hi @koide3 please I have a little problem. I have the VLP-16 lidar mounted on a tripod. As I move the tripod, the map depicted by the /velodyne_points topic moves along with the map while the "velodyne" tf marker remains stationary. Do you know why this could be happening?

can you give me your paper?

Hi,koide:

I'm learning your open source code of hdl_graph_slam, can you give me your paper (Kenji Koide, Jun Miura, and Emanuele Menegatti, A Portable 3D LIDAR-based System for Long-term and Wide-area People Behavior Measurement, IEEE Transactions on Human-Machine Systems)?My e-mail is [email protected]
I promise not to be used for commercial purposes, but for learning.Thanks very much.

Yours
LiYing

Where to find the hdl_graph_slam/SaveMap.h ??

Hi,

I am curious where can i find this file (SaveMap.h). I have been searching it in all the directories, but i couldn't find them. I need to customize it for my own usage.

Best.
Samuel

If I run it in my computer and use velodyne-16, warning: keyframes empty

I'm sorry to ask this seemingly simple question. But I haven't found a solution for a long time.
I can run your bag file properly and save the map. However, when I wanted to build a map with my own velodyne, there were some problems.

In your README.md, you mentioned that we should <remap ……, and I think if I use velodyne, I needn't modify it. So I connected the velodyne, and roslaunch hdl_graph_slam hdl_graph_slam.launch. But I can't see anything except warning: keyframes empty(In the lower left corner of the picture). And if I want to see the topic use rostopic echo /velodyne_points , it's empty too. So I don't think the velodyne works. Do I need to set up something else?

keyframe empty

I find a solution to this problem, I remove the line 15 in hdl_graph_slam.launch <node pkg="nodelet" type="nodelet" name="$(arg nodelet_manager)" args="manager" output="screen"/>, and then start the velodyne byroslaunch velodyne_pointcloud VLP16_points.launch calibration:=/home/sun/Desktop/VLP-16.yaml, the point cloud data can be displayed, but after a while, new problems will arise.like this:

error2

So I don't know how to run your code correctly with my velodyne. Can you provide some solutions? Thanks.

Ubuntu 16.04 + Kinetic
PCL 1.7 (In ROS)
g2o https://github.com/felixendres/g2o
I don't think it has much to do with these versions, because I can run bag properly.

Hardware Requirements

Hello, I found this project a greatful job that build Lidar HD map for localization.

When I run the indoor example it seems all right, but while running the outdoor example it seems to be much slower, and I think it can not run in real-time, cause when I see the trajectory calculated by the program the key point seems to be fewer than the result show in the Readme Document. It seems that the graph_update cannot finish in 3 second as set in the hdl_graph_slam_nodelet.

My hardware info:
Intel Core i7-6820EQ (2.8 GHz 4Cores 8 threads)
8GB memory

Q1: What is the lowest hardware requirements is this project? Can I just slow down the Rosbag relay rate, and set the graph optimize timer longer, for example change the original point cloud period from 10Hz to 5Hz and then set the graph optimize timer to 6s (from the original 3s in the current project)

Q2:And if I want to build a large map, for example a 4km rectangle in outdoor enviroment, with only one closed loop, can this project fininsh that? and will it be slower and slower when the map become larger?

Thank you !

Algorithm crashing

Hi,
I have been experiencing a problem where after a number of nodes are added to the pose graph the algorithm crashes and returns the following errors.

[pcl::NormalEstimation::compute] input_ is empty!

Initially when the algorithm starts no errors are present, then a new marker is added to the map (sphere), this error is printed out in Rviz:

[ WARN] [1533303347.367675061]: Invalid argument passed to canTransform argument source_frame in tf2 frame_ids cannot be empty

And the Marker Array section in Rviz says status error but with no additional information.

I would really appreciate some help on this.
Thank you very much!

Map odom transforms and mapping an unflat surface

Hi @koide3 ,

I have installed you Hdl_graph_slam and Hdl_localizations packages and have been implementing them on a Clearpath Husky robot and have a couple of questions:

Hdl_graph_slam:

1- I recorded a rosbag file of the area I want to map (I am using a VLP-16 lidar and an RTK GPS for scan-matching error correction) and launched the hdl_graph_slam launch file. However, during the mapping process, the odom frame jumps around, while only the map frame stays fixed, the 0,0, 0 of the map frame is the starting point of the mapping process. Also, while the map being built represents the area I am mapping correctly, as the map is being built, the map kind of sinks in the negative z-direction of the map frame axis. I have attached a screen shot, which hopefully better explains what I am talking about. Do you have any idea why these things are happening? Should not the map frame and the odom frame stay fixed to where the mapping process started?

map odom transform

2- I sent you an email to: [email protected] from my email: [email protected] and would really appreciate it if you can send me a copy of your paper, as I would be strictly using it for educational purposes and to better understand the algorithm you implemented in these packages.

3- I have been mainly using the hdl_graph_slam outdoors on unflat surfaces and wanted to ask you about the limitations of the algorithm if I am implementing it with a gps while turning off the floor_detection_nodelet. How accurate is the algorithm? and what are some of the parameters I can tune to get better results?

Hdl_localization:

After obtaining a map of the area, I am implementing the hdl_localization package to localize my Husky robot within this map. However, I wanted to ask about how should I go around fixing my transform tree, which as of right now is consisted of a base_link which is the parent frame for the remaining components of the robot, including the velodyne frame that I am using and another transform tree consisting of the map parent frame and the velodyne child frame. Attached is a screenshot of my transform trees:

frames.pdf

Below is the error I am getting:

`ERROR TF re-parenting contention:

  • reparenting of [velodyne] to [map] by [/velodyne_nodelet_manager]
  • reparenting of [velodyne] to [sensor_arch_mount_link] by [/robot_state_publisher]

ERROR TF multiple authority contention:

  • node [/velodyne_nodelet_manager] publishing transform [velodyne] with parent [map] already published by node [/robot_state_publisher]
  • node [/robot_state_publisher] publishing transform [velodyne] with parent [sensor_arch_mount_link] already published by node [/velodyne_nodelet_manager]`

How can I fix the transform tree so that the map frame publishes to the base_link frame, which has as one of its child frames the velodyne frame for the VLP-16? I tried to insert "" under the globalmap_server_nodelet and the localization_nodelet (not at the same time), however, that did not work.

Apologies for the lengthy message and hope my questions are well defined!

Thanks - Abed

pose of final graph optimization

hi @koide3

Thanks for sharing your great work here,
The topic /odom contains the pose of scan_matching (without the graph optimization). But how can we obtain the pose from the final graph optimization of each epoch?

best
welson

Map is rotated when enabling GPS

Hi @koide3,
I tested this package with both enable_gps and enable_imu_acc set to true, enable_imu_ori is set to false.
I notice that after a couple seconds, the map_frame is rotated 180 degrees relative to odom_frame. You can see it in this video: https://youtu.be/x0whgSeEg8I .
Is that behavior expected, e.g the map is rotated based on gps reading?

g2o version

Hi,
I tried to use the latest version of g2o, 4d23d59f52fe9ed08805bb9183bbf5d2bddfc782, but the definitions of Vector2D, Vector3D and Vector4D used by hdl_graph_slam were replaced by a templated type, VectorN (reference). I added back the type definitions required by this pkg, but got a memory leak when creating the optimizer. Hence, I could not run hdl_graph_slam_nodelet.

Fix
I fetched g2o commit a48ff8c42136f18fbe215b02bfeca48fa0c67507, built and ran the algorithm without any new incidences.

Hope this helps,
Yoshua

sometimes the optimization step will stuck

I've split the backend to a new project on windows to process my visual odometry data and GPS, this phenomenon remains.
So I think maybe the g2o is responsible for it.

CMake warning and Erros while launching

Is it expected to get this warning during CMake? or am i missing anything?

CMake Warning at ndt_omp/CMakeLists.txt:53 (add_executable):
  Cannot generate a safe linker search path for target align because files in
  some directories may conflict with libraries in implicit directories:

    link library [libpcl_kdtree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_search.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_features.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_sample_consensus.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_filters.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_ml.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_segmentation.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_surface.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_common.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_octree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_io.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib

  Some of these libraries may not be found correctly.


CMake Warning at hdl_graph_slam/CMakeLists.txt:90 (add_library):
  Cannot generate a safe linker search path for target
  scan_matching_odometry_nodelet because files in some directories may
  conflict with libraries in implicit directories:

    link library [libpcl_kdtree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_search.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_features.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_sample_consensus.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_filters.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_ml.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_segmentation.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_surface.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_common.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_octree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_io.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib

  Some of these libraries may not be found correctly.


CMake Warning at hdl_graph_slam/CMakeLists.txt:75 (add_library):
  Cannot generate a safe linker search path for target prefiltering_nodelet
  because files in some directories may conflict with libraries in implicit
  directories:

    link library [libpcl_kdtree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_search.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_features.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_sample_consensus.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_filters.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_ml.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_segmentation.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_surface.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_common.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_octree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_io.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib

  Some of these libraries may not be found correctly.


CMake Warning at hdl_graph_slam/CMakeLists.txt:82 (add_library):
  Cannot generate a safe linker search path for target
  floor_detection_nodelet because files in some directories may conflict with
  libraries in implicit directories:

    link library [libpcl_kdtree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_search.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_features.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_sample_consensus.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_filters.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_ml.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_segmentation.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_surface.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_common.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_octree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_io.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib

  Some of these libraries may not be found correctly.


CMake Warning at hdl_graph_slam/CMakeLists.txt:100 (add_library):
  Cannot generate a safe linker search path for target hdl_graph_slam_nodelet
  because files in some directories may conflict with libraries in implicit
  directories:

    link library [libpcl_kdtree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_search.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_features.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_sample_consensus.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_filters.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_ml.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_segmentation.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_surface.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_common.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_octree.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib
    link library [libpcl_io.so] in /usr/lib/x86_64-linux-gnu may be hidden by files in:
      /usr/local/lib

  Some of these libraries may not be found correctly.

Just like I expected, when I tried to launch, I got following error.


[ERROR] [1555302950.666921474]: Failed to load nodelet [/floor_detection_nodelet] of type [hdl_graph_slam/FloorDetectionNodelet] even after refreshing the cache: Failed to load library /home/aravinddoss/hhdl/devel/lib//libfloor_detection_nodelet.so. Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library (Poco exception = /home/aravinddoss/hhdl/devel/lib//libfloor_detection_nodelet.so: undefined symbol: _ZN3pcl25SampleConsensusModelPlaneINS_9PointXYZIEE24computeModelCoefficientsERKSt6vectorIiSaIiEERN5Eigen6MatrixIfLin1ELi1ELi0ELin1ELi1EEE)
[ERROR] [1555302950.666975082]: The error before refreshing the cache was: Failed to load library /home/aravinddoss/hhdl/devel/lib//libfloor_detection_nodelet.so. Make sure that you are calling the PLUGINLIB_EXPORT_CLASS macro in the library code, and that names are consistent between this macro and your XML. Error string: Could not load library (Poco exception = /home/aravinddoss/hhdl/devel/lib//libfloor_detection_nodelet.so: undefined symbol: _ZN3pcl25SampleConsensusModelPlaneINS_9PointXYZIEE24computeModelCoefficientsERKSt6vectorIiSaIiEERN5Eigen6MatrixIfLin1ELi1ELi0ELin1ELi1EEE)
[FATAL] [1555302950.667196565]: Failed to load nodelet '/floor_detection_nodelet` of type `hdl_graph_slam/FloorDetectionNodelet` to manager `velodyne_nodelet_manager'
[floor_detection_nodelet-5] process has died [pid 15140, exit code 255, cmd /opt/ros/melodic/lib/nodelet/nodelet load hdl_graph_slam/FloorDetectionNodelet velodyne_nodelet_manager __name:=floor_detection_nodelet __log:=/home/aravinddoss/.ros/log/ed2338da-5f37-11e9-b41d-34e6ad887d40/floor_detection_nodelet-5.log].
log file: /home/aravinddoss/.ros/log/ed2338da-5f37-11e9-b41d-34e6ad887d40/floor_detection_nodelet-5*.log

Am i missing anything?
I am using ROS Melodic, Ubuntu 18.04, Intel i7.
Thanks!

Failed to run the order for saving map

Hi,the following error occurs when I run "rosservice call /hdl_graph_slam/save_map "resolution: 0.05
destination: '/full_path_directory/map.pcd'"" of example 1 in my own PC.

ERROR: service [/hdl_graph_slam/save_map] responded with an error: : [pcl::PCDWriter::writeBinary] Error during open!

Please can you help me figure out this problem?
Thanks a lot!

[ERROR] I meet some error when I launch hdl_graph_slam_xx.launch

[FATAL] [1523523367.481760577]: Failed to load nodelet '/hdl_graph_slam_nodeletof typehdl_graph_slam/HdlGraphSlamNodeletto managervelodyne_nodelet_manager'
[FATAL] [1523523367.481761178]: Failed to load nodelet '/prefiltering_nodeletof typehdl_graph_slam/PrefilteringNodeletto managervelodyne_nodelet_manager'
[velodyne_nodelet_manager-2] process has died [pid 8412, exit code -6, cmd /opt/ros/kinetic/lib/nodelet/nodelet manager __name:=velodyne_nodelet_manager __log:=/home/shuai/.ros/log/56449ac8-3e2f-11e8-a312-d46a6a561f99/velodyne_nodelet_manager-2.log].
log file: /home/shuai/.ros/log/56449ac8-3e2f-11e8-a312-d46a6a561f99/velodyne_nodelet_manager-2*.log
[prefiltering_nodelet-3] process has died [pid 8413, exit code 255, cmd /opt/ros/kinetic/lib/nodelet/nodelet load hdl_graph_slam/PrefilteringNodelet velodyne_nodelet_manager __name:=prefiltering_nodelet __log:=/home/shuai/.ros/log/56449ac8-3e2f-11e8-a312-d46a6a561f99/prefiltering_nodelet-3.log].
log file: /home/shuai/.ros/log/56449ac8-3e2f-11e8-a312-d46a6a561f99/prefiltering_nodelet-3*.log
[hdl_graph_slam_nodelet-6] process has died [pid 8428, exit code 255, cmd /opt/ros/kinetic/lib/nodelet/nodelet load hdl_graph_slam/HdlGraphSlamNodelet velodyne_nodelet_manager __name:=hdl_graph_slam_nodelet __log:=/home/shuai/.ros/log/56449ac8-3e2f-11e8-a312-d46a6a561f99/hdl_graph_slam_nodelet-6.log].
log file: /home/shuai/.ros/log/56449ac8-3e2f-11e8-a312-d46a6a561f99/hdl_graph_slam_nodelet-6*.log

How could I solve it?
THx!

error in rviz

hi @koide3
when I run my own bag file, the tf transform between the odom and the keyframe/velodyne seems to have not been published. do you have any suggestion on this?
image

best
welson

loop closure issue

I used kitti dataset (kitti_2011_10_03_drive_0027_synced.bag), which is converted from .bin to .bag by kitti2bag.
firstly I use
`roslaunch hdl_graph_slam hdl_graph_slam_400.launch

roscd hdl_graph_slam/rviz
rviz -d hdl_graph_slam.rviz

rosbag play --clock kitti_2011_10_03_drive_0027_synced.bag
`
image

it showed only 4 poses. And hangs on.
In the launch terminal, it showed warning: TF_OLD_DATA ... according to authority unknown_publisher.

Warning: TF_OLD_DATA ignoring data from the past for frame base_link at time 1.31767e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
         at line 277 in /tmp/binarydeb/ros-kinetic-tf2-0.5.20/src/buffer_core.cpp
Warning: TF_OLD_DATA ignoring data from the past for frame velo_link at time 1.31767e+09 according to authority unknown_publisher
Possible reasons are listed at http://wiki.ros.org/tf/Errors%20explained
         at line 277 in /tmp/binarydeb/ros-kinetic-tf2-0.5.20/src/buffer_core.cpp

rosbag info : rosbag info kitti_2011_10_03_drive_0027_synced.bag

path:        kitti_2011_10_03_drive_0027_synced.bag
version:     2.0
duration:    7:50s (470s)
start:       Oct 03 2011 12:55:34.00 (1317671735.00)
end:         Oct 03 2011 13:03:25.83 (1317672205.83)
size:        24.0 GB
messages:    63616
compression: none [18184/18184 chunks]
types:       geometry_msgs/TwistStamped [98d34b0043a2093cf9d9345ab6eef12e]
             sensor_msgs/CameraInfo     [c9a58c1b0b154e0e6da7578cb991d214]
             sensor_msgs/Image          [060021388200f6f0f447d0fcd9c64743]
             sensor_msgs/Imu            [6a62c6daae103f4ff57a132d6f95cec2]
             sensor_msgs/NavSatFix      [2d3a8cd499b9b4a0249fb98fd05cfa48]
             sensor_msgs/PointCloud2    [1158d486dd51d683ce2f1be655c3c181]
             tf2_msgs/TFMessage         [94810edda583a504dfda3829e70d7eec]
topics:      /kitti/camera_color_left/camera_info    4544 msgs    : sensor_msgs/CameraInfo    
             /kitti/camera_color_left/image_raw      4544 msgs    : sensor_msgs/Image         
             /kitti/camera_color_right/camera_info   4544 msgs    : sensor_msgs/CameraInfo    
             /kitti/camera_color_right/image_raw     4544 msgs    : sensor_msgs/Image         
             /kitti/camera_gray_left/camera_info     4544 msgs    : sensor_msgs/CameraInfo    
             /kitti/camera_gray_left/image_raw       4544 msgs    : sensor_msgs/Image         
             /kitti/camera_gray_right/camera_info    4544 msgs    : sensor_msgs/CameraInfo    
             /kitti/camera_gray_right/image_raw      4544 msgs    : sensor_msgs/Image         
             /kitti/oxts/gps/fix                     4544 msgs    : sensor_msgs/NavSatFix     
             /kitti/oxts/gps/vel                     4544 msgs    : geometry_msgs/TwistStamped
             /kitti/oxts/imu                         4544 msgs    : sensor_msgs/Imu           
             /kitti/velo/pointcloud                  4544 msgs    : sensor_msgs/PointCloud2   
             /tf                                     4544 msgs    : tf2_msgs/TFMessage        
             /tf_static                              4544 msgs    : tf2_msgs/TFMessage

I figured it out this issue by using bag_player.py,
But there is a new issue about loop closure. the setting param showed below.
<!-- loop closure params --> <param name="distance_thresh" value="35" /> <param name="accum_distance_thresh" value="500.0" /> <param name="min_edge_interval" value="5.0" /> <param name="fitness_score_thresh" value="6.0" />
image

image
I always get the result showed above no matter which loop closure params I change. And as you can see it detected the loop, there were links between differen nodes(though it didn't matche well), but it didn't adjust the map to fit the loop.
Do you have any idea? Should I change the loop_closure_edge_robust_kernel to other kernels?
Any suggestions?
Thank you!

roslaunch hdl_graph_slam hdl_graph_slam.launch error

image
process[lidar2base_publisher-1]: started with pid [1290]
process[velodyne_laser1-2]: started with pid [1291]
process[velodyne_nodelet_manager-3]: started with pid [1298]
process[prefiltering_nodelet-4]: started with pid [1315]
process[scan_matching_odometry_nodelet-5]: started with pid [1328]
process[hdl_graph_slam_nodelet-6]: started with pid [1330]
process[map2odom_publisher-7]: started with pid [1350]
[ INFO] [1540203422.088669992]: Initializing nodelet with 12 worker threads.
downsample: VOXELGRID 0.1
outlier_removal: RADIUS 0.5 - 2
downsample: NONE
registration: NDT_OMP DIRECT7 1 (0 threads)
construct solver...

Using CHOLMOD poseDim -1 landMarkDim -1 blockordering 1

done
registration: NDT_OMP DIRECT7 1 (0 threads)
[velodyne_nodelet_manager-3] process has died [pid 1298, exit code -11, cmd /opt/ros/kinetic/lib/nodelet/nodelet manager __name:=velodyne_nodelet_manager __log:=/home/tong/.ros/log/985a32fa-d5e3-11e8-a625-80ce62f28ef3/velodyne_nodelet_manager-3.log].
log file: /home/tong/.ros/log/985a32fa-d5e3-11e8-a625-80ce62f28ef3/velodyne_nodelet_manager-3*.log
[prefiltering_nodelet-4] process has finished cleanly
log file: /home/tong/.ros/log/985a32fa-d5e3-11e8-a625-80ce62f28ef3/prefiltering_nodelet-4*.log
[scan_matching_odometry_nodelet-5] process has finished cleanly
log file: /home/tong/.ros/log/985a32fa-d5e3-11e8-a625-80ce62f28ef3/scan_matching_odometry_nodelet-5*.log
[hdl_graph_slam_nodelet-6] process has finished cleanly
log file: /home/tong/.ros/log/985a32fa-d5e3-11e8-a625-80ce62f28ef3/hdl_graph_slam_nodelet-6*.log
^C[map2odom_publisher-7] killing on exit
[lidar2base_publisher-1] killing on exit
[velodyne_laser1-2] killing on exit
^

why some locations are sparse in new pointcloud map

@koide3
I have a question to ask, the following picture is the effect of my test with hdl_graph_slam. Above is the g2o graph, below is the laser point cloud map, the red circle indicates the corresponding position of the two maps, I don't understand what caused the position g2o map is very sparse. The point cloud map is also very sparse. Can you give me some advice?
image

Depend ndt_omp not listed in package.xml

Hi,
First of all, great work! Thank you for sharing and maintaining this project.

I tried to build it locally, and found that the build order is not correct. Specifically, when I run catkin build --dry-run, I get:

[build] Found '3' packages in 0.0 seconds.                                                                                                                                                                                                                                    
Packages to be built:
- hdl_graph_slam   (catkin)
- ndt_omp          (catkin)
- hdl_localization (catkin)
Total packages: 3

But, as ndt_omp is a dependency of hdl_graph_slam and hdl_localization, the order should actually be:

[build] Found '3' packages in 0.0 seconds.                                                                                                                                                                                                                                    
Packages to be built:
- ndt_omp          (catkin)
- hdl_graph_slam   (catkin)
- hdl_localization (catkin)
Total packages: 3

This can be easily fixed by adding the tags

  • <build_depend>ndt_omp</build_depend>
  • <run_depend>ndt_omp</run_depend>

to package.xml. I thought about making a pull request but thought this is a really tiny detail.

Failed to load nodelet

Hi,

I have installed the package correctly on ROS kinetic following the guide. g2o was also installed without error. I also have velodyne drivers sourced installed inside the catkin_ws. When I try to launch any file through the package, I am getting the following errors. I am not sure why it is not able to find the velodyne nodelet manager. Any suggestions would be helpful. Thanks

[FATAL] [1527575498.004853517]: Failed to load nodelet '/hdl_graph_slam_nodelet` of type `hdl_graph_slam/HdlGraphSlamNodelet` to manager `velodyne_nodelet_manager'
[FATAL] [1527575498.004870101]: Failed to load nodelet '/prefiltering_nodelet` of type `hdl_graph_slam/PrefilteringNodelet` to manager `velodyne_nodelet_manager'
[FATAL] [1527575498.004927881]: Failed to load nodelet '/scan_matching_odometry_nodelet` of type `hdl_graph_slam/ScanMatchingOdometryNodelet` to manager `velodyne_nodelet_manager'

hdl_graph_slam hdl_graph_slam_xxx.launch FAILED

Hi guys,

I got this error when I tried to launch the "hdl_graph_slam_xxx.launch" files (on both 400 and 501 bags, the g2o version is the one mentioned on the README file)


Using CSparse poseDim -1 landMarkDim -1 blockordering 0

*** Error in /opt/ros/kinetic/lib/nodelet/nodelet': free(): invalid next size (fast): 0x0000000001ea6c50 *** ======= Backtrace: ========= /lib/x86_64-linux-gnu/libc.so.6(+0x777e5)[0x7f8f66fa97e5] /lib/x86_64-linux-gnu/libc.so.6(+0x8037a)[0x7f8f66fb237a] /lib/x86_64-linux-gnu/libc.so.6(cfree+0x4c)[0x7f8f66fb653c] /opt/ros/kinetic/lib/libroscpp.so(_ZNK3ros10NodeHandle11resolveNameERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEbNS0_11no_validateE+0xa3)[0x7f8f68413a73] /opt/ros/kinetic/lib/libroscpp.so(_ZNK3ros10NodeHandle11resolveNameERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEb+0x6b)[0x7f8f68413d0b] /opt/ros/kinetic/lib/libroscpp.so(_ZNK3ros10NodeHandle8hasParamERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEE+0x2c)[0x7f8f684146dc] /home/z/iliad_ws/devel/lib//libhdl_graph_slam_nodelet.so(_ZNK3ros10NodeHandle5paramIdEEbRKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERT_RKSA_+0x1b)[0x7f8f400c295b] /home/z/iliad_ws/devel/lib//libhdl_graph_slam_nodelet.so(_ZN14hdl_graph_slam19HdlGraphSlamNodelet6onInitEv+0x47b)[0x7f8f400eb8eb] /opt/ros/kinetic/lib/libnodeletlib.so(_ZN7nodelet7Nodelet4initERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKSt3mapIS6_S6_St4lessIS6_ESaISt4pairIS7_S6_EEERKSt6vectorIS6_SaIS6_EEPN3ros22CallbackQueueInterfaceESP_+0x39e)[0x7f8f68b1623e] /opt/ros/kinetic/lib/libnodeletlib.so(_ZN7nodelet6Loader4loadERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEES8_RKSt3mapIS6_S6_St4lessIS6_ESaISt4pairIS7_S6_EEERKSt6vectorIS6_SaIS6_EE+0x3a2)[0x7f8f68b183c2] /opt/ros/kinetic/lib/libnodeletlib.so(_ZN7nodelet9LoaderROS11serviceLoadERNS_19NodeletLoadRequest_ISaIvEEERNS_20NodeletLoadResponse_IS2_EE+0x110)[0x7f8f68b26750] /opt/ros/kinetic/lib/libnodeletlib.so(_ZN3ros22ServiceCallbackHelperTINS_11ServiceSpecIN7nodelet19NodeletLoadRequest_ISaIvEEENS2_20NodeletLoadResponse_IS4_EEEEE4callERNS_31ServiceCallbackHelperCallParamsE+0x707)[0x7f8f68b2f1f7] /opt/ros/kinetic/lib/libroscpp.so(_ZN3ros15ServiceCallback4callEv+0x241)[0x7f8f683b0351] /opt/ros/kinetic/lib/libroscpp.so(_ZN3ros13CallbackQueue9callOneCBEPNS0_3TLSE+0x4b8)[0x7f8f684046f8] /opt/ros/kinetic/lib/libroscpp.so(_ZN3ros13CallbackQueue13callAvailableENS_12WallDurationE+0x54b)[0x7f8f684060fb] /opt/ros/kinetic/lib/libroscpp.so(_ZN3ros21SingleThreadedSpinner4spinEPNS_13CallbackQueueE+0x2a9)[0x7f8f68462ef9] /opt/ros/kinetic/lib/libroscpp.so(_ZN3ros4spinEv+0x2b)[0x7f8f68447edb] /opt/ros/kinetic/lib/nodelet/nodelet(main+0x1e7)[0x405127] /lib/x86_64-linux-gnu/libc.so.6(__libc_start_main+0xf0)[0x7f8f66f52830] /opt/ros/kinetic/lib/nodelet/nodelet(_start+0x29)[0x406449] ======= Memory map: ======== 00400000-0040e000 r-xp 00000000 103:02 47320383 /opt/ros/kinetic/lib/nodelet/nodelet 0060d000-0060e000 r--p 0000d000 103:02 47320383 /opt/ros/kinetic/lib/nodelet/nodelet 0060e000-0060f000 rw-p 0000e000 103:02 47320383 /opt/ros/kinetic/lib/nodelet/nodelet 01b57000-0224b000 rw-p 00000000 00:00 0 [heap] 7f8f30000000-7f8f30021000 rw-p 00000000 00:00 0 7f8f30021000-7f8f34000000 ---p 00000000 00:00 0 7f8f3522a000-7f8f35233000 r-xp 00000000 103:02 11543024 /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1 7f8f35233000-7f8f35432000 ---p 00009000 103:02 11543024 /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1 7f8f35432000-7f8f35433000 r--p 00008000 103:02 11543024 /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1 7f8f35433000-7f8f35434000 rw-p 00009000 103:02 11543024 /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1 7f8f35434000-7f8f3543e000 r-xp 00000000 103:02 11540753 /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0 7f8f3543e000-7f8f3563d000 ---p 0000a000 103:02 11540753 /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0 7f8f3563d000-7f8f3563e000 r--p 00009000 103:02 11540753 /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0 7f8f3563e000-7f8f3563f000 rw-p 0000a000 103:02 11540753 /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0 7f8f3563f000-7f8f35644000 r-xp 00000000 103:02 11542241 /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0 7f8f35644000-7f8f35843000 ---p 00005000 103:02 11542241 /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0 7f8f35843000-7f8f35844000 r--p 00004000 103:02 11542241 /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0 7f8f35844000-7f8f35845000 rw-p 00005000 103:02 11542241 /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0 7f8f35845000-7f8f35847000 r-xp 00000000 103:02 11542230 /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0 7f8f35847000-7f8f35a47000 ---p 00002000 103:02 11542230 /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0 7f8f35a47000-7f8f35a48000 r--p 00002000 103:02 11542230 /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0 7f8f35a48000-7f8f35a49000 rw-p 00003000 103:02 11542230 /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0 7f8f35a49000-7f8f35a82000 r-xp 00000000 103:02 11548756 /usr/lib/x86_64-linux-gnu/libhwloc.so.5.6.8 7f8f35a82000-7f8f35c81000 ---p 00039000 103:02 11548756 /usr/lib/x86_64-linux-gnu/libhwloc.so.5.6.8 7f8f35c81000-7f8f35c82000 r--p 00038000 103:02 11548756 /usr/lib/x86_64-linux-gnu/libhwloc.so.5.6.8 7f8f35c82000-7f8f35c83000 rw-p 00039000 103:02 11548756 /usr/lib/x86_64-linux-gnu/libhwloc.so.5.6.8 7f8f35c83000-7f8f35ca4000 r-xp 00000000 103:02 11543648 /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0 7f8f35ca4000-7f8f35ea3000 ---p 00021000 103:02 11543648 /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0 7f8f35ea3000-7f8f35ea4000 r--p 00020000 103:02 11543648 /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0 7f8f35ea4000-7f8f35ea5000 rw-p 00021000 103:02 11543648 /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0 7f8f35ea5000-7f8f35eb0000 r-xp 00000000 103:02 11542978 /usr/lib/x86_64-linux-gnu/libjbig.so.0 7f8f35eb0000-7f8f360af000 ---p 0000b000 103:02 11542978 /usr/lib/x86_64-linux-gnu/libjbig.so.0 7f8f360af000-7f8f360b0000 r--p 0000a000 103:02 11542978 /usr/lib/x86_64-linux-gnu/libjbig.so.0 7f8f360b0000-7f8f360b3000 rw-p 0000b000 103:02 11542978 /usr/lib/x86_64-linux-gnu/libjbig.so.0 7f8f360b3000-7f8f360d4000 r-xp 00000000 103:02 48894453 /lib/x86_64-linux-gnu/liblzma.so.5.0.0 7f8f360d4000-7f8f362d3000 ---p 00021000 103:02 48894453 /lib/x86_64-linux-gnu/liblzma.so.5.0.0 7f8f362d3000-7f8f362d4000 r--p 00020000 103:02 48894453 /lib/x86_64-linux-gnu/liblzma.so.5.0.0 7f8f362d4000-7f8f362d5000 rw-p 00021000 103:02 48894453 /lib/x86_64-linux-gnu/liblzma.so.5.0.0 7f8f362d5000-7f8f36365000 r-xp 00000000 103:02 11548784 /usr/lib/openmpi/lib/libopen-pal.so.13.0.2 7f8f36365000-7f8f36565000 ---p 00090000 103:02 11548784 /usr/lib/openmpi/lib/libopen-pal.so.13.0.2 7f8f36565000-7f8f36569000 r--p 00090000 103:02 11548784 /usr/lib/openmpi/lib/libopen-pal.so.13.0.2 7f8f36569000-7f8f3656d000 rw-p 00094000 103:02 11548784 /usr/lib/openmpi/lib/libopen-pal.so.13.0.2 7f8f3656d000-7f8f36572000 rw-p 00000000 00:00 0 7f8f36572000-7f8f365e7000 r-xp 00000000 103:02 11548780 /usr/lib/openmpi/lib/libopen-rte.so.12.0.2 7f8f365e7000-7f8f367e6000 ---p 00075000 103:02 11548780 /usr/lib/openmpi/lib/libopen-rte.so.12.0.2 7f8f367e6000-7f8f367e7000 r--p 00074000 103:02 11548780 /usr/lib/openmpi/lib/libopen-rte.so.12.0.2 7f8f367e7000-7f8f367ea000 rw-p 00075000 103:02 11548780 /usr/lib/openmpi/lib/libopen-rte.so.12.0.2 7f8f367ea000-7f8f367ec000 rw-p 00000000 00:00 0 7f8f367ec000-7f8f367f9000 r-xp 00000000 103:02 11548763 /usr/lib/libibverbs.so.1.0.0 7f8f367f9000-7f8f369f9000 ---p 0000d000 103:02 11548763 /usr/lib/libibverbs.so.1.0.0 7f8f369f9000-7f8f369fa000 r--p 0000d000 103:02 11548763 /usr/lib/libibverbs.so.1.0.0 7f8f369fa000-7f8f369fb000 rw-p 0000e000 103:02 11548763 /usr/lib/libibverbs.so.1.0.0 7f8f369fb000-7f8f36a0c000 r-xp 00000000 103:02 11542243 /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0 7f8f36a0c000-7f8f36c0b000 ---p 00011000 103:02 11542243 /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0 7f8f36c0b000-7f8f36c0c000 r--p 00010000 103:02 11542243 /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0 7f8f36c0c000-7f8f36c0d000 rw-p 00011000 103:02 11542243 /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0 7f8f36c0d000-7f8f36d42000 r-xp 00000000 103:02 11542226 /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0 7f8f36d42000-7f8f36f42000 ---p 00135000 103:02 11542226 /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0 7f8f36f42000-7f8f36f43000 r--p 00135000 103:02 11542226 /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0 7f8f36f43000-7f8f36f47000 rw-p 00136000 103:02 11542226 /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0 7f8f36f47000-7f8f383e5000 r-xp 00000000 103:02 11670603 /usr/lib/nvidia-384/libnvidia-glcore.so.384.111 7f8f383e5000-7f8f38406000 rwxp 0149e000 103:02 11670603 /usr/lib/nvidia-384/libnvidia-glcore.so.384.111 7f8f38406000-7f8f387e8000 r-xp 014bf000 103:02 11670603 /usr/lib/nvidia-384/libnvidia-glcore.so.384.111 7f8f387e8000-7f8f389e8000 ---p 018a1000 103:02 11670603 /usr/lib/nvidia-384/libnvidia-glcore.so.384.111 7f8f389e8000-7f8f38deb000 rw-p 018a1000 103:02 11670603 /usr/lib/nvidia-384/libnvidia-glcore.so.384.111 7f8f38deb000-7f8f38e04000 rw-p 00000000 00:00 0 7f8f38e04000-7f8f38e07000 r-xp 00000000 103:02 11670568 /usr/lib/nvidia-384/tls/libnvidia-tls.so.384.111 7f8f38e07000-7f8f39007000 ---p 00003000 103:02 11670568 /usr/lib/nvidia-384/tls/libnvidia-tls.so.384.111 7f8f39007000-7f8f39008000 rw-p 00003000 103:02 11670568 /usr/lib/nvidia-384/tls/libnvidia-tls.so.384.111 7f8f39008000-7f8f39075000 r-xp 00000000 103:02 11542086 /usr/lib/x86_64-linux-gnu/libGLU.so.1.3.1 7f8f39075000-7f8f39275000 ---p 0006d000 103:02 11542086 /usr/lib/x86_64-linux-gnu/libGLU.so.1.3.1 7f8f39275000-7f8f39276000 r--p 0006d000 103:02 11542086 /usr/lib/x86_64-linux-gnu/libGLU.so.1.3.1 7f8f39276000-7f8f39277000 rw-p 0006e000 103:02 11542086 /usr/lib/x86_64-linux-gnu/libGLU.so.1.3.1 7f8f39277000-7f8f3928e000 r-xp 00000000 103:02 11549715 /usr/lib/x86_64-linux-gnu/libvtkDICOMParser-6.2.so.6.2.0 7f8f3928e000-7f8f3948d000 ---p 00017000 103:02 11549715 /usr/lib/x86_64-linux-gnu/libvtkDICOMParser-6.2.so.6.2.0 7f8f3948d000-7f8f3948e000 r--p 00016000 103:02 11549715 /usr/lib/x86_64-linux-gnu/libvtkDICOMParser-6.2.so.6.2.0 7f8f3948e000-7f8f3948f000 rw-p 00017000 103:02 11549715 /usr/lib/x86_64-linux-gnu/libvtkDICOMParser-6.2.so.6.2.0 7f8f3948f000-7f8f39521000 r-xp 00000000 103:02 11549911 /usr/lib/x86_64-linux-gnu/libvtkmetaio-6.2.so.6.2.0 7f8f39521000-7f8f39720000 ---p 00092000 103:02 11549911 /usr/lib/x86_64-linux-gnu/libvtkmetaio-6.2.so.6.2.0 7f8f39720000-7f8f39722000 r--p 00091000 103:02 11549911 /usr/lib/x86_64-linux-gnu/libvtkmetaio-6.2.so.6.2.0 7f8f39722000-7f8f39724000 rw-p 00093000 103:02 11549911 /usr/lib/x86_64-linux-gnu/libvtkmetaio-6.2.so.6.2.0 7f8f39724000-7f8f39795000 r-xp 00000000 103:02 11534651 /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4 7f8f39795000-7f8f39994000 ---p 00071000 103:02 11534651 /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4 7f8f39994000-7f8f39995000 r--p 00070000 103:02 11534651 /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4 7f8f39995000-7f8f39998000 rw-p 00071000 103:02 11534651 /usr/lib/x86_64-linux-gnu/libtiff.so.5.2.4 7f8f39998000-7f8f399ef000 r-xp 00000000 103:02 11542982 /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2 7f8f399ef000-7f8f39bef000 ---p 00057000 103:02 11542982 /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2 7f8f39bef000-7f8f39bf0000 r--p 00057000 103:02 11542982 /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2 7f8f39bf0000-7f8f39bf1000 rw-p 00058000 103:02 11542982 /usr/lib/x86_64-linux-gnu/libjpeg.so.8.0.2 7f8f39bf1000-7f8f39c11000 r-xp 00000000 103:02 11549737 /usr/lib/x86_64-linux-gnu/libvtkCommonMath-6.2.so.6.2.0 7f8f39c11000-7f8f39e11000 ---p 00020000 103:02 11549737 /usr/lib/x86_64-linux-gnu/libvtkCommonMath-6.2.so.6.2.0 7f8f39e11000-7f8f39e12000 r--p 00020000 103:02 11549737 /usr/lib/x86_64-linux-gnu/libvtkCommonMath-6.2.so.6.2.0 7f8f39e12000-7f8f39e13000 rw-p 00021000 103:02 11549737 /usr/lib/x86_64-linux-gnu/libvtkCommonMath-6.2.so.6.2.0 7f8f39e13000-7f8f39e24000 r-xp 00000000 103:02 11549659 /usr/lib/x86_64-linux-gnu/libvtkCommonSystem-6.2.so.6.2.0 7f8f39e24000-7f8f3a024000 ---p 00011000 103:02 11549659 /usr/lib/x86_64-linux-gnu/libvtkCommonSystem-6.2.so.6.2.0 7f8f3a024000-7f8f3a025000 r--p 00011000 103:02 11549659 /usr/lib/x86_64-linux-gnu/libvtkCommonSystem-6.2.so.6.2.0 7f8f3a025000-7f8f3a026000 rw-p 00012000 103:02 11549659 /usr/lib/x86_64-linux-gnu/libvtkCommonSystem-6.2.so.6.2.0 7f8f3a026000-7f8f3a027000 rw-p 00000000 00:00 0 7f8f3a027000-7f8f3a057000 r-xp 00000000 103:02 11546033 /usr/lib/x86_64-linux-gnu/libjsoncpp.so.1.7.2 7f8f3a057000-7f8f3a256000 ---p 00030000 103:02 11546033 /usr/lib/x86_64-linux-gnu/libjsoncpp.so.1.7.2 7f8f3a256000-7f8f3a257000 r--p 0002f000 103:02 11546033 /usr/lib/x86_64-linux-gnu/libjsoncpp.so.1.7.2 7f8f3a257000-7f8f3a258000 rw-p 00030000 103:02 11546033 /usr/lib/x86_64-linux-gnu/libjsoncpp.so.1.7.2 7f8f3a258000-7f8f3a284000 r-xp 00000000 103:02 11549700 /usr/lib/x86_64-linux-gnu/libvtkCommonTransforms-6.2.so.6.2.0 7f8f3a284000-7f8f3a484000 ---p 0002c000 103:02 11549700 /usr/lib/x86_64-linux-gnu/libvtkCommonTransforms-6.2.so.6.2.0 7f8f3a484000-7f8f3a486000 r--p 0002c000 103:02 11549700 /usr/lib/x86_64-linux-gnu/libvtkCommonTransforms-6.2.so.6.2.0 7f8f3a486000-7f8f3a487000 rw-p 0002e000 103:02 11549700 /usr/lib/x86_64-linux-gnu/libvtkCommonTransforms-6.2.so.6.2.0 7f8f3a487000-7f8f3a4aa000 r-xp 00000000 103:02 11549671 /usr/lib/x86_64-linux-gnu/libvtkParallelMPI-6.2.so.6.2.0 7f8f3a4aa000-7f8f3a6a9000 ---p 00023000 103:02 11549671 /usr/lib/x86_64-linux-gnu/libvtkParallelMPI-6.2.so.6.2.0 7f8f3a6a9000-7f8f3a6ab000 r--p 00022000 103:02 11549671 /usr/lib/x86_64-linux-gnu/libvtkParallelMPI-6.2.so.6.2.0 7f8f3a6ab000-7f8f3a6ac000 rw-p 00024000 103:02 11549671 /usr/lib/x86_64-linux-gnu/libvtkParallelMPI-6.2.so.6.2.0 7f8f3a6ac000-7f8f3a6ee000 r-xp 00000000 103:02 11549732 /usr/lib/x86_64-linux-gnu/libvtksys-6.2.so.6.2.0 7f8f3a6ee000-7f8f3a8ee000 ---p 00042000 103:02 11549732 /usr/lib/x86_64-linux-gnu/libvtksys-6.2.so.6.2.0 7f8f3a8ee000-7f8f3a8ef000 r--p 00042000 103:02 11549732 /usr/lib/x86_64-linux-gnu/libvtksys-6.2.so.6.2.0 7f8f3a8ef000-7f8f3a8f0000 rw-p 00043000 103:02 11549732 /usr/lib/x86_64-linux-gnu/libvtksys-6.2.so.6.2.0 7f8f3a8f0000-7f8f3a8f1000 rw-p 00000000 00:00 0 7f8f3a8f1000-7f8f3a93e000 r-xp 00000000 103:02 11549937 /usr/lib/x86_64-linux-gnu/libvtkParallelCore-6.2.so.6.2.0 7f8f3a93e000-7f8f3ab3d000 ---p 0004d000 103:02 11549937 /usr/lib/x86_64-linux-gnu/libvtkParallelCore-6.2.so.6.2.0 7f8f3ab3d000-7f8f3ab3f000 r--p 0004c000 103:02 11549937 /usr/lib/x86_64-linux-gnu/libvtkParallelCore-6.2.so.6.2.0 7f8f3ab3f000-7f8f3ab40000 rw-p 0004e000 103:02 11549937 /usr/lib/x86_64-linux-gnu/libvtkParallelCore-6.2.so.6.2.0 7f8f3ab40000-7f8f3ab58000 r-xp 00000000 103:02 11548768 /usr/lib/openmpi/lib/libmpi_cxx.so.1.1.3 7f8f3ab58000-7f8f3ad58000 ---p 00018000 103:02 11548768 /usr/lib/openmpi/lib/libmpi_cxx.so.1.1.3 7f8f3ad58000-7f8f3ad5a000 r--p 00018000 103:02 11548768 /usr/lib/openmpi/lib/libmpi_cxx.so.1.1.3 7f8f3ad5a000-7f8f3ad5b000 rw-p 0001a000 103:02 11548768 /usr/lib/openmpi/lib/libmpi_cxx.so.1.1.3 7f8f3ad5b000-7f8f3ae0d000 r-xp 00000000 103:02 11548777 /usr/lib/openmpi/lib/libmpi.so.12.0.2 7f8f3ae0d000-7f8f3b00d000 ---p 000b2000 103:02 11548777 /usr/lib/openmpi/lib/libmpi.so.12.0.2 7f8f3b00d000-7f8f3b00e000 r--p 000b2000 103:02 11548777 /usr/lib/openmpi/lib/libmpi.so.12.0.2 7f8f3b00e000-7f8f3b01e000 rw-p 000b3000 103:02 11548777 /usr/lib/openmpi/lib/libmpi.so.12.0.2 7f8f3b01e000-7f8f3b031000 rw-p 00000000 00:00 0 7f8f3b031000-7f8f3b046000 r-xp 00000000 103:02 11549630 /usr/lib/x86_64-linux-gnu/libvtkCommonMisc-6.2.so.6.2.0 7f8f3b046000-7f8f3b245000 ---p 00015000 103:02 11549630 /usr/lib/x86_64-linux-gnu/libvtkCommonMisc-6.2.so.6.2.0 7f8f3b245000-7f8f3b246000 r--p 00014000 103:02 11549630 /usr/lib/x86_64-linux-gnu/libvtkCommonMisc-6.2.so.6.2.0 7f8f3b246000-7f8f3b247000 rw-p 00015000 103:02 11549630 /usr/lib/x86_64-linux-gnu/libvtkCommonMisc-6.2.so.6.2.0 7f8f3b247000-7f8f3b256000 r-xp 00000000 103:02 48894385 /lib/x86_64-linux-gnu/libbz2.so.1.0.4 7f8f3b256000-7f8f3b455000 ---p 0000f000 103:02 48894385 /lib/x86_64-linux-gnu/libbz2.so.1.0.4 7f8f3b455000-7f8f3b456000 r--p 0000e000 103:02 48894385 /lib/x86_64-linux-gnu/libbz2.so.1.0.4 7f8f3b456000-7f8f3b457000 rw-p 0000f000 103:02 48894385 /lib/x86_64-linux-gnu/libbz2.so.1.0.4 7f8f3b457000-7f8f3b522000 r-xp 00000000 103:02 11670590 /usr/lib/nvidia-384/libGL.so.384.111 7f8f3b522000-7f8f3b556000 rwxp 000cb000 103:02 11670590 /usr/lib/nvidia-384/libGL.so.384.111 7f8f3b556000-7f8f3b56a000 r-xp 000ff000 103:02 11670590 /usr/lib/nvidia-384/libGL.so.384.111 7f8f3b56a000-7f8f3b769000 ---p 00113000 103:02 11670590 /usr/lib/nvidia-384/libGL.so.384.111 7f8f3b769000-7f8f3b792000 rw-p 00112000 103:02 11670590 /usr/lib/nvidia-384/libGL.so.384.111 7f8f3b792000-7f8f3b799000 rw-p 00000000 00:00 0 7f8f3b799000-7f8f3b79c000 r-xp 00000000 103:02 12068924 /usr/local/lib/libg2o_opengl_helper.so 7f8f3b79c000-7f8f3b99c000 ---p 00003000 103:02 12068924 /usr/local/lib/libg2o_opengl_helper.so 7f8f3b99c000-7f8f3b99d000 r--p 00003000 103:02 12068924 /usr/local/lib/libg2o_opengl_helper.so 7f8f3b99d000-7f8f3b99e000 rw-p 00004000 103:02 12068924 /usr/local/lib/libg2o_opengl_helper.so 7f8f3b99e000-7f8f3b9ab000 r-xp 00000000 103:02 12068920 /usr/local/lib/libg2o_ext_csparse.so 7f8f3b9ab000-7f8f3bbaa000 ---p 0000d000 103:02 12068920 /usr/local/lib/libg2o_ext_csparse.so 7f8f3bbaa000-7f8f3bbab000 r--p 0000c000 103:02 12068920 /usr/local/lib/libg2o_ext_csparse.so 7f8f3bbab000-7f8f3bbac000 rw-p 0000d000 103:02 12068920 /usr/local/lib/libg2o_ext_csparse.so 7f8f3bbac000-7f8f3bbb1000 r-xp 00000000 103:02 12068945 /usr/local/lib/libg2o_csparse_extension.so 7f8f3bbb1000-7f8f3bdb0000 ---p 00005000 103:02 12068945 /usr/local/lib/libg2o_csparse_extension.so 7f8f3bdb0000-7f8f3bdb1000 r--p 00004000 103:02 12068945 /usr/local/lib/libg2o_csparse_extension.so 7f8f3bdb1000-7f8f3bdb2000 rw-p 00005000 103:02 12068945 /usr/local/lib/libg2o_csparse_extension.so 7f8f3bdb2000-7f8f3bdce000 r-xp 00000000 103:02 12068923 /usr/local/lib/libg2o_stuff.so 7f8f3bdce000-7f8f3bfcd000 ---p 0001c000 103:02 12068923 /usr/local/lib/libg2o_stuff.so 7f8f3bfcd000-7f8f3bfce000 r--p 0001b000 103:02 12068923 /usr/local/lib/libg2o_stuff.so 7f8f3bfce000-7f8f3bfcf000 rw-p 0001c000 103:02 12068923 /usr/local/lib/libg2o_stuff.so 7f8f3bfcf000-7f8f3bfd0000 rw-p 00000000 00:00 0 7f8f3bfd0000-7f8f3c2de000 r-xp 00000000 103:02 11549804 /usr/lib/x86_64-linux-gnu/libvtkCommonCore-6.2.so.6.2.0 7f8f3c2de000-7f8f3c4de000 ---p 0030e000 103:02 11549804 /usr/lib/x86_64-linux-gnu/libvtkCommonCore-6.2.so.6.2.0 7f8f3c4de000-7f8f3c4f6000 r--p 0030e000 103:02 11549804 /usr/lib/x86_64-linux-gnu/libvtkCommonCore-6.2.so.6.2.0 7f8f3c4f6000-7f8f3c4fd000 rw-p 00326000 103:02 11549804 /usr/lib/x86_64-linux-gnu/libvtkCommonCore-6.2.so.6.2.0 7f8f3c4fd000-7f8f3c4fe000 rw-p 00000000 00:00 0 7f8f3c4fe000-7f8f3c84a000 r-xp 00000000 103:02 11549809 /usr/lib/x86_64-linux-gnu/libvtkCommonDataModel-6.2.so.6.2.0 7f8f3c84a000-7f8f3ca49000 ---p 0034c000 103:02 11549809 /usr/lib/x86_64-linux-gnu/libvtkCommonDataModel-6.2.so.6.2.0 7f8f3ca49000-7f8f3ca5e000 r--p 0034b000 103:02 11549809 /usr/lib/x86_64-linux-gnu/libvtkCommonDataModel-6.2.so.6.2.0 7f8f3ca5e000-7f8f3ca6d000 rw-p 00360000 103:02 11549809 /usr/lib/x86_64-linux-gnu/libvtkCommonDataModel-6.2.so.6.2.0 7f8f3ca6d000-7f8f3cb11000 r-xp 00000000 103:02 11549849 /usr/lib/x86_64-linux-gnu/libvtkCommonExecutionModel-6.2.so.6.2.0 7f8f3cb11000-7f8f3cd10000 ---p 000a4000 103:02 11549849 /usr/lib/x86_64-linux-gnu/libvtkCommonExecutionModel-6.2.so.6.2.0 7f8f3cd10000-7f8f3cd19000 r--p 000a3000 103:02 11549849 /usr/lib/x86_64-linux-gnu/libvtkCommonExecutionModel-6.2.so.6.2.0 7f8f3cd19000-7f8f3cd1b000 rw-p 000ac000 103:02 11549849 /usr/lib/x86_64-linux-gnu/libvtkCommonExecutionModel-6.2.so.6.2.0 7f8f3cd1b000-7f8f3cd8c000 r-xp 00000000 103:02 11549888 /usr/lib/x86_64-linux-gnu/libvtkIOCore-6.2.so.6.2.0 7f8f3cd8c000-7f8f3cf8c000 ---p 00071000 103:02 11549888 /usr/lib/x86_64-linux-gnu/libvtkIOCore-6.2.so.6.2.0 7f8f3cf8c000-7f8f3cf90000 r--p 00071000 103:02 11549888 /usr/lib/x86_64-linux-gnu/libvtkIOCore-6.2.so.6.2.0 7f8f3cf90000-7f8f3cf91000 rw-p 00075000 103:02 11549888 /usr/lib/x86_64-linux-gnu/libvtkIOCore-6.2.so.6.2.0 7f8f3cf91000-7f8f3cf92000 rw-p 00000000 00:00 0 7f8f3cf92000-7f8f3d0ef000 r-xp 00000000 103:02 11549795 /usr/lib/x86_64-linux-gnu/libvtkIOImage-6.2.so.6.2.0 7f8f3d0ef000-7f8f3d2ee000 ---p 0015d000 103:02 11549795 /usr/lib/x86_64-linux-gnu/libvtkIOImage-6.2.so.6.2.0 7f8f3d2ee000-7f8f3d2f7000 r--p 0015c000 103:02 11549795 /usr/lib/x86_64-linux-gnu/libvtkIOImage-6.2.so.6.2.0 7f8f3d2f7000-7f8f3d2f9000 rw-p 00165000 103:02 11549795 /usr/lib/x86_64-linux-gnu/libvtkIOImage-6.2.so.6.2.0 7f8f3d2f9000-7f8f3d399000 r-xp 00000000 103:02 11549731 /usr/lib/x86_64-linux-gnu/libvtkIOLegacy-6.2.so.6.2.0 7f8f3d399000-7f8f3d599000 ---p 000a0000 103:02 11549731 /usr/lib/x86_64-linux-gnu/libvtkIOLegacy-6.2.so.6.2.0 7f8f3d599000-7f8f3d5a0000 r--p 000a0000 103:02 11549731 /usr/lib/x86_64-linux-gnu/libvtkIOLegacy-6.2.so.6.2.0 7f8f3d5a0000-7f8f3d5a2000 rw-p 000a7000 103:02 11549731 /usr/lib/x86_64-linux-gnu/libvtkIOLegacy-6.2.so.6.2.0 7f8f3d5a2000-7f8f3d775000 r-xp 00000000 103:02 11549673 /usr/lib/x86_64-linux-gnu/libvtkImagingCore-6.2.so.6.2.0 7f8f3d775000-7f8f3d974000 ---p 001d3000 103:02 11549673 /usr/lib/x86_64-linux-gnu/libvtkImagingCore-6.2.so.6.2.0 7f8f3d974000-7f8f3d97d000 r--p 001d2000 103:02 11549673 /usr/lib/x86_64-linux-gnu/libvtkImagingCore-6.2.so.6.2.0 7f8f3d97d000-7f8f3d97f000 rw-p 001db000 103:02 11549673 /usr/lib/x86_64-linux-gnu/libvtkImagingCore-6.2.so.6.2.0 7f8f3d97f000-7f8f3dabf000 r-xp 00000000 103:02 11549901 /usr/lib/x86_64-linux-gnu/libvtkIOGeometry-6.2.so.6.2.0 7f8f3dabf000-7f8f3dcbe000 ---p 00140000 103:02 11549901 /usr/lib/x86_64-linux-gnu/libvtkIOGeometry-6.2.so.6.2.0 7f8f3dcbe000-7f8f3dcc4000 r--p 0013f000 103:02 11549901 /usr/lib/x86_64-linux-gnu/libvtkIOGeometry-6.2.so.6.2.0 7f8f3dcc4000-7f8f3dcc7000 rw-p 00145000 103:02 11549901 /usr/lib/x86_64-linux-gnu/libvtkIOGeometry-6.2.so.6.2.0 7f8f3dcc7000-7f8f3dd3e000 r-xp 00000000 103:02 11546050 /usr/lib/libOpenNI.so.0 7f8f3dd3e000-7f8f3df3d000 ---p 00077000 103:02 11546050 /usr/lib/libOpenNI.so.0 7f8f3df3d000-7f8f3df3f000 r--p 00076000 103:02 11546050 /usr/lib/libOpenNI.so.0 7f8f3df3f000-7f8f3df42000 rw-p 00078000 103:02 11546050 /usr/lib/libOpenNI.so.0 7f8f3df42000-7f8f3df43000 rw-p 00000000 00:00 0 7f8f3df43000-7f8f3df5a000 r-xp 00000000 103:02 48894566 /lib/x86_64-linux-gnu/libusb-1.0.so.0.1.0 7f8f3df5a000-7f8f3e159000 ---p 00017000 103:02 48894566 /lib/x86_64-linux-gnu/libusb-1.0.so.0.1.0 7f8f3e159000-7f8f3e15a000 r--p 00016000 103:02 48894566 /lib/x86_64-linux-gnu/libusb-1.0.so.0.1.0 7f8f3e15a000-7f8f3e15b000 rw-p 00017000 103:02 48894566 /lib/x86_64-linux-gnu/libusb-1.0.so.0.1.0 7f8f3e15b000-7f8f3e181000 r-xp 00000000 103:02 11549742 /usr/lib/x86_64-linux-gnu/libvtkIOMPIImage-6.2.so.6.2.0 7f8f3e181000-7f8f3e380000 ---p 00026000 103:02 11549742 /usr/lib/x86_64-linux-gnu/libvtkIOMPIImage-6.2.so.6.2.0 7f8f3e380000-7f8f3e383000 r--p 00025000 103:02 11549742 /usr/lib/x86_64-linux-gnu/libvtkIOMPIImage-6.2.so.6.2.0 7f8f3e383000-7f8f3e384000 rw-p 00028000 103:02 11549742 /usr/lib/x86_64-linux-gnu/libvtkIOMPIImage-6.2.so.6.2.0 7f8f3e384000-7f8f3e3a8000 r-xp 00000000 103:02 11549646 /usr/lib/x86_64-linux-gnu/libvtkIOMPIParallel-6.2.so.6.2.0 7f8f3e3a8000-7f8f3e5a8000 ---p 00024000 103:02 11549646 /usr/lib/x86_64-linux-gnu/libvtkIOMPIParallel-6.2.so.6.2.0 7f8f3e5a8000-7f8f3e5aa000 r--p 00024000 103:02 11549646 /usr/lib/x86_64-linux-gnu/libvtkIOMPIParallel-6.2.so.6.2.0 7f8f3e5aa000-7f8f3e5ab000 rw-p 00026000 103:02 11549646 /usr/lib/x86_64-linux-gnu/libvtkIOMPIParallel-6.2.so.6.2.0 7f8f3e5ab000-7f8f3e5c2000 r-xp 00000000 103:02 11549946 /usr/lib/x86_64-linux-gnu/libvtkIOPLY-6.2.so.6.2.0 7f8f3e5c2000-7f8f3e7c2000 ---p 00017000 103:02 11549946 /usr/lib/x86_64-linux-gnu/libvtkIOPLY-6.2.so.6.2.0 7f8f3e7c2000-7f8f3e7c3000 r--p 00017000 103:02 11549946 /usr/lib/x86_64-linux-gnu/libvtkIOPLY-6.2.so.6.2.0 7f8f3e7c3000-7f8f3e7c4000 rw-p 00018000 103:02 11549946 /usr/lib/x86_64-linux-gnu/libvtkIOPLY-6.2.so.6.2.0 7f8f3e7c4000-7f8f3e7c6000 rw-p 00000000 00:00 0 7f8f3e7c6000-7f8f3e7ea000 r-xp 00000000 103:02 48894527 /lib/x86_64-linux-gnu/libpng12.so.0.54.0 7f8f3e7ea000-7f8f3e9e9000 ---p 00024000 103:02 48894527 /lib/x86_64-linux-gnu/libpng12.so.0.54.0 7f8f3e9e9000-7f8f3e9ea000 r--p 00023000 103:02 48894527 /lib/x86_64-linux-gnu/libpng12.so.0.54.0 7f8f3e9ea000-7f8f3e9eb000 rw-p 00024000 103:02 48894527 /lib/x86_64-linux-gnu/libpng12.so.0.54.0 7f8f3e9eb000-7f8f3ea3e000 r-xp 00000000 103:02 11550936 /usr/lib/x86_64-linux-gnu/libpcl_io_ply.so.1.7.2 7f8f3ea3e000-7f8f3ec3d000 ---p 00053000 103:02 11550936 /usr/lib/x86_64-linux-gnu/libpcl_io_ply.so.1.7.2 7f8f3ec3d000-7f8f3ec40000 r--p 00052000 103:02 11550936 /usr/lib/x86_64-linux-gnu/libpcl_io_ply.so.1.7.2 7f8f3ec40000-7f8f3ec41000 rw-p 00055000 103:02 11550936 /usr/lib/x86_64-linux-gnu/libpcl_io_ply.so.1.7.2 7f8f3ec41000-7f8f3ec58000 r-xp 00000000 103:02 11542381 /usr/lib/x86_64-linux-gnu/libboost_iostreams.so.1.58.0 7f8f3ec58000-7f8f3ee58000 ---p 00017000 103:02 11542381 /usr/lib/x86_64-linux-gnu/libboost_iostreams.so.1.58.0 7f8f3ee58000-7f8f3ee59000 r--p 00017000 103:02 11542381 /usr/lib/x86_64-linux-gnu/libboost_iostreams.so.1.58.0 7f8f3ee59000-7f8f3ee5a000 rw-p 00018000 103:02 11542381 /usr/lib/x86_64-linux-gnu/libboost_iostreams.so.1.58.0 7f8f3ee5a000-7f8f3eeb0000 r-xp 00000000 103:02 12068940 /usr/local/lib/libg2o_types_slam3d_addons.so 7f8f3eeb0000-7f8f3f0af000 ---p 00056000 103:02 12068940 /usr/local/lib/libg2o_types_slam3d_addons.so 7f8f3f0af000-7f8f3f0b2000 r--p 00055000 103:02 12068940 /usr/local/lib/libg2o_types_slam3d_addons.so 7f8f3f0b2000-7f8f3f0b3000 rw-p 00058000 103:02 12068940 /usr/local/lib/libg2o_types_slam3d_addons.so 7f8f3f0b3000-7f8f3f11e000 r-xp 00000000 103:02 12068934 /usr/local/lib/libg2o_types_slam3d.so 7f8f3f11e000-7f8f3f31e000 ---p 0006b000 103:02 12068934 /usr/local/lib/libg2o_types_slam3d.so 7f8f3f31e000-7f8f3f321000 r--p 0006b000 103:02 12068934 /usr/local/lib/libg2o_types_slam3d.so 7f8f3f321000-7f8f3f322000 rw-p 0006e000 103:02 12068934 /usr/local/lib/libg2o_types_slam3d.so 7f8f3f322000-7f8f3f377000 r-xp 00000000 103:02 12068944 /usr/local/lib/libg2o_solver_csparse.so 7f8f3f377000-7f8f3f577000 ---p 00055000 103:02 12068944 /usr/local/lib/libg2o_solver_csparse.so 7f8f3f577000-7f8f3f578000 r--p 00055000 103:02 12068944 /usr/local/lib/libg2o_solver_csparse.so 7f8f3f578000-7f8f3f579000 rw-p 00056000 103:02 12068944 /usr/local/lib/libg2o_solver_csparse.so 7f8f3f579000-7f8f3f5d7000 r-xp 00000000 103:02 12068925 /usr/local/lib/libg2o_core.so 7f8f3f5d7000-7f8f3f7d6000 ---p 0005e000 103:02 12068925 /usr/local/lib/libg2o_core.so 7f8f3f7d6000-7f8f3f7d8000 r--p 0005d000 103:02 12068925 /usr/local/lib/libg2o_core.so 7f8f3f7d8000-7f8f3f7d9000 rw-p 0005f000 103:02 12068925 /usr/local/lib/libg2o_core.so 7f8f3f7d9000-7f8f3f7dd000 r-xp 00000000 103:02 47188635 /opt/ros/kinetic/lib/libmessage_filters.so 7f8f3f7dd000-7f8f3f9dc000 ---p 00004000 103:02 47188635 /opt/ros/kinetic/lib/libmessage_filters.so 7f8f3f9dc000-7f8f3f9dd000 r--p 00003000 103:02 47188635 /opt/ros/kinetic/lib/libmessage_filters.so 7f8f3f9dd000-7f8f3f9de000 rw-p 00004000 103:02 47188635 /opt/ros/kinetic/lib/libmessage_filters.so 7f8f3f9de000-7f8f3f9e1000 r-xp 00000000 103:02 47188605 /opt/ros/kinetic/lib/libgeoconv.so 7f8f3f9e1000-7f8f3fbe1000 ---p 00003000 103:02 47188605 /opt/ros/kinetic/lib/libgeoconv.so 7f8f3fbe1000-7f8f3fbe2000 r--p 00003000 103:02 47188605 /opt/ros/kinetic/lib/libgeoconv.so 7f8f3fbe2000-7f8f3fbe3000 rw-p 00004000 103:02 47188605 /opt/ros/kinetic/lib/libgeoconv.so 7f8f3fbe3000-7f8f3fe48000 r-xp 00000000 103:02 11550937 /usr/lib/x86_64-linux-gnu/libpcl_io.so.1.7.2 7f8f3fe48000-7f8f40047000 ---p 00265000 103:02 11550937 /usr/lib/x86_64-linux-gnu/libpcl_io.so.1.7.2 7f8f40047000-7f8f40050000 r--p 00264000 103:02 11550937 /usr/lib/x86_64-linux-gnu/libpcl_io.so.1.7.2 7f8f40050000-7f8f40051000 rw-p 0026d000 103:02 11550937 /usr/lib/x86_64-linux-gnu/libpcl_io.so.1.7.2 7f8f40051000-7f8f40052000 rw-p 00000000 00:00 0 7f8f40052000-7f8f40148000 r-xp 00000000 103:02 31985261 /home/z/iliad_ws/devel/lib/libhdl_graph_slam_nodelet.so 7f8f40148000-7f8f40348000 ---p 000f6000 103:02 31985261 /home/z/iliad_ws/devel/lib/libhdl_graph_slam_nodelet.so 7f8f40348000-7f8f4034e000 r--p 000f6000 103:02 31985261 /home/z/iliad_ws/devel/lib/libhdl_graph_slam_nodelet.so 7f8f4034e000-7f8f40350000 rw-p 000fc000 103:02 31985261 /home/z/iliad_ws/devel/lib/libhdl_graph_slam_nodelet.so 7f8f40350000-7f8f4036e000 r-xp 00000000 103:02 47190369 /opt/ros/kinetic/lib/libactionlib.so 7f8f4036e000-7f8f4056d000 ---p 0001e000 103:02 47190369 /opt/ros/kinetic/lib/libactionlib.so 7f8f4056d000-7f8f4056f000 r--p 0001d000 103:02 47190369 /opt/ros/kinetic/lib/libactionlib.so 7f8f4056f000-7f8f40570000 rw-p 0001f000 103:02 47190369 /opt/ros/kinetic/lib/libactionlib.so 7f8f40570000-7f8f405a2000 r-xp 00000000 103:02 47189214 /opt/ros/kinetic/lib/libtf2.so 7f8f405a2000-7f8f407a1000 ---p 00032000 103:02 47189214 /opt/ros/kinetic/lib/libtf2.so 7f8f407a1000-7f8f407a3000 r--p 00031000 103:02 47189214 /opt/ros/kinetic/lib/libtf2.so 7f8f407a3000-7f8f407a4000 rw-p 00033000 103:02 47189214 /opt/ros/kinetic/lib/libtf2.so 7f8f407a4000-7f8f4084a000 r-xp 00000000 103:02 47187758 /opt/ros/kinetic/lib/libtf2_ros.so 7f8f4084a000-7f8f40a49000 ---p 000a6000 103:02 47187758 /opt/ros/kinetic/lib/libtf2_ros.so 7f8f40a49000-7f8f40a4d000 r--p 000a5000 103:02 47187758 /opt/ros/kinetic/lib/libtf2_ros.so 7f8f40a4d000-7f8f40a4f000 rw-p 000a9000 103:02 47187758 /opt/ros/kinetic/lib/libtf2_ros.so 7f8f40a4f000-7f8f40acf000 r-xp 00000000 103:02 31983020 /home/z/iliad_ws/devel/lib/libndt_omp.so 7f8f40acf000-7f8f40cce000 ---p 00080000 103:02 31983020 /home/z/iliad_ws/devel/lib/libndt_omp.so 7f8f40cce000-7f8f40cd1000 r--p 0007f000 103:02 31983020 /home/z/iliad_ws/devel/lib/libndt_omp.so 7f8f40cd1000-7f8f40cd2000 rw-p 00082000 103:02 31983020 /home/z/iliad_ws/devel/lib/libndt_omp.so 7f8f40cd2000-7f8f40d08000 r-xp 00000000 103:02 47187822 /opt/ros/kinetic/lib/libtf.so 7f8f40d08000-7f8f40f08000 ---p 00036000 103:02 47187822 /opt/ros/kinetic/lib/libtf.so 7f8f40f08000-7f8f40f0a000 r--p 00036000 103:02 47187822 /opt/ros/kinetic/lib/libtf.so 7f8f40f0a000-7f8f40f0b000 rw-p 00038000 103:02 47187822 /opt/ros/kinetic/lib/libtf.so 7f8f40f0b000-7f8f40f73000 r-xp 00000000 103:02 31985126 /home/z/iliad_ws/devel/lib/libscan_matching_odometry_nodelet.so 7f8f40f73000-7f8f41173000 ---p 00068000 103:02 31985126 /home/z/iliad_ws/devel/lib/libscan_matching_odometry_nodelet.so 7f8f41173000-7f8f41176000 r--p 00068000 103:02 31985126 /home/z/iliad_ws/devel/lib/libscan_matching_odometry_nodelet.so 7f8f41176000-7f8f41177000 rw-p 0006b000 103:02 31985126 /home/z/iliad_ws/devel/lib/libscan_matching_odometry_nodelet.so 7f8f41177000-7f8f41178000 ---p 00000000 00:00 0 7f8f41178000-7f8f41978000 rw-p 00000000 00:00 0 7f8f41978000-7f8f43213000 r-xp 00000000 103:02 11550924 /usr/lib/x86_64-linux-gnu/libpcl_features.so.1.7.2 7f8f43213000-7f8f43412000 ---p 0189b000 103:02 11550924 /usr/lib/x86_64-linux-gnu/libpcl_features.so.1.7.2 7f8f43412000-7f8f43494000 r--p 0189a000 103:02 11550924 /usr/lib/x86_64-linux-gnu/libpcl_features.so.1.7.2 7f8f43494000-7f8f434e8000 rw-p 0191c000 103:02 11550924 /usr/lib/x86_64-linux-gnu/libpcl_features.so.1.7.2 7f8f434e8000-7f8f436da000 r-xp 00000000 103:02 11550920 /usr/lib/x86_64-linux-gnu/libpcl_octree.so.1.7.2 7f8f436da000-7f8f438d9000 ---p 001f2000 103:02 11550920 /usr/lib/x86_64-linux-gnu/libpcl_octree.so.1.7.2 7f8f438d9000-7f8f438dc000 r--p 001f1000 103:02 11550920 /usr/lib/x86_64-linux-gnu/libpcl_octree.so.1.7.2 7f8f438dc000-7f8f438dd000 rw-p 001f4000 103:02 11550920 /usr/lib/x86_64-linux-gnu/libpcl_octree.so.1.7.2 7f8f438dd000-7f8f43a07000 r-xp 00000000 103:02 11550918 /usr/lib/x86_64-linux-gnu/libpcl_kdtree.so.1.7.2 7f8f43a07000-7f8f43c07000 ---p 0012a000 103:02 11550918 /usr/lib/x86_64-linux-gnu/libpcl_kdtree.so.1.7.2 7f8f43c07000-7f8f43c0f000 r--p 0012a000 103:02 11550918 /usr/lib/x86_64-linux-gnu/libpcl_kdtree.so.1.7.2 7f8f43c0f000-7f8f43c10000 rw-p 00132000 103:02 11550918 /usr/lib/x86_64-linux-gnu/libpcl_kdtree.so.1.7.2 7f8f43c10000-7f8f43df4000 r-xp 00000000 103:02 11550922 /usr/lib/x86_64-linux-gnu/libpcl_search.so.1.7.2 7f8f43df4000-7f8f43ff4000 ---p 001e4000 103:02 11550922 /usr/lib/x86_64-linux-gnu/libpcl_search.so.1.7.2 7f8f43ff4000-7f8f43fff000 r--p 001e4000 103:02 11550922 /usr/lib/x86_64-linux-gnu/libpcl_search.so.1.7.2 7f8f43fff000-7f8f44000000 rw-p 001ef000 103:02 11550922 /usr/lib/x86_64-linux-gnu/libpcl_search.so.1.7.2 7f8f44000000-7f8f44021000 rw-p 00000000 00:00 0 7f8f44021000-7f8f48000000 ---p 00000000 00:00 0 7f8f48000000-7f8f48021000 rw-p 00000000 00:00 0 7f8f48021000-7f8f4c000000 ---p 00000000 00:00 0 7f8f4c000000-7f8f4c021000 rw-p 00000000 00:00 0 7f8f4c021000-7f8f50000000 ---p 00000000 00:00 0 7f8f50000000-7f8f50021000 rw-p 00000000 00:00 0 7f8f50021000-7f8f54000000 ---p 00000000 00:00 0 7f8f54109000-7f8f54b30000 r-xp 00000000 103:02 11550926 /usr/lib/x86_64-linux-gnu/libpcl_sample_consensus.so.1.7.2 7f8f54b30000-7f8f54d30000 ---p 00a27000 103:02 11550926 /usr/lib/x86_64-linux-gnu/libpcl_sample_consensus.so.1.7.2 7f8f54d30000-7f8f54d56000 r--p 00a27000 103:02 11550926 /usr/lib/x86_64-linux-gnu/libpcl_sample_consensus.so.1.7.2 7f8f54d56000-7f8f54d57000 rw-p 00a4d000 103:02 11550926 /usr/lib/x86_64-linux-gnu/libpcl_sample_consensus.so.1.7.2 7f8f54d57000-7f8f54d58000 rw-p 00000000 00:00 0 7f8f54d58000-7f8f54d79000 r-xp 00000000 103:02 11534765 /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0 7f8f54d79000-7f8f54f78000 ---p 00021000 103:02 11534765 /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0 7f8f54f78000-7f8f54f79000 r--p 00020000 103:02 11534765 /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0 7f8f54f79000-7f8f54f7a000 rw-p 00021000 103:02 11534765 /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0 7f8f54f7a000-7f8f553d1000 r-xp 00000000 103:02 11550946 /usr/lib/x86_64-linux-gnu/libpcl_recognition.so.1.7.2 7f8f553d1000-7f8f555d0000 ---p 00457000 103:02 11550946 /usr/lib/x86_64-linux-gnu/libpcl_recognition.so.1.7.2 7f8f555d0000-7f8f555ea000 r--p 00456000 103:02 11550946 /usr/lib/x86_64-linux-gnu/libpcl_recognition.so.1.7.2 7f8f555ea000-7f8f555eb000 rw-p 00470000 103:02 11550946 /usr/lib/x86_64-linux-gnu/libpcl_recognition.so.1.7.2 7f8f555eb000-7f8f55fb3000 r-xp 00000000 103:02 11550930 /usr/lib/x86_64-linux-gnu/libpcl_segmentation.so.1.7.2 7f8f55fb3000-7f8f561b3000 ---p 009c8000 103:02 11550930 /usr/lib/x86_64-linux-gnu/libpcl_segmentation.so.1.7.2 7f8f561b3000-7f8f561f8000 r--p 009c8000 103:02 11550930 /usr/lib/x86_64-linux-gnu/libpcl_segmentation.so.1.7.2 7f8f561f8000-7f8f561f9000 rw-p 00a0d000 103:02 11550930 /usr/lib/x86_64-linux-gnu/libpcl_segmentation.so.1.7.2 7f8f561f9000-7f8f568f4000 r-xp 00000000 103:02 11550928 /usr/lib/x86_64-linux-gnu/libpcl_filters.so.1.7.2 7f8f568f4000-7f8f56af3000 ---p 006fb000 103:02 11550928 /usr/lib/x86_64-linux-gnu/libpcl_filters.so.1.7.2 7f8f56af3000-7f8f56b1b000 r--p 006fa000 103:02 11550928 /usr/lib/x86_64-linux-gnu/libpcl_filters.so.1.7.2 7f8f56b1b000-7f8f56b1c000 rw-p 00722000 103:02 11550928 /usr/lib/x86_64-linux-gnu/libpcl_filters.so.1.7.2 7f8f56b1c000-7f8f56bd2000 r-xp 00000000 103:02 11550916 /usr/lib/x86_64-linux-gnu/libpcl_common.so.1.7.2 7f8f56bd2000-7f8f56dd1000 ---p 000b6000 103:02 11550916 /usr/lib/x86_64-linux-gnu/libpcl_common.so.1.7.2 7f8f56dd1000-7f8f56dd5000 r--p 000b5000 103:02 11550916 /usr/lib/x86_64-linux-gnu/libpcl_common.so.1.7.2 7f8f56dd5000-7f8f56dd6000 rw-p 000b9000 103:02 11550916 /usr/lib/x86_64-linux-gnu/libpcl_common.so.1.7.2 7f8f56dd6000-7f8f56dfb000 r-xp 00000000 103:02 31983004 /home/z/iliad_ws/devel/lib/libprefiltering_nodelet.so 7f8f56dfb000-7f8f56ffb000 ---p 00025000 103:02 31983004 /home/z/iliad_ws/devel/lib/libprefiltering_nodelet.so 7f8f56ffb000-7f8f56ffd000 r--p 00025000 103:02 31983004 /home/z/iliad_ws/devel/lib/libprefiltering_nodelet.so 7f8f56ffd000-7f8f56ffe000 rw-p 00027000 103:02 31983004 /home/z/iliad_ws/devel/lib/libprefiltering_nodelet.so 7f8f56ffe000-7f8f56fff000 ---p 00000000 00:00 0 7f8f56fff000-7f8f577ff000 rw-p 00000000 00:00 0 7f8f577ff000-7f8f57800000 ---p 00000000 00:00 0 7f8f57800000-7f8f58000000 rw-p 00000000 00:00 0 7f8f58000000-7f8f58021000 rw-p 00000000 00:00 0 7f8f58021000-7f8f5c000000 ---p 00000000 00:00 0 7f8f5c06e000-7f8f5c06f000 ---p 00000000 00:00 0 7f8f5c06f000-7f8f5c86f000 rw-p 00000000 00:00 0 7f8f5c86f000-7f8f5c870000 ---p 00000000 00:00 0 7f8f5c870000-7f8f5d070000 rw-p 00000000 00:00 0 7f8f5d070000-7f8f5d071000 ---p 00000000 00:00 0 7f8f5d071000-7f8f5d871000 rw-p 00000000 00:00 0 7f8f5d871000-7f8f5d872000 ---p 00000000 00:00 0 7f8f5d872000-7f8f5e072000 rw-p 00000000 00:00 0 7f8f5e072000-7f8f5e073000 ---p 00000000 00:00 0 7f8f5e073000-7f8f5e873000 rw-p 00000000 00:00 0 7f8f5e873000-7f8f5e874000 ---p 00000000 00:00 0 7f8f5e874000-7f8f5f074000 rw-p 00000000 00:00 0 7f8f5f074000-7f8f5f075000 ---p 00000000 00:00 0 7f8f5f075000-7f8f5f875000 rw-p 00000000 00:00 0 7f8f5f875000-7f8f5f876000 ---p 00000000 00:00 0 7f8f5f876000-7f8f60076000 rw-p 00000000 00:00 0 7f8f60076000-7f8f60081000 r-xp 00000000 103:02 48889952 /lib/x86_64-linux-gnu/libnss_files-2.23.so 7f8f60081000-7f8f60280000 ---p 0000b000 103:02 48889952 /lib/x86_64-linux-gnu/libnss_files-2.23.so 7f8f60280000-7f8f60281000 r--p 0000a000 103:02 48889952 /lib/x86_64-linux-gnu/libnss_files-2.23.so 7f8f60281000-7f8f60282000 rw-p 0000b000 103:02 48889952 /lib/x86_64-linux-gnu/libnss_files-2.23.so 7f8f60282000-7f8f60288000 rw-p 00000000 00:00 0 7f8f60288000-7f8f60293000 r-xp 00000000 103:02 48894403 /lib/x86_64-linux-gnu/libnss_nis-2.23.so 7f8f60293000-7f8f60492000 ---p 0000b000 103:02 48894403 /lib/x86_64-linux-gnu/libnss_nis-2.23.so 7f8f60492000-7f8f60493000 r--p 0000a000 103:02 48894403 /lib/x86_64-linux-gnu/libnss_nis-2.23.so 7f8f60493000-7f8f60494000 rw-p 0000b000 103:02 48894403 /lib/x86_64-linux-gnu/libnss_nis-2.23.so 7f8f60494000-7f8f604aa000 r-xp 00000000 103:02 48889870 /lib/x86_64-linux-gnu/libnsl-2.23.so 7f8f604aa000-7f8f606a9000 ---p 00016000 103:02 48889870 /lib/x86_64-linux-gnu/libnsl-2.23.so 7f8f606a9000-7f8f606aa000 r--p 00015000 103:02 48889870 /lib/x86_64-linux-gnu/libnsl-2.23.so 7f8f606aa000-7f8f606ab000 rw-p 00016000 103:02 48889870 /lib/x86_64-linux-gnu/libnsl-2.23.so 7f8f606ab000-7f8f606ad000 rw-p 00000000 00:00 0 7f8f606ad000-7f8f606b5000 r-xp 00000000 103:02 48889947 /lib/x86_64-linux-gnu/libnss_compat-2.23.so 7f8f606b5000-7f8f608b4000 ---p 00008000 103:02 48889947 /lib/x86_64-linux-gnu/libnss_compat-2.23.so 7f8f608b4000-7f8f608b5000 r--p 00007000 103:02 48889947 /lib/x86_64-linux-gnu/libnss_compat-2.23.so 7f8f608b5000-7f8f608b6000 rw-p 00008000 103:02 48889947 /lib/x86_64-linux-gnu/libnss_compat-2.23.so 7f8f608b6000-7f8f608b8000 r-xp 00000000 103:02 48889946 /lib/x86_64-linux-gnu/libutil-2.23.so 7f8f608b8000-7f8f60ab7000 ---p 00002000 103:02 48889946 /lib/x86_64-linux-gnu/libutil-2.23.so 7f8f60ab7000-7f8f60ab8000 r--p 00001000 103:02 48889946 /lib/x86_64-linux-gnu/libutil-2.23.so 7f8f60ab8000-7f8f60ab9000 rw-p 00002000 103:02 48889946 /lib/x86_64-linux-gnu/libutil-2.23.so 7f8f60ab9000-7f8f6236f000 r-xp 00000000 103:02 11548588 /usr/lib/x86_64-linux-gnu/libicudata.so.55.1 7f8f6236f000-7f8f6256e000 ---p 018b6000 103:02 11548588 /usr/lib/x86_64-linux-gnu/libicudata.so.55.1 7f8f6256e000-7f8f6256f000 r--p 018b5000 103:02 11548588 /usr/lib/x86_64-linux-gnu/libicudata.so.55.1 7f8f6256f000-7f8f62570000 rw-p 018b6000 103:02 11548588 /usr/lib/x86_64-linux-gnu/libicudata.so.55.1 7f8f62570000-7f8f62596000 r-xp 00000000 103:02 48894417 /lib/x86_64-linux-gnu/libexpat.so.1.6.0 7f8f62596000-7f8f62796000 ---p 00026000 103:02 48894417 /lib/x86_64-linux-gnu/libexpat.so.1.6.0 7f8f62796000-7f8f62798000 r--p 00026000 103:02 48894417 /lib/x86_64-linux-gnu/libexpat.so.1.6.0 7f8f62798000-7f8f62799000 rw-p 00028000 103:02 48894417 /lib/x86_64-linux-gnu/libexpat.so.1.6.0 7f8f62799000-7f8f627a2000 r-xp 00000000 103:02 48894405 /lib/x86_64-linux-gnu/libcrypt-2.23.so 7f8f627a2000-7f8f629a1000 ---p 00009000 103:02 48894405 /lib/x86_64-linux-gnu/libcrypt-2.23.so 7f8f629a1000-7f8f629a2000 r--p 00008000 103:02 48894405 /lib/x86_64-linux-gnu/libcrypt-2.23.so 7f8f629a2000-7f8f629a3000 rw-p 00009000 103:02 48894405 /lib/x86_64-linux-gnu/libcrypt-2.23.so 7f8f629a3000-7f8f629d1000 rw-p 00000000 00:00 0 7f8f629d1000-7f8f62cc3000 r-xp 00000000 103:02 11534349 /usr/lib/x86_64-linux-gnu/libpython2.7.so.1.0 7f8f62cc3000-7f8f62ec3000 ---p 002f2000 103:02 11534349 /usr/lib/x86_64-linux-gnu/libpython2.7.so.1.0 7f8f62ec3000-7f8f62ec5000 r--p 002f2000 103:02 11534349 /usr/lib/x86_64-linux-gnu/libpython2.7.so.1.0 7f8f62ec5000-7f8f62f3c000 rw-p 002f4000 103:02 11534349 /usr/lib/x86_64-linux-gnu/libpython2.7.so.1.0 7f8f62f3c000-7f8f62f5f000 rw-p 00000000 00:00 0 7f8f62f5f000-7f8f62fd9000 r-xp 00000000 103:02 11548331 /usr/lib/x86_64-linux-gnu/libboost_program_options.so.1.58.0 7f8f62fd9000-7f8f631d9000 ---p 0007a000 103:02 11548331 /usr/lib/x86_64-linux-gnu/libboost_program_options.so.1.58.0 7f8f631d9000-7f8f631dc000 r--p 0007a000 103:02 11548331 /usr/lib/x86_64-linux-gnu/libboost_program_options.so.1.58.0 7f8f631dc000-7f8f631dd000 rw-p 0007d000 103:02 11548331 /usr/lib/x86_64-linux-gnu/libboost_program_options.so.1.58.0 7f8f631dd000-7f8f631f1000 r-xp 00000000 103:02 11546046 /usr/lib/x86_64-linux-gnu/libtinyxml.so.2.6.2 7f8f631f1000-7f8f633f1000 ---p 00014000 103:02 11546046 /usr/lib/x86_64-linux-gnu/libtinyxml.so.2.6.2 7f8f633f1000-7f8f633f2000 r--p 00014000 103:02 11546046 /usr/lib/x86_64-linux-gnu/libtinyxml.so.2.6.2 7f8f633f2000-7f8f633f3000 rw-p 00015000 103:02 11546046 /usr/lib/x86_64-linux-gnu/libtinyxml.so.2.6.2 7f8f633f3000-7f8f633f6000 r-xp 00000000 103:02 48889941 /lib/x86_64-linux-gnu/libdl-2.23.so 7f8f633f6000-7f8f635f5000 ---p 00003000 103:02 48889941 /lib/x86_64-linux-gnu/libdl-2.23.so 7f8f635f5000-7f8f635f6000 r--p 00002000 103:02 48889941 /lib/x86_64-linux-gnu/libdl-2.23.so 7f8f635f6000-7f8f635f7000 rw-p 00003000 103:02 48889941 /lib/x86_64-linux-gnu/libdl-2.23.so 7f8f635f7000-7f8f63610000 r-xp 00000000 103:02 48894577 /lib/x86_64-linux-gnu/libz.so.1.2.8 7f8f63610000-7f8f6380f000 ---p 00019000 103:02 48894577 /lib/x86_64-linux-gnu/libz.so.1.2.8 7f8f6380f000-7f8f63810000 r--p 00018000 103:02 48894577 /lib/x86_64-linux-gnu/libz.so.1.2.8 7f8f63810000-7f8f63811000 rw-p 00019000 103:02 48894577 /lib/x86_64-linux-gnu/libz.so.1.2.8 7f8f63811000-7f8f6387f000 r-xp 00000000 103:02 48894515 /lib/x86_64-linux-gnu/libpcre.so.3.13.2 7f8f6387f000-7f8f63a7f000 ---p 0006e000 103:02 48894515 /lib/x86_64-linux-gnu/libpcre.so.3.13.2 7f8f63a7f000-7f8f63a80000 r--p 0006e000 103:02 48894515 /lib/x86_64-linux-gnu/libpcre.so.3.13.2 7f8f63a80000-7f8f63a81000 rw-p 0006f000 103:02 48894515 /lib/x86_64-linux-gnu/libpcre.so.3.13.2 7f8f63a81000-7f8f63c00000 r-xp 00000000 103:02 11548592 /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1 7f8f63c00000-7f8f63e00000 ---p 0017f000 103:02 11548592 /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1 7f8f63e00000-7f8f63e10000 r--p 0017f000 103:02 11548592 /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1 7f8f63e10000-7f8f63e11000 rw-p 0018f000 103:02 11548592 /usr/lib/x86_64-linux-gnu/libicuuc.so.55.1 7f8f63e11000-7f8f63e15000 rw-p 00000000 00:00 0 7f8f63e15000-7f8f64067000 r-xp 00000000 103:02 11548589 /usr/lib/x86_64-linux-gnu/libicui18n.so.55.1 7f8f64067000-7f8f64267000 ---p 00252000 103:02 11548589 /usr/lib/x86_64-linux-gnu/libicui18n.so.55.1 7f8f64267000-7f8f64276000 r--p 00252000 103:02 11548589 /usr/lib/x86_64-linux-gnu/libicui18n.so.55.1 7f8f64276000-7f8f64277000 rw-p 00261000 103:02 11548589 /usr/lib/x86_64-linux-gnu/libicui18n.so.55.1 7f8f64277000-7f8f6429d000 r-xp 00000000 103:02 11548630 /usr/lib/x86_64-linux-gnu/libaprutil-1.so.0.5.4 7f8f6429d000-7f8f6449c000 ---p 00026000 103:02 11548630 /usr/lib/x86_64-linux-gnu/libaprutil-1.so.0.5.4 7f8f6449c000-7f8f6449d000 r--p 00025000 103:02 11548630 /usr/lib/x86_64-linux-gnu/libaprutil-1.so.0.5.4 7f8f6449d000-7f8f6449e000 rw-p 00026000 103:02 11548630 /usr/lib/x86_64-linux-gnu/libaprutil-1.so.0.5.4 7f8f6449e000-7f8f644cf000 r-xp 00000000 103:02 11548616 /usr/lib/x86_64-linux-gnu/libapr-1.so.0.5.2 7f8f644cf000-7f8f646ce000 ---p 00031000 103:02 11548616 /usr/lib/x86_64-linux-gnu/libapr-1.so.0.5.2 7f8f646ce000-7f8f646cf000 r--p 00030000 103:02 11548616 /usr/lib/x86_64-linux-gnu/libapr-1.so.0.5.2 7f8f646cf000-7f8f646d0000 rw-p 00031000 103:02 11548616 /usr/lib/x86_64-linux-gnu/libapr-1.so.0.5.2 7f8f646d0000-7f8f64711000 r-xp 00000000 103:02 47186564 /opt/ros/kinetic/lib/librospack.so 7f8f64711000-7f8f64910000 ---p 00041000 103:02 47186564 /opt/ros/kinetic/lib/librospack.so 7f8f64910000-7f8f64911000 r--p 00040000 103:02 47186564 /opt/ros/kinetic/lib/librospack.so 7f8f64911000-7f8f64912000 rw-p 00041000 103:02 47186564 /opt/ros/kinetic/lib/librospack.so 7f8f64912000-7f8f64a61000 r-xp 00000000 103:02 11549398 /usr/lib/libPocoFoundation.so.9 7f8f64a61000-7f8f64c61000 ---p 0014f000 103:02 11549398 /usr/lib/libPocoFoundation.so.9 7f8f64c61000-7f8f64c6a000 r--p 0014f000 103:02 11549398 /usr/lib/libPocoFoundation.so.9 7f8f64c6a000-7f8f64c6d000 rw-p 00158000 103:02 11549398 /usr/lib/libPocoFoundation.so.9 7f8f64c6d000-7f8f64c6e000 rw-p 00000000 00:00 0 7f8f64c6e000-7f8f64c75000 r-xp 00000000 103:02 48894404 /lib/x86_64-linux-gnu/librt-2.23.so 7f8f64c75000-7f8f64e74000 ---p 00007000 103:02 48894404 /lib/x86_64-linux-gnu/librt-2.23.so 7f8f64e74000-7f8f64e75000 r--p 00006000 103:02 48894404 /lib/x86_64-linux-gnu/librt-2.23.so 7f8f64e75000-7f8f64e76000 rw-p 00007000 103:02 48894404 /lib/x86_64-linux-gnu/librt-2.23.so 7f8f64e76000-7f8f64f79000 r-xp 00000000 103:02 11548332 /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.58.0 7f8f64f79000-7f8f65179000 ---p 00103000 103:02 11548332 /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.58.0 7f8f65179000-7f8f6517d000 r--p 00103000 103:02 11548332 /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.58.0 7f8f6517d000-7f8f6517e000 rw-p 00107000 103:02 11548332 /usr/lib/x86_64-linux-gnu/libboost_regex.so.1.58.0 7f8f6517e000-7f8f6532d000 r-xp 00000000 103:02 11549358 /usr/lib/x86_64-linux-gnu/liblog4cxx.so.10.0.0 7f8f6532d000-7f8f6552c000 ---p 001af000 103:02 11549358 /usr/lib/x86_64-linux-gnu/liblog4cxx.so.10.0.0 7f8f6552c000-7f8f65552000 r--p 001ae000 103:02 11549358 /usr/lib/x86_64-linux-gnu/liblog4cxx.so.10.0.0 7f8f65552000-7f8f65553000 rw-p 001d4000 103:02 11549358 /usr/lib/x86_64-linux-gnu/liblog4cxx.so.10.0.0 7f8f65553000-7f8f65555000 rw-p 00000000 00:00 0 7f8f65555000-7f8f65556000 r-xp 00000000 103:02 47186342 /opt/ros/kinetic/lib/librosconsole_backend_interface.so 7f8f65556000-7f8f65755000 ---p 00001000 103:02 47186342 /opt/ros/kinetic/lib/librosconsole_backend_interface.so 7f8f65755000-7f8f65756000 r--p 00000000 103:02 47186342 /opt/ros/kinetic/lib/librosconsole_backend_interface.so 7f8f65756000-7f8f65757000 rw-p 00001000 103:02 47186342 /opt/ros/kinetic/lib/librosconsole_backend_interface.so 7f8f65757000-7f8f6576d000 r-xp 00000000 103:02 47186344 /opt/ros/kinetic/lib/librosconsole_log4cxx.so 7f8f6576d000-7f8f6596d000 ---p 00016000 103:02 47186344 /opt/ros/kinetic/lib/librosconsole_log4cxx.so 7f8f6596d000-7f8f6596f000 r--p 00016000 103:02 47186344 /opt/ros/kinetic/lib/librosconsole_log4cxx.so 7f8f6596f000-7f8f65970000 rw-p 00018000 103:02 47186344 /opt/ros/kinetic/lib/librosconsole_log4cxx.so 7f8f65970000-7f8f65976000 r-xp 00000000 103:02 11548724 /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0 7f8f65976000-7f8f65b76000 ---p 00006000 103:02 11548724 /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0 7f8f65b76000-7f8f65b77000 r--p 00006000 103:02 11548724 /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0 7f8f65b77000-7f8f65b78000 rw-p 00007000 103:02 11548724 /usr/lib/x86_64-linux-gnu/libboost_chrono.so.1.58.0 7f8f65b78000-7f8f65b7f000 r-xp 00000000 103:02 47186076 /opt/ros/kinetic/lib/libcpp_common.so 7f8f65b7f000-7f8f65d7e000 ---p 00007000 103:02 47186076 /opt/ros/kinetic/lib/libcpp_common.so 7f8f65d7e000-7f8f65d7f000 r--p 00006000 103:02 47186076 /opt/ros/kinetic/lib/libcpp_common.so 7f8f65d7f000-7f8f65d80000 rw-p 00007000 103:02 47186076 /opt/ros/kinetic/lib/libcpp_common.so 7f8f65d80000-7f8f65e88000 r-xp 00000000 103:02 48889861 /lib/x86_64-linux-gnu/libm-2.23.so 7f8f65e88000-7f8f66087000 ---p 00108000 103:02 48889861 /lib/x86_64-linux-gnu/libm-2.23.so 7f8f66087000-7f8f66088000 r--p 00107000 103:02 48889861 /lib/x86_64-linux-gnu/libm-2.23.so 7f8f66088000-7f8f66089000 rw-p 00108000 103:02 48889861 /lib/x86_64-linux-gnu/libm-2.23.so 7f8f66089000-7f8f6608d000 r-xp 00000000 103:02 11548449 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.2 7f8f6608d000-7f8f6628c000 ---p 00004000 103:02 11548449 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.2 7f8f6628c000-7f8f6628d000 r--p 00003000 103:02 11548449 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.2 7f8f6628d000-7f8f6628e000 rw-p 00004000 103:02 11548449 /usr/lib/x86_64-linux-gnu/libconsole_bridge.so.0.2 7f8f6628e000-7f8f662a6000 r-xp 00000000 103:02 48889881 /lib/x86_64-linux-gnu/libpthread-2.23.so 7f8f662a6000-7f8f664a5000 ---p 00018000 103:02 48889881 /lib/x86_64-linux-gnu/libpthread-2.23.so 7f8f664a5000-7f8f664a6000 r--p 00017000 103:02 48889881 /lib/x86_64-linux-gnu/libpthread-2.23.so 7f8f664a6000-7f8f664a7000 rw-p 00018000 103:02 48889881 /lib/x86_64-linux-gnu/libpthread-2.23.so 7f8f664a7000-7f8f664ab000 rw-p 00000000 00:00 0 7f8f664ab000-7f8f664cf000 r-xp 00000000 103:02 11548333 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0 7f8f664cf000-7f8f666ce000 ---p 00024000 103:02 11548333 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0 7f8f666ce000-7f8f666d0000 r--p 00023000 103:02 11548333 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0 7f8f666d0000-7f8f666d1000 rw-p 00025000 103:02 11548333 /usr/lib/x86_64-linux-gnu/libboost_thread.so.1.58.0 7f8f666d1000-7f8f666e8000 r-xp 00000000 103:02 11542380 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.58.0 7f8f666e8000-7f8f668e7000 ---p 00017000 103:02 11542380 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.58.0 7f8f668e7000-7f8f668e8000 r--p 00016000 103:02 11542380 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.58.0 7f8f668e8000-7f8f668e9000 rw-p 00017000 103:02 11542380 /usr/lib/x86_64-linux-gnu/libboost_filesystem.so.1.58.0 7f8f668e9000-7f8f668f9000 r-xp 00000000 103:02 47186572 /opt/ros/kinetic/lib/libroslib.so 7f8f668f9000-7f8f66af9000 ---p 00010000 103:02 47186572 /opt/ros/kinetic/lib/libroslib.so 7f8f66af9000-7f8f66afa000 r--p 00010000 103:02 47186572 /opt/ros/kinetic/lib/libroslib.so 7f8f66afa000-7f8f66afb000 rw-p 00011000 103:02 47186572 /opt/ros/kinetic/lib/libroslib.so 7f8f66afb000-7f8f66b1d000 r-xp 00000000 103:02 47187578 /opt/ros/kinetic/lib/libclass_loader.so 7f8f66b1d000-7f8f66d1d000 ---p 00022000 103:02 47187578 /opt/ros/kinetic/lib/libclass_loader.so 7f8f66d1d000-7f8f66d1e000 r--p 00022000 103:02 47187578 /opt/ros/kinetic/lib/libclass_loader.so 7f8f66d1e000-7f8f66d1f000 rw-p 00023000 103:02 47187578 /opt/ros/kinetic/lib/libclass_loader.so 7f8f66d1f000-7f8f66d30000 r-xp 00000000 103:02 11548461 /usr/lib/x86_64-linux-gnu/libtinyxml2.so.2.2.0 7f8f66d30000-7f8f66f30000 ---p 00011000 103:02 11548461 /usr/lib/x86_64-linux-gnu/libtinyxml2.so.2.2.0 7f8f66f30000-7f8f66f31000 r--p 00011000 103:02 11548461 /usr/lib/x86_64-linux-gnu/libtinyxml2.so.2.2.0 7f8f66f31000-7f8f66f32000 rw-p 00012000 103:02 11548461 /usr/lib/x86_64-linux-gnu/libtinyxml2.so.2.2.0 7f8f66f32000-7f8f670f2000 r-xp 00000000 103:02 48889939 /lib/x86_64-linux-gnu/libc-2.23.so 7f8f670f2000-7f8f672f2000 ---p 001c0000 103:02 48889939 /lib/x86_64-linux-gnu/libc-2.23.so 7f8f672f2000-7f8f672f6000 r--p 001c0000 103:02 48889939 /lib/x86_64-linux-gnu/libc-2.23.so 7f8f672f6000-7f8f672f8000 rw-p 001c4000 103:02 48889939 /lib/x86_64-linux-gnu/libc-2.23.so 7f8f672f8000-7f8f672fc000 rw-p 00000000 00:00 0 7f8f672fc000-7f8f67312000 r-xp 00000000 103:02 48894424 /lib/x86_64-linux-gnu/libgcc_s.so.1 7f8f67312000-7f8f67511000 ---p 00016000 103:02 48894424 /lib/x86_64-linux-gnu/libgcc_s.so.1 7f8f67511000-7f8f67512000 rw-p 00015000 103:02 48894424 /lib/x86_64-linux-gnu/libgcc_s.so.1 7f8f67512000-7f8f67684000 r-xp 00000000 103:02 11536518 /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.21 7f8f67684000-7f8f67884000 ---p 00172000 103:02 11536518 /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.21 7f8f67884000-7f8f6788e000 r--p 00172000 103:02 11536518 /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.21 7f8f6788e000-7f8f67890000 rw-p 0017c000 103:02 11536518 /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.21 7f8f67890000-7f8f67894000 rw-p 00000000 00:00 0 7f8f67894000-7f8f67897000 r-xp 00000000 103:02 11542382 /usr/lib/x86_64-linux-gnu/libboost_system.so.1.58.0 7f8f67897000-7f8f67a96000 ---p 00003000 103:02 11542382 /usr/lib/x86_64-linux-gnu/libboost_system.so.1.58.0 7f8f67a96000-7f8f67a97000 r--p 00002000 103:02 11542382 /usr/lib/x86_64-linux-gnu/libboost_system.so.1.58.0 7f8f67a97000-7f8f67a98000 rw-p 00003000 103:02 11542382 /usr/lib/x86_64-linux-gnu/libboost_system.so.1.58.0 7f8f67a98000-7f8f67ac3000 r-xp 00000000 103:02 47186088 /opt/ros/kinetic/lib/librostime.so 7f8f67ac3000-7f8f67cc3000 ---p 0002b000 103:02 47186088 /opt/ros/kinetic/lib/librostime.so 7f8f67cc3000-7f8f67cc5000 r--p 0002b000 103:02 47186088 /opt/ros/kinetic/lib/librostime.so 7f8f67cc5000-7f8f67cc6000 rw-p 0002d000 103:02 47186088 /opt/ros/kinetic/lib/librostime.so 7f8f67cc6000-7f8f67cc8000 r-xp 00000000 103:02 47186110 /opt/ros/kinetic/lib/libroscpp_serialization.so 7f8f67cc8000-7f8f67ec7000 ---p 00002000 103:02 47186110 /opt/ros/kinetic/lib/libroscpp_serialization.so 7f8f67ec7000-7f8f67ec8000 r--p 00001000 103:02 47186110 /opt/ros/kinetic/lib/libroscpp_serialization.so 7f8f67ec8000-7f8f67ec9000 rw-p 00002000 103:02 47186110 /opt/ros/kinetic/lib/libroscpp_serialization.so 7f8f67ec9000-7f8f67ee7000 r-xp 00000000 103:02 47186408 /opt/ros/kinetic/lib/libxmlrpcpp.so 7f8f67ee7000-7f8f680e6000 ---p 0001e000 103:02 47186408 /opt/ros/kinetic/lib/libxmlrpcpp.so 7f8f680e6000-7f8f680e7000 r--p 0001d000 103:02 47186408 /opt/ros/kinetic/lib/libxmlrpcpp.so 7f8f680e7000-7f8f680e8000 rw-p 0001e000 103:02 47186408 /opt/ros/kinetic/lib/libxmlrpcpp.so 7f8f680e8000-7f8f68117000 r-xp 00000000 103:02 47186341 /opt/ros/kinetic/lib/librosconsole.so 7f8f68117000-7f8f68317000 ---p 0002f000 103:02 47186341 /opt/ros/kinetic/lib/librosconsole.so 7f8f68317000-7f8f68319000 r--p 0002f000 103:02 47186341 /opt/ros/kinetic/lib/librosconsole.so 7f8f68319000-7f8f6831a000 rw-p 00031000 103:02 47186341 /opt/ros/kinetic/lib/librosconsole.so 7f8f6831a000-7f8f684ac000 r-xp 00000000 103:02 47186511 /opt/ros/kinetic/lib/libroscpp.so 7f8f684ac000-7f8f686ab000 ---p 00192000 103:02 47186511 /opt/ros/kinetic/lib/libroscpp.so 7f8f686ab000-7f8f686b2000 r--p 00191000 103:02 47186511 /opt/ros/kinetic/lib/libroscpp.so 7f8f686b2000-7f8f686b6000 rw-p 00198000 103:02 47186511 /opt/ros/kinetic/lib/libroscpp.so 7f8f686b6000-7f8f686e3000 r-xp 00000000 103:02 47187689 /opt/ros/kinetic/lib/libbondcpp.so 7f8f686e3000-7f8f688e3000 ---p 0002d000 103:02 47187689 /opt/ros/kinetic/lib/libbondcpp.so 7f8f688e3000-7f8f688e5000 r--p 0002d000 103:02 47187689 /opt/ros/kinetic/lib/libbondcpp.so 7f8f688e5000-7f8f688e6000 rw-p 0002f000 103:02 47187689 /opt/ros/kinetic/lib/libbondcpp.so 7f8f688e6000-7f8f688ea000 r-xp 00000000 103:02 48894327 /lib/x86_64-linux-gnu/libuuid.so.1.3.0 7f8f688ea000-7f8f68ae9000 ---p 00004000 103:02 48894327 /lib/x86_64-linux-gnu/libuuid.so.1.3.0 7f8f68ae9000-7f8f68aea000 r--p 00003000 103:02 48894327 /lib/x86_64-linux-gnu/libuuid.so.1.3.0 7f8f68aea000-7f8f68aeb000 rw-p 00004000 103:02 48894327 /lib/x86_64-linux-gnu/libuuid.so.1.3.0 7f8f68aeb000-7f8f68b4f000 r-xp 00000000 103:02 47187877 /opt/ros/kinetic/lib/libnodeletlib.so 7f8f68b4f000-7f8f68d4e000 ---p 00064000 103:02 47187877 /opt/ros/kinetic/lib/libnodeletlib.so 7f8f68d4e000-7f8f68d51000 r--p 00063000 103:02 47187877 /opt/ros/kinetic/lib/libnodeletlib.so 7f8f68d51000-7f8f68d52000 rw-p 00066000 103:02 47187877 /opt/ros/kinetic/lib/libnodeletlib.so 7f8f68d52000-7f8f68d78000 r-xp 00000000 103:02 48889873 /lib/x86_64-linux-gnu/ld-2.23.so 7f8f68f16000-7f8f68f32000 rw-p 00000000 00:00 0 7f8f68f43000-7f8f68f44000 rw-p 00000000 00:00 0 7f8f68f44000-7f8f68f62000 r-xp 00000000 103:02 48890201 /lib/x86_64-linux-gnu/libudev.so.1.6.4 7f8f68f62000-7f8f68f63000 r--p 0001d000 103:02 48890201 /lib/x86_64-linux-gnu/libudev.so.1.6.4 7f8f68f63000-7f8f68f64000 rw-p 0001e000 103:02 48890201 /lib/x86_64-linux-gnu/libudev.so.1.6.4 7f8f68f64000-7f8f68f77000 rw-p 00000000 00:00 0 7f8f68f77000-7f8f68f78000 r--p 00025000 103:02 48889873 /lib/x86_64-linux-gnu/ld-2.23.so 7f8f68f78000-7f8f68f79000 rw-p 00026000 103:02 48889873 /lib/x86_64-linux-gnu/ld-2.23.so 7f8f68f79000-7f8f68f7a000 rw-p 00000000 00:00 0 7fff42482000-7fff424a4000 rw-p 00000000 00:00 0 [stack] 7fff42518000-7fff4251b000 r--p 00000000 00:00 0 [vvar] 7fff4251b000-7fff4251d000 r-xp 00000000 00:00 0 [vdso] ffffffffff600000-ffffffffff601000 r-xp 00000000 00:00 0 [vsyscall] �[31m[FATAL] [1523463428.264180369, 1503376897.164371795]: Failed to load nodelet '/floor_detection_nodelet of type hdl_graph_slam/FloorDetectionNodelet to manager velodyne_nodelet_manager'�[0m �[31m[FATAL] [1523463428.265538021, 1503376897.164371795]: Failed to load nodelet '/hdl_graph_slam_nodelet of type hdl_graph_slam/HdlGraphSlamNodelet to manager `velodyne_nodelet_manager'�[0m
�[31m[velodyne_nodelet_manager-1] process has died [pid 487, exit code -6, cmd /opt/ros/kinetic/lib/nodelet/nodelet manager __name:=velodyne_nodelet_manager __log:=/home/z/.ros/log/40bdce56-3da1-11e8-ab99-28c63f080efd/velodyne_nodelet_manager-1.log].
log file: /home/z/.ros/log/40bdce56-3da1-11e8-ab99-28c63f080efd/velodyne_nodelet_manager-1*.log�[0m
�[31m[floor_detection_nodelet-4] process has died [pid 491, exit code 255, cmd /opt/ros/kinetic/lib/nodelet/nodelet load hdl_graph_slam/FloorDetectionNodelet velodyne_nodelet_manager __name:=floor_detection_nodelet __log:=/home/z/.ros/log/40bdce56-3da1-11e8-ab99-28c63f080efd/floor_detection_nodelet-4.log].
log file: /home/z/.ros/log/40bdce56-3da1-11e8-ab99-28c63f080efd/floor_detection_nodelet-4*.log�[0m
�[31m[hdl_graph_slam_nodelet-5] process has died [pid 504, exit code 255, cmd /opt/ros/kinetic/lib/nodelet/nodelet load hdl_graph_slam/HdlGraphSlamNodelet velodyne_nodelet_manager __name:=hdl_graph_slam_nodelet __log:=/home/z/.ros/log/40bdce56-3da1-11e8-ab99-28c63f080efd/hdl_graph_slam_nodelet-5.log].


Any ideas will be appreciated.
Many thanks in advance.
Kevin

Mapping faild when used our own data

I have been able to use the data your have provided, but I had problem using my own data. I used our platform to collect data of velodyne hdl-32e and save it as *.bag file. Then I start built map by running hdl_graph_slam_501.launch. I found two problem. Firstly, the speed of mapping is not as fast as rosbag playing. When playing of rosbag is finished, the mapping is also stop. Secondly, when starting to build the map, you can build the map correctly, but when the map is over 100 m, the point cloud cannot be properly matched. Have you ever had a problem like this?

tf setup

what the default tf tree is like?? Is that the lidar x axis must be forward?

Using IMU with hdl_graph_slam

Hi, Please I would like to ask if I was to implement the hdl_graph_slam algorithm with a mobile robot will it be possible to integrate an IMU to work with the algorithm or use odometry? Also i would like to ask what is the differences between the various launch files (that is, hdl_graph_slam.launch, hdl_graph_slam_400.launch, hdl_graph_slam_500.launch and hdl_graph_slam_ford.launch) ?

data collection equipment

Dear,
Can you introduce your data collection equipment? What do the "rostopic gpsimu_driver/gpstime gpsimu_driver/imu_data gpsimu_driver/temperature" mean?

Multi-floor situation

Hi, the output is not well optimized when dealing with multi-floor laser data. Can you give me some advice on fixing it? You know, after stepping upstairs, everything goes wrong.

how to use pointcloud to further optimize generated map?

On my dataset which was gathered in suburb environment about 5km long, multiple blur edges of same object was observed in generated pointcloud map. It seems the GPS constraint will cause the trajectory to bend. Since the optimization step and the point match step is totally seperated, this phenomenon can be expected.
In VSLAM, the reprojection error and GPS constraints may be optimized together, the result may be more reliable.
So I think is there any way to optimize pointcloud matching and GPS together? or to use pointcloud further optimize the final result to get a more clear map?

Cannot use own bag file

I am using VLP16 , and the .pcap I converted using velodyne_driver ,and then record as it .bag
But when I try to use it with the your system nothing appear in Rviz , Seem like it did not detect my bag file.
The mapping run smoothly with your .bag file but not mine

crash when optimizing

1.testing Example1 (Indoor)
2.g2o:https://github.com/koide3/g2o.git

crash when optimizing:

ROS_MASTER_URI=http://localhost:11311

process[nodelet_manager-1]: started with pid [2710]
process[prefiltering_nodelet-2]: started with pid [2711]
process[scan_matching_odometry_nodelet-3]: started with pid [2712]
process[floor_detection_nodelet-4]: started with pid [2713]
process[hdl_graph_slam_nodelet-5]: started with pid [2714]
process[map2odom_publisher-6]: started with pid [2715]
[ INFO] [1533869775.044699738]: Initializing nodelet with 8 worker threads.
downsample: NONE
registration: NDT_OMP DIRECT7 1 (0 threads)
downsample: VOXELGRID 0.1
outlier_removal: RADIUS 0.5 - 2
construct solver...

Using CSparse poseDim -1 landMarkDim -1 blockordering 0

done
registration: NDT_OMP DIRECT7 1 (0 threads)

--- pose graph optimization ---
nodes: 7 edges: 10
optimizing... [nodelet_manager-1] process has died [pid 2710, exit code -11, cmd /opt/ros/kinetic/lib/nodelet/nodelet manager __name:=nodelet_manager __log:=/home/haylion/.ros/log/d05bb482-9c48-11e8-947a-2cfda189a91d/nodelet_manager-1.log].
log file: /home/haylion/.ros/log/d05bb482-9c48-11e8-947a-2cfda189a91d/nodelet_manager-1*.log
[scan_matching_odometry_nodelet-3] process has finished cleanly
log file: /home/haylion/.ros/log/d05bb482-9c48-11e8-947a-2cfda189a91d/scan_matching_odometry_nodelet-3*.log
[prefiltering_nodelet-2] process has finished cleanly
log file: /home/haylion/.ros/log/d05bb482-9c48-11e8-947a-2cfda189a91d/prefiltering_nodelet-2*.log
[floor_detection_nodelet-4] process has finished cleanly
log file: /home/haylion/.ros/log/d05bb482-9c48-11e8-947a-2cfda189a91d/floor_detection_nodelet-4*.log
[hdl_graph_slam_nodelet-5] process has finished cleanly
log file: /home/haylion/.ros/log/d05bb482-9c48-11e8-947a-2cfda189a91d/hdl_graph_slam_nodelet-5*.log

screenshot from 2018-08-10 11-05-04

Access to sample data sets

@koide3 Thank you so much for releasing this package.
I want to test it with your sample data sets. However, I have trouble downloading them.
Maybe this problem only occurs to me. So may I ask whether it is possible for you to put those data sets on a second server (google drive, dropbox, etc.)?
Thank you so much for your help!

How to save map

Hello everybody. I would like to ask how to save the map built with HDL SLAM. I am interested in testing localization. I saw that hdl_localization can load a pcd file, which is a separate application. Is localization part of HDL SLAM? If so, do I need to create my own launch file?

a possible typo?

hdl_graph_slam_nodelet.cpp
line 413
keyframe->orientation = keyframe->orientation;

Failed to load nodelet [/prefiltering_nodelet] of type [hdl_graph_slam/PrefilteringNodelet]

Hi, I am trying to implement the hdl_graph_slam in real time using the Velodyne VLP-16 LiDAR, however I keep getting this error

process[velodyne_nodelet_manager-1]: started with pid [3596]
process[prefiltering_nodelet-2]: started with pid [3597]
process[scan_matching_odometry_nodelet-3]: started with pid [3598]
process[floor_detection_nodelet-4]: started with pid [3605]
process[hdl_graph_slam_nodelet-5]: started with pid [3625]
process[map2odom_publisher-6]: started with pid [3641]
[FATAL] [1526472122.134142445]: Failed to load nodelet '/prefiltering_nodeletof typehdl_graph_slam/PrefilteringNodeletto managervelodyne_nodelet_manager'
[ INFO] [1526472122.136054231]: Initializing nodelet with 4 worker threads.
[FATAL] [1526472122.156214309]: Failed to load nodelet '/scan_matching_odometry_nodeletof typehdl_graph_slam/ScanMatchingOdometryNodeletto managervelodyne_nodelet_manager'
[prefiltering_nodelet-2] process has died [pid 3597, exit code 255, cmd /opt/ros/kinetic/lib/nodelet/nodelet load hdl_graph_slam/PrefilteringNodelet velodyne_nodelet_manager __name:=prefiltering_nodelet __log:=/home/lunet/coem2/.ros/log/b1897200-5900-11e8-b12f-9c8e99dee3fc/prefiltering_nodelet-2.log].
log file: /home/lunet/coem2/.ros/log/b1897200-5900-11e8-b12f-9c8e99dee3fc/prefiltering_nodelet-2*.log
[scan_matching_odometry_nodelet-3] process has died [pid 3598, exit code 255, cmd /opt/ros/kinetic/lib/nodelet/nodelet load hdl_graph_slam/ScanMatchingOdometryNodelet velodyne_nodelet_manager __name:=scan_matching_odometry_nodelet __log:=/home/lunet/coem2/.ros/log/b1897200-5900-11e8-b12f-9c8e99dee3fc/scan_matching_odometry_nodelet-3.log].
log file: /home/lunet/coem2/.ros/log/b1897200-5900-11e8-b12f-9c8e99dee3fc/scan_matching_odometry_nodelet-3*.log

Some help will be appreciated.

How to debug the plugin

Hi,
the bag of hdl_graph_slam is constructed by some plugins.How can I debug them if I've made some changes?
Thank You!

Map Construction

Hi, I just have a question on how the map is built. When the sensor is moved from one point to another, does the generated points on the map change? Is the map built relative to the world coordinates or relative to the sensor coordinates?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.