Git Product home page Git Product logo

lsd_slam's Introduction

LSD-SLAM: Large-Scale Direct Monocular SLAM

LSD-SLAM is a novel approach to real-time monocular SLAM. It is fully direct (i.e. does not use keypoints / features) and creates large-scale, semi-dense maps in real-time on a laptop. For more information see http://vision.in.tum.de/lsdslam where you can also find the corresponding publications and Youtube videos, as well as some example-input datasets, and the generated output as rosbag or .ply point cloud.

Related Papers

  • LSD-SLAM: Large-Scale Direct Monocular SLAM, J. Engel, T. Schöps, D. Cremers, ECCV '14

  • Semi-Dense Visual Odometry for a Monocular Camera, J. Engel, J. Sturm, D. Cremers, ICCV '13

1. Quickstart / Minimal Setup

First, install LSD-SLAM following 2.1 or 2.2, depending on your Ubuntu / ROS version. You don't need openFabMap for now.

Download the Room Example Sequence and extract it.

Launch the lsd_slam viewer:

	rosrun lsd_slam_viewer viewer

Launch the lsd_slam main ros node:

	rosrun lsd_slam_core live_slam image:=/image_raw camera_info:=/camera_info

Play the sequence:

	rosbag play ~/LSD_room.bag

You should see one window showing the current keyframe with color-coded depth (from live_slam), and one window showing the 3D map (from viewer). If for some reason the initialization fails (i.e., after ~5s the depth map still looks wrong), focus the depth map and hit 'r' to re-initialize.

2. Installation

We tested LSD-SLAM on two different system configurations, using Ubuntu 12.04 (Precise) and ROS fuerte, or Ubuntu 14.04 (trusty) and ROS indigo. Note that building without ROS is not supported, however ROS is only used for input and output, facilitating easy portability to other platforms.

2.1 ROS fuerte + Ubuntu 12.04

Install system dependencies:

sudo apt-get install ros-fuerte-libg2o liblapack-dev libblas-dev freeglut3-dev libqglviewer-qt4-dev libsuitesparse-dev libx11-dev

In your ROS package path, clone the repository:

git clone https://github.com/tum-vision/lsd_slam.git lsd_slam

Compile the two package by typing:

rosmake lsd_slam

2.2 ROS indigo + Ubuntu 14.04

We do not use catkin, however fortunately old-fashioned CMake-builds are still possible with ROS indigo. For this you need to create a rosbuild workspace (if you don't have one yet), using:

sudo apt-get install python-rosinstall
mkdir ~/rosbuild_ws
cd ~/rosbuild_ws
rosws init . /opt/ros/indigo
mkdir package_dir
rosws set ~/rosbuild_ws/package_dir -t .
echo "source ~/rosbuild_ws/setup.bash" >> ~/.bashrc
bash
cd package_dir

Install system dependencies:

sudo apt-get install ros-indigo-libg2o ros-indigo-cv-bridge liblapack-dev libblas-dev freeglut3-dev libqglviewer-dev libsuitesparse-dev libx11-dev

In your ROS package path, clone the repository:

git clone https://github.com/tum-vision/lsd_slam.git lsd_slam

Compile the two package by typing:

rosmake lsd_slam

2.3 openFabMap for large loop-closure detection [optional]

If you want to use openFABMAP for large loop closure detection, uncomment the following lines in lsd_slam_core/CMakeLists.txt :

#add_subdirectory(${PROJECT_SOURCE_DIR}/thirdparty/openFabMap)
#include_directories(${PROJECT_SOURCE_DIR}/thirdparty/openFabMap/include)
#add_definitions("-DHAVE_FABMAP")
#set(FABMAP_LIB openFABMAP )

Note for Ubuntu 14.04: The packaged OpenCV for Ubuntu 14.04 does not include the nonfree module, which is required for openFabMap (which requires SURF features). You need to get a full version of OpenCV with nonfree module, which is easiest by compiling your own version. We suggest to use the 2.4.8 version, to assure compatibility with the current indigo open-cv package.

3 Usage

LSD-SLAM is split into two ROS packages, lsd_slam_core and lsd_slam_viewer. lsd_slam_core contains the full SLAM system, whereas lsd_slam_viewer is optionally used for 3D visualization. Please also read General Notes for good results below.

3.1 lsd_slam_core

We provide two different usage modes, one meant for live-operation (live_slam) using ROS input/output, and one dataset_slam to use on datasets in the form of image files.

3.1.1 Using live_slam

If you want to directly use a camera.

rosrun lsd_slam_core live_slam /image:=<yourstreamtopic> /camera_info:=<yourcamera_infotopic>

When using ROS camera_info, only the image dimensions and the K matrix from the camera info messages will be used - hence the video has to be rectified.

Alternatively, you can specify a calibration file using

rosrun lsd_slam_core live_slam /image:=<yourstreamtopic> _calib:=<calibration_file>

In this case, the camera_info topic is ignored, and images may also be radially distorted. See the Camera Calibration section for details on the calibration file format.

3.1.2 Using dataset_slam

rosrun lsd_slam_core dataset_slam _files:=<files> _hz:=<hz> _calib:=<calibration_file>

Here, <files> can either be a folder containing image files (which will be sorted alphabetically), or a text file containing one image file per line. <hz> is the framerate at which the images are processed, and <calibration_file> the camera calibration file.

Specify _hz:=0 to enable sequential tracking and mapping, i.e. make sure that every frame is mapped properly. Note that while this typically will give best results, it can be much slower than real-time operation.

3.1.3 Camera Calibration

LSD-SLAM operates on a pinhole camera model, however we give the option to undistort images before they are being used. You can find some sample calib files in lsd_slam_core/calib.

Calibration File for FOV camera model:

fx/width fy/height cx/width cy/height d
in_width in_height
"crop" / "full" / "none" / "e1 e2 e3 e4 0"
out_width out_height

Here, the values in the first line are the camera intrinsics and radial distortion parameter as given by the PTAM cameracalibrator, in_width and in_height is the input image size, and out_width out_height is the desired undistorted image size. The latter can be chosen freely, however 640x480 is recommended as explained in section 3.1.6. The third line specifies how the image is distorted, either by specifying a desired camera matrix in the same format as the first four intrinsic parameters, or by specifying "crop", which crops the image to maximal size while including only valid image pixels.

Calibration File for Pre-Rectified Images

This one is without radial distortion correction, as a special case of ATAN camera model but without the computational cost:

fx/width fy/height cx/width cy/height 0
width height
none
width height

Calibration File for OpenCV camera model:

fx fy cx cy k1 k2 p1 p2
inputWidth inputHeight
"crop" / "full" / "none" / "e1 e2 e3 e4 0"
outputWidth outputHeight

3.1.4 Useful Hotkeys

  • r: Do a full reset

  • d / e: Cycle through debug displays (in particular color-coded variance and color-coded inverse depth).

  • o: Toggle on screen info display

  • m: Save current state of the map (depth & variance) as images to lsd_slam_core/save/

  • p: Brute-Force-Try to find new constraints. May improve the map by finding more constraints, but will block mapping for a while.

  • l: Manually indicate that tracking is lost: will stop tracking and mapping, and start the re-localizer.

3.1.5 Parameters (Dynamic Reconfigure)

A number of things can be changed dynamically, using (for ROS fuerte)

rosrun dynamic_reconfigure reconfigure_gui 

or (for ROS indigo)

rosrun rqt_reconfigure rqt_reconfigure

Parameters are split into two parts, ones that enable / disable various sorts of debug output in /LSD_SLAM/Debug, and ones that affect the actual algorithm, in /LSD_SLAM. Note that debug output options from /LSD_SLAM/Debug only work if lsd_slam_core is built with debug info, e.g. with set(ROS_BUILD_TYPE RelWithDebInfo).

  • minUseGrad: [double] Minimal absolute image gradient for a pixel to be used at all. Increase if your camera has large image noise, decrease if you have low image-noise and want to also exploit small gradients.
  • cameraPixelNoise: [double] Image intensity noise used for e.g. tracking weight calculation. Should be set larger than the actual sensor-noise, to also account for noise originating from discretization / linear interpolation.
  • KFUsageWeight: [double] Determines how often keyframes are taken, depending on the overlap to the current keyframe. Larger -> more keyframes.
  • KFDistWeight: [double] Determines how often keyframes are taken, depending on the distance to the current Keyframe. Larger -> more keyframes.
  • doSLAM: [bool] Toggle global mapping component on/off. Only takes effect after a reset.
  • doKFReActivation: [bool] Toggle keyframe re-activation on/off: If close to an existing keyframe, re-activate it instead of creating a new one. If false, the map will continually grow even if the camera moves in a relatively constrained area; If false, the number of keyframes will not grow arbitrarily.
  • doMapping: [bool] Toggle entire keyframe creating / update module on/off: If false, only tracking stays active, which will prevent rapid motion or moving objects from corrupting the map.
  • useFabMap: [bool] Use openFABMAP to find large loop-closures. Only takes effect after a reset, and requires LSD-SLAM to be compiled with FabMap.
  • allowNegativeIdepths: [bool] Allow idepth to be (slightly) negative to avoid introducing a bias for far-away points.
  • useSubpixelStereo: [bool] Compute subpixel-accurate stereo disparity.
  • useAffineLightningEstimation: [bool] EXPERIMENTAL: Correct for global affine intensity changes during tracking. Might help if you have problems with auto-exposure.
  • multiThreading: [bool] Toggle multi-threading of depth map estimation. Disable for less CPU usage, but possibly slightly less quality.
  • maxLoopClosureCandidates: [int] Maximal number of loop-closures that are tracked initially for each new keyframe.
  • loopclosureStrictness: [double] Threshold on reciprocal loop-closure consistency check, to be added to the map. Larger -> more (possibly wrong) loop-closures.
  • relocalizationTH: [double] How good a relocalization-attempt has to be to be accepted. Larger -> more strict.
  • depthSmoothingFactor: [double] How much to smooth the depth map. Larger -> less smoothing.

Useful for debug output are:

  • plotStereoImages: [bool] Plot searched stereo lines, and color-coded stereo-results. Nice visualization of what's going on, however drastically decreases mapping speed.
  • plotTracking: [bool] Plot final tracking residual. Nice visualization of what's going on, however drastically decreases tracking speed.
  • continuousPCOutput: [bool] Publish current keyframe's point cloud after each update, to be seen in the viewer. Nice visualization, however bad for performance and bandwidth.

3.1.6 General Notes for Good Results

  • Use a global shutter camera. Using a rolling shutter will lead to inferior results.
  • Use a lens with a wide field-of-view (we use a 130° fisheye lens).
  • Use a high framerate, at least 30fps (depending on the movements speed of course). For our experiments, we used between 30 and 60 fps.
  • We recommend an image resolution of 640x480, significantly higher or lower resolutions may require some hard-coded parameters to be adapted.
  • LSD-SLAM is a monocular SLAM system, and as such cannot estimate the absolute scale of the map. Further it requires sufficient camera translation: Rotating the camera without translating it at the same time will not work. Generally sideways motion is best - depending on the field of view of your camera, forwards / backwards motion is equally good. Rotation around the optical axis does not cause any problems.
  • During initialization, it is best to move the camera in a circle parallel to the image without rotating it. The scene should contain sufficient structure (intensity gradient at different depths).
  • Adjust minUseGrad and cameraPixelNoise to fit the sensor-noise and intensity contrast of your camera.
  • If tracking / mapping quality is poor, try decreasing the keyframe thresholds KFUsageWeight and KFDistWeight slightly to generate more keyframes.
  • Note that LSD-SLAM is very much non-deterministic, i.e. results will be different each time you run it on the same dataset. This is due to parallelism, and the fact that small changes regarding when keyframes are taken will have a huge impact on everything that follows afterwards.

3.2 LSD-SLAM Viewer

The viewer is only for visualization. It can also be used to output a generated point cloud as .ply. For live operation, start it using

rosrun lsd_slam_viewer viewer

You can use rosbag to record and re-play the output generated by certain trajectories. Record & playback using

rosbag record /lsd_slam/graph /lsd_slam/keyframes /lsd_slam/liveframes -o file_pc.bag
rosbag play file_pc.bag

You should never have to restart the viewer node, it resets the graph automatically.

If you just want to lead a certain pointcloud from a .bag file into the viewer, you can directly do that using

rosrun lsd_slam_viewer viewer file_pc.bag

3.2.1 Useful Hotkeys

  • r: Reset, will clear all displayed data.

  • w: Print the number of points / currently displayed points / keyframes / constraints to the console.

  • p: Write currently displayed points as point cloud to file lsd_slam_viewer/pc.ply, which can be opened e.g. in meshlab. Use in combination with sparsityFactor to reduce the number of points.

3.2.2 Parameters (Dynamic Reconfigure)

  • showKFCameras : Toggle drawing of blue keyframe camera-frustrums. min: False, default: True, max: True
  • showKFPointclouds : Toggle drawing of point clouds for all keyframes. min: False, default: True, max: True
  • showConstraints : Toggle drawing of red/green pose-graph constraints. min: False, default: True, max: True
  • showCurrentCamera : Toggle drawing of red frustrum for the current camera pose. min: False, default: True, max: True
  • showCurrentPointcloud : Toggle drawing of the latest point cloud added to the map. min: False, default: True, max: True
  • pointTesselation : Size of points. min: 0.0, default: 1.0, max: 5.0
  • lineTesselation : Width of lines. min: 0.0, default: 1.0, max: 5.0
  • scaledDepthVarTH : log10 of threshold on point's variance, in the respective keyframe's scale. min: -10.0, default: -3.0, max: 1.0
  • absDepthVarTH : log10 of threshold on point's variance, in absolute scale. min: -10.0, default: -1.0, max: 1.0
  • minNearSupport : Only plot points that have #minNearSupport similar neighbours (higher values remove outliers). min: 0, default: 7, max: 9
  • cutFirstNKf : Do not display the first #cutFirstNKf keyframe's point clouds, to remove artifacts left-over from the random initialization. min: 0, default: 5, max: 100
  • sparsifyFactor : Only plot one out of #sparsifyFactor points, selected at random. Use this to significantly speed up rendering for large maps. min: 1, default: 1, max: 100
  • sceneRadius : Defines near- and far clipping plane. Decrease to be able to zoom in more. min: 1, default: 80, max: 200
  • saveAllVideo : Save all rendered images... only use if you know what you are doing. min: False, default: False, max: True
  • keepInMemory : If set to false, the point cloud is only stored in OpenGL buffers, and not kept in RAM. This greatly reduces the required RAM for large maps, however also prohibits saving / dynamically changing sparsifyFactor and variance-thresholds. min: False, default: True, max: True

4 Datasets

For convenience we provide a number of datasets, including the video, lsd-slam's output and the generated point cloud as .ply. See http://vision.in.tum.de/lsdslam

5 License

LSD-SLAM is licensed under the GNU General Public License Version 3 (GPLv3), see http://www.gnu.org/licenses/gpl.html.

For commercial purposes, we also offer a professional version under different licencing terms.

6 Troubleshoot / FAQ

How can I get the live-pointcloud in ROS to use with RVIZ?

You cannot, at least not on-line and in real-time. The reason is the following:

In the background, LSD-SLAM continuously optimizes the pose-graph, i.e., the poses of all keyframes. Each time a keyframe's pose changes (which happens all the time, if only by a little bit), all points from this keyframe change their 3D position with it. Hence, you would have to continuously re-publish and re-compute the whole pointcloud (at 100k points per keyframe and up to 1000 keyframes for the longer sequences, that's 100 million points, i.e., ~1.6GB), which would crush real-time performance.

Instead, this is solved in LSD-SLAM by publishing keyframes and their poses separately:

  • keyframeGraphMsg contains the updated pose of each keyframe, nothing else.
  • keyframeMsg contains one frame with it's pose, and - if it is a keyframe - it's points in the form of a depth map.

Points are then always kept in their keyframe's coodinate system: That way, a keyframe's pose can be changed without even touching the points. In fact, in the viewer, the points in the keyframe's coodinate frame are moved to a GLBuffer immediately and never touched again - the only thing that changes is the pushed modelViewMatrix before rendering.

Note that "pose" always refers to a Sim3 pose (7DoF, including scale) - which ROS doesn't even have a message type for.

If you need some other way in which the map is published (e.g. publish the whole pointcloud as ROS standard message as a service), the easiest is to implement your own Output3DWrapper.

Tracking immediately diverges / I keep getting "TRACKING LOST for frame 34 (0.00% good Points, which is -nan% of available points, DIVERGED)!"

  • double-check your camera calibration.
  • try more translational movement and less roational movement

lsd_slam's People

Contributors

artivis avatar dvad avatar jakobengel avatar pierrickkoch avatar pmoulon avatar puzzlepaint 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  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

lsd_slam's Issues

Map not being created properly around the corner

Hi I am using parrot ar drone to create maps with lsd slam but when I move the camera around the corner, the map for that particular image data set/ stream is not created properly it just puts that part on top of the original map. Im using both camera rotation and translation.

what going wrong here ?

Trying to compile on Jetson TK1

Hi!

So I am trying to compile LSD-SLAM on my Jetson TK1, however I ran into an issue while running rosmake.

First, I was getting an error message telling me that a ';' was expected in Frame.cpp around line 530 (in the lsd_slam_core/src/Datastructures directory). As I was looking through the code I saw that this part was only called if -DENABLE_SSE is set. Otherwise it would go to the next part if -DENABLE_NEON is set. Curious as to whether this would make it work (I must honestly admit that I do not know what I was actually changing) I changed -DENABLE_SSE to -DENABLE_NEON in the CMakeLists.txt. After calling rosmake lsd_slam again, it looked like it worked - this time it ran longer than before. Now, however, I am getting these error messages from the assembler:

/tmp/ccnTsMpJ.s: Assembler messages:
/tmp/ccnTsMpJ.s:10805: Error: VFP single precision register expected -- vldmia r0,{q10}' /tmp/ccnTsMpJ.s:10811: Error: selected FPU does not support instruction --vadd.f32 q0,q0,q2'
/tmp/ccnTsMpJ.s:10812: Error: selected FPU does not support instruction -- vadd.f32 q1,q1,q3' /tmp/ccnTsMpJ.s:10813: Error: selected processor does not support Thumb modevpadd.f32 d0,d0,d1'
/tmp/ccnTsMpJ.s:10814: Error: selected processor does not support Thumb mode vpadd.f32 d1,d2,d3' /tmp/ccnTsMpJ.s:10815: Error: selected FPU does not support instruction --vmul.f32 q0,q0,q10'
make[3]: *** [CMakeFiles/lsdslam.dir/src/DataStructures/Frame.cpp.o] Error 1

This looks like the compiler generated code that the hardware doesn't support? Please let me know if there's anything I could try to make this work!

Thanks a lot,
Marc

Get the position of camera and pointcloud in the slam-viewer

Sorry for the similar issue with #24 ,but the question is a little different.
My purpose is to get the updated position of camera and all the pointcloud in order to mapping to the 2-d map. And publish it as a topic in ROS. (maybe ROSOutput3DWrapper::publishTrajectory in ROSOutput3DWrapper, but it is still not implemented )
Therefore, other node on the ROS can easily get the result of LSD-SLAM.
(Just like the way slam-viewer get the result )

So i started working on the code of slam-viewer.
Below is what i understand with the code,but i am not sure if i understand it correctly:
i think i can get the (x,y,z,intensity) of pointcloud from KeyFrameGraphDisplay::draw() in KeyFrameGraphDisplay.cpp. And the function flushpc() in KeyFrameDisplay deal with the position of pointclouds.

However i had difficulty to understand how the cam position being processed. i think "camToWorld" in KeyFrameDisplay.cpp may be what i need. But the data structure has stopped me, especially Sim3f, which is the type of "camToWorld"

My question is

  1. is the variable "camToWorld" in KeyFrameDisplay.cpp storing the cam position?
  2. should i know how the Sophus group work?(it seem involved lots of linear algebra that i had no clue ) Is there any suggested document i can ref before i go further with this code?
    3.Or i just digging into the wrong direction?

Thanks a lot.
Regards,

Unable to locate package

While trying to install the system dependencies I get the following error:

"E: Unable to locate package libqglviewer-dev"

I am calling
sudo apt-get install ros-indigo-libg2o ros-indigo-cv-bridge liblapack-dev libblas-dev freeglut3-dev libqglviewer-dev libsuitesparse-dev

from ~/rosbuild_ws/package_dir

Does any other software have to be downloaded to get the package? I am new to ROS so any help would really be appreciated.

Time

Hi,

I have a question regarding the time of a keyframe. In the ROS msg, it has the following field: float64 time.

What time does this field represent? The time the keyframe was published, or perhaps the time of the source image where the keyframe was based on?

For my application I need to know to which source image the keyframe's pointcloud corresponds to.

Thanks for the help,
Ruud

liveframes vs. keyframes

Hi,

What is the difference between the message published on the /lsd_slam/keyframes and /lsd_slam/liveframes ?

Best,
Ruud

question about calibration file

Dear all,

Take example as Desk Sequence (png file and bag file) for testing.
For png images, the focal length and principle setting and distortion setting in file cameraCalibration.cfg is:
0.771557 1.368560 0.552779 0.444056 1.156010
640 480
0.771557 1.368560 0.552779 0.444056 1.156010
640 480
That means: fx=0.771557, fy=1.368560, cx= 0.552779,cy=0.444056, distortion param = 1.156010

While for /camera_info within LSD_room.bag file are:
K[0]: 254.326954
K[1]: 0
K[2]: 267.381897
K[3]: 0
K[4]: 375.934381
K[5]: 231.599091
K[6], K[7]: 0
K[8]: 1
That means: fx=254.326954, fy=375.934381, cx= 267.381897,cy= 231.599091 and also D is found to be 0.

Why are these two K settings(Camera matrix) so different significantly?

Hope someone can hint me for this question.

THX~
Milton

Obtaining camera positions from .ply

Hi,

I'm still in my learning stages of ROS and SLAM but I am wondering if I there is a way of getting the coordinates for the camera from the generated .ply file.

I've got everything running and I'm able to output bags and .ply files from sequences of frames acquired with my calibrated camera. I also installed Meshlab and I'm able to display the point cloud but again don't seem to be able to retrieve the camera locations.

I remember from other multi-view geometry packages such as bundler that the output file showed clearly the location of each point, their intensities and the camera locations. The .ply shows a lot of gibberish and if I do as in issue #22 I still don't see anything in clear text.

Thanks a lot.

Regards,

J

live_slam crashes on startup

I'm using the LSD_room.bag dataset and running:

rosrun lsd_slam_core live_slam image:=image_raw camera_info:=camera_info

on a 32bit Ubuntu 12.04 computer with ROS hydro.

I'm having the following error, which seems to be related with Eigen (probably one of those MAKE_ALIGNED macros is missed in some clasess):

WAITING for ROS camera calibration!
Received ROS Camera Calibration: fx: 254.326950, fy: 375.934387, cx: 267.381897, cy: 231.599091 @ 640x480
RECEIVED ROS camera calibration!
Started mapping thread!
Started  constraint search thread!
Started optimization thread 
Doing Random initialization!
live_slam: /usr/include/eigen3/Eigen/src/Core/DenseStorage.h:69: Eigen::internal::plain_array::plain_array() [with T = double, int Size = 4, int MatrixOrArrayOptions = 0]: Assertion `(reinterpret_cast(array) & 0xf) == 0 && "this assertion is explained here: " "http://eigen.tuxfamily.org/dox-devel/TopicUnalignedArrayAssert.html" " **** READ THIS WEB PAGE !!! ****"' failed.
Aborted (core dumped)

PointCloud Viewer window shows only the moving camera but no point cloud

Hi, I have tried to run lsd_slam for several days but still got no successful result, and I need some suggestions to find out where the problem is.

The issue I've encountered is that the code seemed keeping running (and it also lost tracking frequently, but it's might be another issue), and the moving camera was shown in the PointCloud Viewer window. However, no point cloud was shown. The following screenshot shows my result (I changed the code to alter the camera line color):

lsd_slam_viewer_camera_only

Even when I followed the Quickstart instruction to run lsd_slam with LSD_room.bag file, the results were all the same (it lost tracking at random frame, around after 1000th frame).

I traced the source code with printf and found the program always touched the following part in KeyFrameDisplay::drawPC():

if (! vertexBufferIdValid )
{
    return ;
}

Also, when I pressed Ctrl-w on PointCloud Viewer window when lsd_slam was running with LSD_room.bag, the terminal always returned

Have 0 points, 0 keyframes, 0 constraints. Displaying 0 points.

So the program generated no point cloud, even when the tracking was still working?

At least I should get some reasonable results with the LSD_room.bag example, but I didn't. Did I miss something essential? I need some hints and helps from you. Thank you.

Running on onboard computers [Odroid U3 Hydro 12.04 success]

Hey Guys,

I've been eagerly following your progress for a long time. I had two MAVs on standby waiting for LSD-SLAM integration as soon as it released :)

My system consists of a large copter with 2 cameras, bottom and front facing. Running SVO on the downward camera and tightly coupled optical flow approach for velocity recovery in case of map loss. The forward camera was initially supposed to be a stereo head, but then I decided to try out LSD SLAM. In near future, will probably also be running optical flow on front camera too for robustness.

LSD-SLAM will be used for vehicle state estimation and navigation. The pose estimate from LSD-SLAM is integrated with pose from SVO with IMU data in an EKF for metric scaling and used for MAV's control . Other sensors like GPS, rangefinder, etc. are also integrated in the EKF.

Presently, the onboard computer is an Odroid U3 running 12.04 and ROS Hydro. Will be testing LSD SLAM independently on this testbed, before moving onto the final copter and much more powerful onboard i7 computer.

I had make some small hacks to get it to run LSD-SLAM, especially due to missing dependencies, etc.
Wanted to do a wiki entry to help others, but was unsure whether I should do so without your permission :

  1. Remove lsd_slam_viewer due to QGLViewer dependency. Couldn't get package, could not compile from source either.
  2. Remove viewer dependency from core
  3. Move external keyframeGraph messages from the viewer into core.
  4. Use -mfpu=neon and -DENABLE_NEON compilation flags to enable NEON on the Odroid.
  5. Disable debugWindow as there is a problem with XInitThreads. Any idea on this???

Hope you will be glad to see my work :)

P.S - What is the coordinate system considering the camera frame? X outward from lens, Y left, Z down?

Kabir

libX11.so.6: error adding symbols: DSO missing from command line collect2: error: ld returned 1 exit status

During compilation lsd_slam(ROS indigo + ubuntu 14.04), I get following error.

Linking CXX executable ../bin/live_slam
/usr/bin/ld: CMakeFiles/live_slam.dir/src/main_live_odometry.cpp.o: undefined reference to symbol 'XInitThreads'
//usr/lib/x86_64-linux-gnu/libX11.so.6: error adding symbols: DSO missing from command line
collect2: error: ld returned 1 exit status
make[3]: *** [../bin/live_slam] Error 1
make[3]: Leaving directory /home/user/ros_workspace/lsd_slam/lsd_slam_core/build' make[2]: *** [CMakeFiles/live_slam.dir/all] Error 2 make[2]: Leaving directory/home/user/ros_workspace/lsd_slam/lsd_slam_core/build'
make[1]: *** [all] Error 2
make[1]: Leaving directory `/home/user/ros_workspace/lsd_slam/lsd_slam_core/build'

Tracking Lost after small number of frames, "Cholesky failure"

The closed issue with the same problem does not seem to affect my case at all. I have calibrated an admittedly ill-suited camera (stock Logitech webcam, roughly 70 deg FOV, similar setup to this guy). I frequently get:

TRACKING LOST for frame 34 (0.00% good Points, which is -nan% of available points, DIVERGED)!

When I can keep the algorithm running for longer (around a minute), it will fail with:

int g2o::csparse_extension::cs_cholsolsymb(const cs_di_, double_, const cs_dis_, double_, int*): cholesky failed!
Cholesky failure, writing debug.txt (Hessian loadable by Octave)
terminate called after throwing an instance of 'Sophus::ScaleNotPositive'

I used the openCV camera calibrator, and my calibration file is as follows:

663.64 655.32 332.39 248.66 -0.0197 -0.123 0.0015 -0.0061
800 600
crop
640 480

Any idea what is wrong?

Tracking issues?

When moving in a circle (in this picture) the graph seems to think I'm moving tangentially along a wall, and the point cloud is literally a cloud.

lsd-slam broken

Actually, it seems no matter how I move it always seems to think I'm translating. The red constraint lines means that the constraints were bad, and if I add a print of the number of contraints added at then end of findConstraintsForNewKeyFrames(...) the number is 2 for the first 10 or so updates then, predominately 0 with the occasional 1 or 2 (when I start revisiting known keyframes)

Thought this might be partially due to not having openFABMAP but adding that made no difference.

Could g2o have changed internally? (I'm using a build from their github)

My only other thought is that it's being caused by a bad camera calibration. Which is quite possible as the PTAM calibrator refuses to go below about 2 RMS pixel error for this camera.

How to install LSD-SLAM?

I installed ros indgo in 14.04 ubuntu

However, I don't know how to set up lsd_slam_core for using live_slam and dataset_slam

Also I am really wondering what is meant of image:= _calib:=<calibration_file>. Shoulld I fix it?

TRACKING LOST for frame x (x = small number) and "cholesky failed!"

I read your recommendations about having CCD, fps, not rotating/moving sideways and wide angle lens. My initial setup was things I had laying around (ps3 eye) and unfortunately tests showed that algorithm wasn't capable of tracking.

There were two main problems what program indicated:

TRACKING LOST for frame 34 (0.00% good Points, which is -nan% of available points, DIVERGED)!

and quite frequent...

int g2o::csparse_extension::cs_cholsolsymb(const cs_di_, double_, const cs_dis_, double_, int*): cholesky failed!
Cholesky failure, writing debug.txt (Hessian loadable by Octave)
terminate called after throwing an instance of 'Sophus::ScaleNotPositive'
what(): Sophus exception: Scale factor is not positive
Aborted (core dumped)

I was wondering might I be doing something wrongly or/and my problems come from my setup (is there any hope getting lsd_slam to work with ps3 eye -> cmos, 30 fps and not wide angle (75 deg))?

All help appreciated.

Point Cloud Custom Viewer

Hi,

I'm testing LSD-SLAM and I'm very impressed with the results. At this moment, I would like to make the code ROS-independently. In the first time, I need to get the pointcloud data and plot in my C++ application. How can I get these data?

Thanks.

Cant see anything in Point Cloud Window

Hi I am using LSD-SLAm with Parrot Ardrone 2.0. First I was using the camera calibration file from the desk sequence example just for testing and now I just the changed the camera calibration file but it doesnt display anything in the point cloud window whereas previously point cloud was being generated but wasnt accurate. This is my camera calibration file

0.771557 1.368560 0.552779 0.444056 1.156010
640 360
0.771557 1.368560 0.552779 0.444056 1.156010
640 480

What am I doing wrong here?

calibration file for dataset_slam

Hello,

I am trying to use the dataset_slam use case of the algorithm but I lose tracking in a couple frames and the lsd_slam goes over rest of the images very fast. I believe my problem is creating the calibration file but I couldn't find a solution myself.

The calibration file is as follows (converted from yaml to ini for easier reading):

width
640
height
480

camera matrix
1055.37849 0.00000 315.68028
0.00000 1053.85271 205.37223
0.00000 0.00000 1.00000

distortion
-0.51926 0.34129 0.00533 -0.00140 0.00000

rectification
1.00000 0.00000 0.00000
0.00000 1.00000 0.00000
0.00000 0.00000 1.00000

projection
1001.52264 0.00000 314.22782 0.00000
0.00000 1022.16687 203.95875 0.00000
0.00000 0.00000 1.00000 0.00000

I create the calibration file LSD SLAM requires from the K matrix as mentioned so the calibration file I use during calling dataset_slam is:

1055.37848633721 1053.85270577403 315.680278553583 205.372229361795 0
640 480
none
640 480

What am I doing wrong?

I have the bag file of the same set of images, which seem to work for a couple hundred frames. That's why I think my problem is the calibration file. I would like to use the dataset_slam to test the hz=0 option.

Thanks,

How to use my own dataset to do experiment?

I installed lsd slam correctly and the LSD_room.bag example works well. How to use video stream file e.g. mp4 to conduct experiment? And how to use AR Drone 2 to do live slam? Thanks in advance, any suggestion would be appreciate.

no window live_slam !!! and no tracking!

Hello again!
I started all over again) to reinstall Ubuntu 14.04, ROS Indigo and installed Opencv 2.4.8 https://github.com/Itseez/opencv/tree/2.4.8.x-prep

Installed lsd-slam with openFabMap and uncommented line in lsd_slam_core / CMakeLists.txt

Installation problems was not, but now at start


slava@slava-ubuntu:~$ rosrun lsd_slam_core live_slam image:=/image_raw camera_info:=/camera_info
WAITING for ROS camera calibration!
Received ROS Camera Calibration: fx: 254.326950, fy: 375.934387, cx: 267.381897, cy: 231.599091 @ 640x480
RECEIVED ROS camera calibration!
Started mapping thread!
Started constraint search thread!
Doing Random initialization!
Started optimization thread
started image display thread!
Done Random initialization!
init done
opengl support available
TRACKING LOST for frame 574 (0,00% good Points, which is 16,67% of available points, DIVERGED)!
Backward-Jump in SEQ detected, but ignoring for now.


and rosbag play -l LSD_room.bag
and rosrun lsd_slam_viewer viewer

no window live_slam !!! and no tracking!

viewer window appears

https://drive.google.com/file/d/0B_w8l8HXXdd8QzZWcmNiMVBpUFk/view?usp=sharing

Help me please!

questions about post-process for the 3D mapping (*.ply)

Dear all,

I had some questions about post-process for the 3D mapping result which I saved as pc.ply file.
My plan is to load pc.ply using PCL (Point Cloud Library). The following is my code for reading ply file:

include <iostream

include <pcl/io/pcd_io.h

include <pcl/io/ply_io.h

include <pcl/point_types.h

int main (int argc, char** argv)
{
pcl::PointCloudpcl::PointXYZI::Ptr cloud (new pcl::PointCloudpcl::PointXYZI);

if (pcl::io::loadPLYFilepcl::PointXYZI ("pc.ply", cloud) == -1) // load the file
{
PCL_ERROR ("Couldn't read file pc.ply\n");
return (-1);
}

std::cout << "Loaded "
<< cloud->width * cloud->height
<< " data points from file test.ply with the following fields: "
<< std::endl;
for (size_t i = 0; i < cloud->points.size (); ++i)
std::cout << " " << cloud->points[i].x
<< " " << cloud->points[i].y
<< " " << cloud->points[i].z<< std::endl;

return (0);
}

output result (parsing ply error)

./ply_read
[pcl::PLYReader] pc.ply:8: parse error
[pcl::PLYReader::read] problem parsing header!
[pcl::PLYReader::read] problem parsing header!
Couldn't read file pc.ply

I think the parsing error due to the wrong pointcloud template. But I' m confused about which pointcloud template I should choose because the format of the ply output of LSD_SLAM is not described clearly.

Could someone give me some hints to fix it?
THX!

Best regards,
Milton

No Viewer, No map

Hi,

 The compiling went well and there were no errors in the destop which installed Ubuntu14.04 and ROS indigo.

  I am using ASUS Xtion's monocular camera. So after executing $roslaunch openni_launch openni.launch and $ rosrun lsd_slam_core live_slam /image:=/camera/rgb/image_mono  /camera_info:=/camera/rgb/camera_info

  It displayed the following but without any map and viewer : 

  WAITING for ROS camera calibration!

Received ROS Camera Calibration: fx: 525.000000, fy: 525.000000, cx: 319.500000, cy: 239.500000 @ 640x480
RECEIVED ROS camera calibration!
Started constraint search thread!
Started mapping thread!
Doing Random initialization!
Started optimization thread
started image display thread!
Done Random initialization!
Fontconfig error: "/etc/fonts/conf.d/65-khmer.conf", line 14: out of memory
Fontconfig error: "/etc/fonts/conf.d/65-khmer.conf", line 23: out of memory
Fontconfig error: "/etc/fonts/conf.d/65-khmer.conf", line 32: out of memory
init done
opengl support available

The rqt_graph has displayed that /LSD_SLAM node has been connected with /camera/rgb/image_mono.

There is no map or viewer! Could anyone figure out how to solve this problem? Thanks in advance!

Issue running LSD_room.bag example

When executing: $ rosbag play ~/LSD_room.bag
the following happens.

OpenCV Error: Assertion failed (scn == 1 && (dcn == 3 || dcn == 4)) in cvtColor, file /build/buildd/opencv-2.4.8+dfsg1/modules/imgproc/src/color.cpp, line 3789
terminate called after throwing an instance of 'cv::Exception'
what(): /build/buildd/opencv-2.4.8+dfsg1/modules/imgproc/src/color.cpp:3789: error: (-215) scn == 1 && (dcn == 3 || dcn == 4) in function cvtColor

and kills the process.

I am on xubuntu 14.04.1.

EDIT: It might be relevant that this is happening in a virtualbox.

live_slam and dataset_slam is not working

Hello,

I'm working on Linux Ubuntu 12.04.5 LTS with ROS Fuerte.

I’m currently working on a drone project which consists on making the 3D reconstruction of the environment. I am now in the preliminary tests phase of the 3D reconstruction via multiple algorithms in order to determine which is the most relevant.

This said, while testing the LSD-SLAM algorithm, I encountered some problems and I can’t seem to be able to generate a good cloud of points. The camera has been recalibrated 3 times to be sure we got coherent values (because I thought that the problem could be a bad calibration), but the reconstruction is still bad.

I have a set of images taken by a drone with its OpenCV calibration parameters; you will also find the information in the calibImages.cfg file with its coefficients. All this taken in consideration, I get with following command :

rosrun lsd_slam_core dataset _files:=/home/djeef/Documents/TER/TER_img_drones _calib:=/home/djeef/Documents/calibImages.cfg _hz:=30

  • In the "best case" scenario :

Reading Calibration from file /home/djeef/Documents/calibImages.cfg ... found!
found OpenCV camera model, building rectifier.
Input resolution: 640 480
In: 738.035034 738.035034 309.750183 227.734238 -0.139448 0.208432 0.000000 0.000000
Out: Crop
Output resolution: 640 480
Started mapping thread!
Started constraint search thread!
Started optimization thread
found 999 image files in folder /home/djeef/Documents/TER/TER_img_drones!
Doing Random initialization!
started image display thread!
Done Random initialization!
TRACKING LOST for frame 15 (0.00% good Points, which is -nan% of available points, DIVERGED)!
...

  • Or in the worst case scenario :

Reading Calibration from file /home/djeef/Documents/calibImages.cfg ... found!
found OpenCV camera model, building rectifier.
Input resolution: 640 480
In: 738.035034 738.035034 309.750183 227.734238 -0.139448 0.208432 0.000000 0.000000
Out: Crop
Output resolution: 640 480
Started mapping thread!
Started constraint search thread!
Started optimization thread
found 999 image files in folder /home/djeef/Documents/TER/TER_img_drones!
Doing Random initialization!
started image display thread!
Done Random initialization!
warning: reciprocal tracking on new frame failed badly, added odometry edge (Hacky).
warning: reciprocal tracking on new frame failed badly, added odometry edge (Hacky).
int g2o::csparse_extension::cs_cholsolsymb(const cs_di_, double_, const cs_dis_, double_, int*): cholesky failed!
Cholesky failure, writing debug.txt (Hessian loadable by Octave)
terminate called after throwing an instance of 'Sophus::ScaleNotPositive'
what(): Sophus exception: Scale factor is not positive
Abandon (core dumped)

I tested the algorithm with this calibration file, when it's on "crop" or "full" mode or the "e1 e2 e3 e4 0", I get the problem I described above. When I use "none" I get :

Reading Calibration from file /home/djeef/Documents/calibImages.cfg ... found!
found OpenCV camera model, building rectifier.
Input resolution: 640 480
In: 738.035034 738.035034 309.750183 227.734238 -0.139448 0.208432 0.000000 0.000000
NO RECTIFICATION
Output resolution: 640 480
OpenCV Error: Assertion failed (func != 0) in transpose, file /tmp/buildd/ros-fuerte-opencv2-2.4.2-1precise-20130312-1306/modules/core/src/matrix.cpp, line 1885
terminate called after throwing an instance of 'cv::Exception'
what(): /tmp/buildd/ros-fuerte-opencv2-2.4.2-1precise-20130312-1306/modules/core/src/matrix.cpp:1885: error: (-215) func != 0 in function transpose

Intrinsic parameters :
Res : 640x480
cx : 309.750187
cy : 227.734240
fx : 738.0350082
fy : 738.0350082
k1 : -0.1394478
k2 : 0.208432
k3 : 0
p1 : 0
p2 : 0

My calibration file :
738.0350082 738.0350082 309.750187 227.734240 -0.1394478 0.208432 0 0
640 480
crop
640 480

I also tested with a monocular camera; it gives me a black screen. Here are its intrinsic parameters, I saw here (#16) that the problem could be coming from the fact that the camera I'm using is an RGB camera and not a monochrome camera :

Intrinsic parameters :
Res : 640x480
fx : 675.471
fy : 676.928
cx : 317.989
cy : 237.301
k1 : 0.152314
k2 : -1.26394
k3 : 2.4048
p1 : -0.000654936
p2 : 0.000568698

My calibration file :
675.471008 676.927979 317.898010 237.300995 0.152314 -1.263940 -0.000655 0.000569
640 480
crop
640 480

Spiky/floating particules problem with ROSBags

Hello,

My lab is hoping to use LSD-SLAM as the mapping mechanism for our quadrotor bridge inspection project. I have been getting really low quality results with a GoPro (every object is spiking out from/to the camera and there are lots of points just floating in the air). I thought I just had really bad camera calibrations but running the various ROS bags make me think something else might be happening.

When I run the ROS Bags, I am getting some similar artifacts (though perhaps not as bad). There are points floating in mid air and the geometry is kinda spiky. If I may ask, do you know what could cause this sort of behavior?

Thanks,
Charlie West

I dont' totally know about error

rosrun lsd_slam_core live_slam /image:= _calib:=<calibration_file>

In this senntence what is mean of yourstream topic. I know calibration_file maybe it's name is camera.cfg

plz tell me what is mean of yourstream topic

Opencv error

Following was what I got on running Room dataset.

WAITING for ROS camera calibration!
Received ROS Camera Calibration: fx: 254.326950, fy: 375.934387, cx: 267.381897, cy: 231.599091 @ 640x480
RECEIVED ROS camera calibration!
Doing Random initialization!
Started mapping thread!
Started constraint search thread!
Started optimization thread
OpenCV Error: Assertion failed (k == STD_VECTOR_MAT) in create, file /build/buildd/opencv-2.4.8+dfsg1/modules/core/src/matrix.cpp, line 1557
terminate called after throwing an instance of 'cv::Exception'
what(): /build/buildd/opencv-2.4.8+dfsg1/modules/core/src/matrix.cpp:1557: error: (-215) k == STD_VECTOR_MAT in function create

Aborted (core dumped)

Segmentation fault (core dumped)

hi
i followed the instruction
Launch the lsd_slam viewer:

    rosrun lsd_slam_viewer viewer

Launch the lsd_slam main ros node:

    rosrun lsd_slam_core live_slam image:=/image_raw camera_info:=/camera_info

Play the sequence:

    rosbag play ~/LSD_room.bag

and have a segmentation fault error

Then i dig in the function to check out where is the error using print and find the error is at the frame.cpp

if (width % 8 == 0)
{
__m128 p025 = _mm_setr_ps(0.25f,0.25f,0.25f,0.25f);
printf("m128 p025 \n");
const float* maxY = source+width_height;
for(const float
y = source; y < maxY; y+=width_2)
{
const float
maxX = y+width;
printf("__m128 p025 y%f \n",&y);
//if(maxX
for(const float* x=y; x < maxX; x += 8)
{
printf("__m128 p025 x%f %f\n",&x,&maxX);
// i am calculating four dest pixels at a time.

            __m128 top_left = _mm_load_ps((float*)x);
            printf("_mm_load_ps");
            __m128 bot_left = _mm_load_ps((float*)x+width);
            __m128 left = _mm_add_ps(top_left,bot_left);
            printf("left");
            __m128 top_right = _mm_load_ps((float*)x+4);
            __m128 bot_right = _mm_load_ps((float*)x+width+4);
            __m128 right = _mm_add_ps(top_right,bot_right);
            printf("right");

            __m128 sumA = _mm_shuffle_ps(left,right, _MM_SHUFFLE(2,0,2,0));
            __m128 sumB = _mm_shuffle_ps(left,right, _MM_SHUFFLE(3,1,3,1));
            printf("sumB");

            __m128 sum = _mm_add_ps(sumA,sumB);
            sum = _mm_mul_ps(sum,p025);

            _mm_store_ps(dest, sum);
            printf("_mm_store_ps");
            dest += 4;
        }
    }

    data.imageValid[level] = true;
    return;
}

I add the print and the outcome is shown below

numData[level] > 0
pyrIdepthVarSource
buildImage
__m128 p025
__m128 p025 y0.000000
__m128 p025 x-0.124992 -0.000000
Segmentation fault (core dumped)

previous are the print function from caller function.
is there anyway to fix this error?

dataset_slam not getting past GUI

System:
Ubuntu 14.04 64bit
rosdistro: indigo
rosversion: 1.11.9
OpenCV 2.4.10.1 (Compiled with CUD Support)

I initialize roscore in a terminal. Loads fine and accepts connections.

I then, in another terminal window, run the command:

rkhan@rkhanXPS:~/repos/rosbuild_ws$ rosrun lsd_slam_core dataset_slam _files:=/home/rkhan/Downloads/LSD_room/images/ _hz:=0 _calib:=/home/rkhan/Downloads/LSD_room/cameraCalibration.cfg

This is the dataset provided on the site.

The following output is show from the software:
Reading Calibration from file /home/rkhan/Downloads/LSD_room/cameraCalibration.cfg ... found!
found ATAN camera model, building rectifier.
Input resolution: 640 480
In: 0.397386 0.783197 0.417784 0.482498 0.000000
Out: 0.397386 0.783197 0.417784 0.482498 0.000000
Output resolution: 640 480
Prepped Warp matrices
Started constraint search thread!
Started optimization thread
Started mapping thread!
found 2702 image files in folder /home/rkhan/Downloads/LSD_room/images/!
Doing Random initialization!
started image display thread!
Done Random initialization!
init done
opengl support available

At this point the program sits idle. In the program "top", I see it using 2%-3% of CPU load, but that's it.
There is another window shown "DebugWindow DEPTH", but it is "frozen"/unreponsive from it's creation and turns grey/black by Ubuntu to indicate as such. There's no image in it and it's size is very small.

Please help, thank you.

Tracking lost for frame

Hi Im using Lsd SLam with images collected with parrot drone and trying to make lsd slam work with parrot. In one of the data sets I collect it says tracking lost for frame, whats causing that to happen ?

Im using java to turn the images to gray scale and changing their original resolution from 640 x 360 to 640 x 480 and Im using the same calibration file from LSD_slam room. It does builds some of the map but then tracking is lost so are the changes Ive done, affecting that in any case??

Cheers !

no "LSDParamsConfig.h" and "LSDDebugParamsConfig.h" header

when I compile LSD_SLAM, I got the error that :
/home/xieguotian/LSD_SLAM/src/lsd_slam/lsd_slam_core/src/IOWrapper/ROS/rosReconfigure.h:25:43: fatal error: lsd_slam_core/LSDParamsConfig.h: no such file or directory
#include "lsd_slam_core/LSDParamsConfig.h"
How can I fix this error?

Structure of topics.

I have a question regarding the message structure that the live_slam node would like to receive. For example whilst launching:

$ rosrun lsd_slam_core live_slam /image:= /camera_info:=<yourcamera_infotopic>

I assume the /image is a sensor_msgs::Image message format. But what about the /camera_info ?

Thanks!
Ruud

lsd_slam_viewer error in roslaunch

First, thanks for your awesome work!

When I try to launch lsd_slam_viewer using roslaunch with the following launch file

<launch>
  <node name="lsd_slam_viewer" pkg="lsd_slam_viewer" type="viewer"
        output="screen">
  </node>
</launch>

roslaunch throw the following error:

process[lsd_slam_viewer-2]: started with pid [5219]
Started QApplication thread
terminate called after throwing an instance of 'rosbag::BagIOException'
what(): Error opening file: __log:=/home/simbaforrest/.ros/log/c1b907b4-961a-11e4-bf23-100ba9beb87c/lsd_slam_viewer-2.log
[lsd_slam_viewer-2] process has died [pid 5219, exit code -6, cmd >/home/simbaforrest/bot/fuerte_ws/lsd_slam/lsd_slam_viewer/bin/viewer __name:=lsd_slam_viewer __log:=/home/simbaforrest/.ros/log/c1b907b4-961a-11e4-bf23-100ba9beb87c/lsd_slam_viewer-2.log].
log file: /home/simbaforrest/.ros/log/c1b907b4-961a-11e4-bf23-100ba9beb87c/lsd_slam_viewer-2*.log
^C[rosout-1] killing on exit

I investigated the main_viewer.cpp a bit and found that the ros::init(argc, argv, "viewer"); was called inside the rosFileLoop and rosThreadLoop which caused the problem because roslaunch add an extra input argument __name:=lsd_slam_viewer, thus the following code

    if(argc > 1)
    {
        rosThread = boost::thread(rosFileLoop, argc, argv);
    }
    else
    {
        // start ROS thread
        rosThread = boost::thread(rosThreadLoop, argc, argv);
    }

will always start rosFileLoop instead of rosThreadLoop.

I guess it should be safe to move the ros::init into the main function and it did help resolve the issue.

GPU acceleration

Hey!

Has anyone thought about implementing GPU acceleration? That would make it really useful for onboard computers that have a powerful GPU, e.g. the NVIDIA Jetson TK1...

I would do it if I knew how to, but unfortunately my programming knowledge is not there yet...

Marc

Getting the point cloud with a custom wrapper

Hi, I have been looking to test your library. As an extension, I wanted to make my own wrapper for output, and visualize the point cloud with my own code. When I take the idepth that is >0 and backproject it, this is what I get:

screen shot 2014-12-08 at 6 25 39 pm

Is something going wrong? I don't get any errors from the console, even with debug activated. My publishKeyframe is this:

  int width = kf->width();

  // extract depth map
  const float *depthMap = kf->idepth();
  const float *depthMapValidity = kf->idepthVar();

  // extract camera
  Sim3 camToWorld = kf->getScaledCamToWorld();
  double fx = kf->fx();
  double fy = kf->fy();
  double cx = kf->cx();
  double cy = kf->cy();
  double fxi = 1/fx;
  double fyi = 1/fy;
  double cxi = -cx / fx;
  double cyi = -cy / fy;

  // extract image
  float *image = kf->image(0);
  int minNearSupport = 5;
  std::vector<Sophus::Vector3d> transformedPoints;
  std::vector<uint8_t> intensities;

  for(int y=1; y<kf->height()-1; y++) {
    for(int x=1; x<width-1; x++) {
      double d = depthMap[x+y*width];

      // skip all invalid points
      if (d <= 0) {
        continue;
      }

      // calculate the depth of the point
      float depth = 1 / d;

      int nearSupport = 0;

      for(int dx=-1;dx<2;dx++) {
        for(int dy=-1;dy<2;dy++) {
          int idx = x+dx+(y+dy)*width;
          double neighbour = depthMap[idx];

          if (neighbour > 0){
            float diff = neighbour - 1.0f / depth;
            if (diff * diff < 2 * depthMapValidity[x+y*width])
              nearSupport++;
          }
        }

        if (nearSupport < minNearSupport) {
          continue;
        }
      }

      // backproject to world
      Sophus::Vector3d homogeneous((x*fxi + cxi), (y*fyi + cyi), 1);
      Sophus::Vector3d transformedPoint = camToWorld * (homogeneous * depth);

      // add point to pointcloud
      transformedPoints.push_back(transformedPoint);
      intensities.push_back(image[y*width+x]);
    }
  }

The depth map looks something like this for the first keyframe:

img_1468

Some stats:

Upd 984.9ms (0.4Hz); Create 0.0ms (0.0Hz); Final 0.0ms (0.0Hz) // Obs 564.8ms (0.4Hz); Reg 336.8ms (0.4Hz); Prop 0.0ms (0.0Hz); Fill 58.8ms (0.4Hz); Set 24.4ms (0.4Hz)
MapIt: 984.9ms (0.4Hz); Track: 880.3ms (0.5Hz); Create: 0.0ms (0.0Hz); FindRef: 0.0ms (0.0Hz); PermaTrk: 0.0ms (0.0Hz); Opt: 0.0ms (0.0Hz); FindConst: 0.0ms (0.0Hz);
FINALIZING KF 0
TRACKING 11 on 0
(3-0): ACCEPTED increment of 0.012268 with lambda 0.0, residual: 3.680577 -> 3.656424
         p=-0.0345 0.0244 0.0029 -0.0175 0.0251 -0.0019
(3-1): ACCEPTED increment of 0.011236 with lambda 0.0, residual: 3.656424 -> 3.254479
         p=-0.0421 0.0243 0.0005 -0.0200 0.0325 -0.0028
(3-2): ACCEPTED increment of 0.005422 with lambda 0.0, residual: 3.254479 -> 3.244507
         p=-0.0448 0.0256 -0.0027 -0.0208 0.0355 -0.0029
(3-3): ACCEPTED increment of 0.007936 with lambda 0.0, residual: 3.244507 -> 3.012756
         p=-0.0495 0.0287 -0.0054 -0.0201 0.0403 -0.0026
(3-4): ACCEPTED increment of 0.015319 with lambda 0.0, residual: 3.012756 -> 2.754024
         p=-0.0577 0.0366 -0.0078 -0.0146 0.0485 -0.0014
(3-5): ACCEPTED increment of 0.028333 with lambda 0.0, residual: 2.754024 -> 2.345105
         p=-0.0727 0.0510 -0.0113 -0.0029 0.0632 0.0008
(3-6): ACCEPTED increment of 0.031557 with lambda 0.0, residual: 2.345105 -> 2.063821
         p=-0.0858 0.0701 -0.0151 0.0134 0.0765 0.0009
(3-7): ACCEPTED increment of 0.032163 with lambda 0.0, residual: 2.063821 -> 1.858116
         p=-0.0931 0.0928 -0.0183 0.0330 0.0846 0.0025
(3-8): ACCEPTED increment of 0.027517 with lambda 0.0, residual: 1.858116 -> 1.716052
         p=-0.0987 0.1124 -0.0183 0.0506 0.0908 0.0011
(3-9): ACCEPTED increment of 0.020318 with lambda 0.0, residual: 1.716052 -> 1.595070
         p=-0.1083 0.1240 -0.0158 0.0599 0.1008 -0.0006
(3-10): ACCEPTED increment of 0.009325 with lambda 0.0, residual: 1.595070 -> 1.585776
         p=-0.1122 0.1200 -0.0128 0.0543 0.1050 0.0000
(3-11): ACCEPTED increment of 0.003826 with lambda 0.0, residual: 1.585776 -> 1.565200
         p=-0.1144 0.1203 -0.0109 0.0540 0.1075 0.0001
(3-12): REJECTED increment of 0.005886 with lambda 0.0, (residual: 1.565200 -> 1.572315)
(3-12): ACCEPTED increment of 0.001558 with lambda 0.2, residual: 1.565200 -> 1.561690
         p=-0.1143 0.1206 -0.0095 0.0537 0.1078 -0.0002
(3-13): ACCEPTED increment of 0.002274 with lambda 0.1, residual: 1.561690 -> 1.555817
         p=-0.1142 0.1209 -0.0074 0.0532 0.1083 0.0001
(3-14): REJECTED increment of 0.015002 with lambda 0.0, (residual: 1.555817 -> 1.595475)
(3-14): REJECTED increment of 0.002837 with lambda 0.2, (residual: 1.555817 -> 1.556309)
(3-14): ACCEPTED increment of 0.001844 with lambda 0.8, residual: 1.555817 -> 1.554043
         p=-0.1140 0.1212 -0.0056 0.0529 0.1086 0.0001
(3-15): REJECTED increment of 0.002041 with lambda 0.4, (residual: 1.554043 -> 1.559329)
(3-15): REJECTED increment of 0.001638 with lambda 0.8, (residual: 1.554043 -> 1.558871)
(3-15): REJECTED increment of 0.000783 with lambda 3.2, (residual: 1.554043 -> 1.555813)
(3-15): ACCEPTED increment of 0.000142 with lambda 25.6, residual: 1.554043 -> 1.553711
         p=-0.1139 0.1213 -0.0055 0.0529 0.1086 -0.0000
(3-15): FINISHED pyramid level (last residual reduction too small).

installation dependency

just a side note my system (Trusty 14.04 Ros indigo) needed additionally library libsuitesparse
apt-get install libsuitesparse-dev<code>

question: how to use live camera

Dear all,

I had installed lsd_slam package successfully and followed the Quicksteps smoothly.

Now, I attached a camera to experiment the live setting. First, I initiate the camera using command:
'rosrun uvc_cam uvc_cam_node device:=/dev/video1'
Then I run commands:
'rosrun lsd_slam_viewer viewer'
and then,
'rosrun lsd_slam_core live_slam image:=/camera/image_raw camera_info:=/camera_info'
(the published topic is /camera/image_raw)
But then, nothing happens. I cannot see the live result. Did I miss some steps?
I use rqt_graph to see the info of topics and node, here is:
rosgraph

Could someone give me some suggestion to fix it? THX~

Best regards,
Milton

FabMap activation (opencv 2.4.9 Ubuntu 14.04)

Hello!
Please tell me how to properly connect openFabMap? How should I edit CMakeLists.txt?

System:
Ubuntu 14.04 64-bit
Opencv 2.4.9
ROS Indigo

Installing without openFabMap all works.
If I uncomment the line in CMakeLists.txt

add_subdirectory(${PROJECT_SOURCE_DIR}/thirdparty/openFabMap)
include_directories(${PROJECT_SOURCE_DIR}/thirdparty/openFabMap/include)
add_definitions("-DHAVE_FABMAP")
set(FABMAP_LIB openFABMAP )

and make rosmake lsd_slam, I get the error:

Linking CXX executable ../bin/live_slam
//usr/local/lib/libopencv_nonfree.so: undefined reference to `cv :: ocl :: integral (cv :: ocl :: oclMat const &, cv :: ocl :: oclMat &) '
collect2: error: ld returned 1 exit status

log file
https://drive.google.com/file/d/0B_w8l8HXXdd8dnlULXZoRkozZk0/view?usp=sharing

Scene reconstructed pointcloud and increasing FPS

Hey,

I am reconstructing a simple scene in a pointcloud using the lsd_slam library. I have a few questions before I start doing redundant or stupid things. :)

My main goal is to create and update a combined pointcloud of the scene that is published in ROS for other nodes to use, for example RVIZ for visualization or other nodes to do computations on.

Whilst running the lsd_slam_core on a live image stream ($ rosrun lsd_slam_core live_slam image:=/image_raw camera_info:=/camera_info), I can vizualize such a reconstructed scene by running the lsd_slam_viewer (rosrun lsd_slam_viewer viewer).

I also can vizualize the pointcloud in RVIZ by listening to the /lsd_slam/keyframes topic and extract and republish a pointcloud from that data. However, this is just from a single frame and is not a combined scence reconstruction using also the previous frames. Would I need to write my own combination algortihm? Or is the whole reconstructed pointcloud published somewhere like in the displayed in the lsd_slam_viewer?

I also have a question about the performance. When running the lsd_slam_core ($ rosrun lsd_slam_core live_slam image:=/image_raw camera_info:=/camera_info), it looks like the framerate is quite low due to the vizualization in the 'DebugWindow Depth' window. Is there a parameter that turns off that display? I could not find it in the dynamic reconfigure parameters.

Thanks for the help!
Ruud

Delayed depth initialization / Metrically-accurate maps with scale updates

I have a question regarding scale consistency/drift. I was wondering if the API permits intermittent scale updates (i.e. providing metrically accurate scale updates) to the pose graph in an on-line fashion. This would imply that providing a scale measurement at time t should technically propagate forward and backward in time over the pose graph, to be consistent with the metric map at any point of time (as long as there is at least one scale measurement available). I haven't spent too much time looking at the API to see if there's an obvious way of doing such an update. This would be particularly useful to obtain metrically accurate maps for future use.

Any help would be greatly appreciated.
Thanks

lsd_slam_viewer immediate crash on archlinux

I managed to install lsd_slam from the catkin branch. lsd_slam_core runs, but when running lsd_slam_viewer it crashes immediately with the following backtrace and memory map:

*** Error in `/home/bellbreaker/catkin_ws/devel/lib/lsd_slam_viewer/viewer': realloc(): invalid pointer: 0x00007fcaf2711820 ***
======= Backtrace: =========
/usr/lib/libc.so.6(+0x7340e)[0x7fcaf0eb040e]
/usr/lib/libc.so.6(+0x7884e)[0x7fcaf0eb584e]
/usr/lib/libc.so.6(realloc+0x1e8)[0x7fcaf0eb9b58]
/usr/lib/libnvidia-tls.so.343.22(+0x214a)[0x7fcae514a14a]
======= Memory map: ========
00400000-00464000 r-xp 00000000 08:03 49040190                           /home/bellbreaker/catkin_ws/devel/lib/lsd_slam_viewer/viewer
00664000-00666000 rw-p 00064000 08:03 49040190                           /home/bellbreaker/catkin_ws/devel/lib/lsd_slam_viewer/viewer
0110e000-01648000 rw-p 00000000 00:00 0                                  [heap]
7fcad6391000-7fcad63ff000 r-xp 00000000 08:03 49187136                   /usr/lib/libnvidia-glsi.so.343.22
7fcad63ff000-7fcad65ff000 ---p 0006e000 08:03 49187136                   /usr/lib/libnvidia-glsi.so.343.22
7fcad65ff000-7fcad6607000 rw-p 0006e000 08:03 49187136                   /usr/lib/libnvidia-glsi.so.343.22
7fcad6607000-7fcad6619000 rw-p 00000000 00:00 0 
7fcad6619000-7fcad661e000 r-xp 00000000 08:03 49172829                   /usr/lib/libXdmcp.so.6.0.0
7fcad661e000-7fcad681d000 ---p 00005000 08:03 49172829                   /usr/lib/libXdmcp.so.6.0.0
7fcad681d000-7fcad681e000 r--p 00004000 08:03 49172829                   /usr/lib/libXdmcp.so.6.0.0
7fcad681e000-7fcad681f000 rw-p 00005000 08:03 49172829                   /usr/lib/libXdmcp.so.6.0.0
7fcad681f000-7fcad6821000 r-xp 00000000 08:03 49169640                   /usr/lib/libXau.so.6.0.0
7fcad6821000-7fcad6a21000 ---p 00002000 08:03 49169640                   /usr/lib/libXau.so.6.0.0
7fcad6a21000-7fcad6a22000 r--p 00002000 08:03 49169640                   /usr/lib/libXau.so.6.0.0
7fcad6a22000-7fcad6a23000 rw-p 00003000 08:03 49169640                   /usr/lib/libXau.so.6.0.0
7fcad6a23000-7fcad6a25000 r-xp 00000000 08:03 49155311                   /usr/lib/libutil-2.20.so
7fcad6a25000-7fcad6c24000 ---p 00002000 08:03 49155311                   /usr/lib/libutil-2.20.so
7fcad6c24000-7fcad6c25000 r--p 00001000 08:03 49155311                   /usr/lib/libutil-2.20.so
7fcad6c25000-7fcad6c26000 rw-p 00002000 08:03 49155311                   /usr/lib/libutil-2.20.so
7fcad6c26000-7fcad6c9c000 r-xp 00000000 08:03 49159053                   /usr/lib/libgmp.so.10.2.0
7fcad6c9c000-7fcad6e9b000 ---p 00076000 08:03 49159053                   /usr/lib/libgmp.so.10.2.0
7fcad6e9b000-7fcad6e9c000 r--p 00075000 08:03 49159053                   /usr/lib/libgmp.so.10.2.0
7fcad6e9c000-7fcad6e9d000 rw-p 00076000 08:03 49159053                   /usr/lib/libgmp.so.10.2.0
7fcad6e9d000-7fcad6eca000 r-xp 00000000 08:03 49174015                   /usr/lib/libhogweed.so.2.5
7fcad6eca000-7fcad70ca000 ---p 0002d000 08:03 49174015                   /usr/lib/libhogweed.so.2.5
7fcad70ca000-7fcad70cb000 r--p 0002d000 08:03 49174015                   /usr/lib/libhogweed.so.2.5
7fcad70cb000-7fcad70cc000 rw-p 0002e000 08:03 49174015                   /usr/lib/libhogweed.so.2.5
7fcad70cc000-7fcad70f9000 r-xp 00000000 08:03 49174018                   /usr/lib/libnettle.so.4.7
7fcad70f9000-7fcad72f8000 ---p 0002d000 08:03 49174018                   /usr/lib/libnettle.so.4.7
7fcad72f8000-7fcad72f9000 r--p 0002c000 08:03 49174018                   /usr/lib/libnettle.so.4.7
7fcad72f9000-7fcad72fa000 rw-p 0002d000 08:03 49174018                   /usr/lib/libnettle.so.4.7
7fcad72fa000-7fcad730b000 r-xp 00000000 08:03 49190077                   /usr/lib/libtasn1.so.6.3.2
7fcad730b000-7fcad750b000 ---p 00011000 08:03 49190077                   /usr/lib/libtasn1.so.6.3.2
7fcad750b000-7fcad750c000 r--p 00011000 08:03 49190077                   /usr/lib/libtasn1.so.6.3.2
7fcad750c000-7fcad750d000 rw-p 00012000 08:03 49190077                   /usr/lib/libtasn1.so.6.3.2
7fcad750d000-7fcad7567000 r-xp 00000000 08:03 49182190                   /usr/lib/libp11-kit.so.0.1.0
7fcad7567000-7fcad7767000 ---p 0005a000 08:03 49182190                   /usr/lib/libp11-kit.so.0.1.0
7fcad7767000-7fcad7771000 r--p 0005a000 08:03 49182190                   /usr/lib/libp11-kit.so.0.1.0
7fcad7771000-7fcad7773000 rw-p 00064000 08:03 49182190                   /usr/lib/libp11-kit.so.0.1.0
7fcad7773000-7fcad78cc000 r-xp 00000000 08:03 49173896                   /usr/lib/libxml2.so.2.9.2
7fcad78cc000-7fcad7acc000 ---p 00159000 08:03 49173896                   /usr/lib/libxml2.so.2.9.2
7fcad7acc000-7fcad7ad4000 r--p 00159000 08:03 49173896                   /usr/lib/libxml2.so.2.9.2
7fcad7ad4000-7fcad7ad6000 rw-p 00161000 08:03 49173896                   /usr/lib/libxml2.so.2.9.2
7fcad7ad6000-7fcad7ad8000 rw-p 00000000 00:00 0 
7fcad7ad8000-7fcad7b58000 r-xp 00000000 08:03 49184283                   /usr/lib/liborc-0.4.so.0.19.0
7fcad7b58000-7fcad7d57000 ---p 00080000 08:03 49184283                   /usr/lib/liborc-0.4.so.0.19.0
7fcad7d57000-7fcad7d59000 r--p 0007f000 08:03 49184283                   /usr/lib/liborc-0.4.so.0.19.0
7fcad7d59000-7fcad7d5e000 rw-p 00081000 08:03 49184283                   /usr/lib/liborc-0.4.so.0.19.0
7fcad7d5e000-7fcad7d64000 r-xp 00000000 08:03 49172721                   /usr/lib/libogg.so.0.8.2
7fcad7d64000-7fcad7f63000 ---p 00006000 08:03 49172721                   /usr/lib/libogg.so.0.8.2
7fcad7f63000-7fcad7f64000 r--p 00005000 08:03 49172721                   /usr/lib/libogg.so.0.8.2
7fcad7f64000-7fcad7f65000 rw-p 00006000 08:03 49172721                   /usr/lib/libogg.so.0.8.2
7fcad7f65000-7fcad7f8a000 r-xp 00000000 08:03 49178436                   /usr/lib/libv4lconvert.so.0.0.0
7fcad7f8a000-7fcad818a000 ---p 00025000 08:03 49178436                   /usr/lib/libv4lconvert.so.0.0.0
7fcad818a000-7fcad818c000 r--p 00025000 08:03 49178436                   /usr/lib/libv4lconvert.so.0.0.0
7fcad818c000-7fcad818d000 rw-p 00027000 08:03 49178436                   /usr/lib/libv4lconvert.so.0.0.0
7fcad818d000-7fcad81df000 rw-p 00000000 00:00 0 
7fcad81df000-7fcad81e8000 r-xp 00000000 08:03 49187300                   /usr/lib/libxcb-render.so.0.0.0
7fcad81e8000-7fcad83e7000 ---p 00009000 08:03 49187300                   /usr/lib/libxcb-render.so.0.0.0
7fcad83e7000-7fcad83e8000 r--p 00008000 08:03 49187300                   /usr/lib/libxcb-render.so.0.0.0
7fcad83e8000-7fcad83e9000 rw-p 00009000 08:03 49187300                   /usr/lib/libxcb-render.so.0.0.0
7fcad83e9000-7fcad83eb000 r-xp 00000000 08:03 49187328                   /usr/lib/libxcb-shm.so.0.0.0
7fcad83eb000-7fcad85eb000 ---p 00002000 08:03 49187328                   /usr/lib/libxcb-shm.so.0.0.0
7fcad85eb000-7fcad85ec000 r--p 00002000 08:03 49187328                   /usr/lib/libxcb-shm.so.0.0.0
7fcad85ec000-7fcad85ed000 rw-p 00003000 08:03 49187328                   /usr/lib/libxcb-shm.so.0.0.0
7fcad85ed000-7fcad86b6000 r-xp 00000000 08:03 49685525                   /usr/lib/nvidia/libEGL.so.343.22
7fcad86b6000-7fcad88b6000 ---p 000c9000 08:03 49685525                   /usr/lib/nvidia/libEGL.so.343.22
7fcad88b6000-7fcad88e0000 rw-p 000c9000 08:03 49685525                   /usr/lib/nvidia/libEGL.so.343.22
7fcad88e0000-7fcad88f8000 rw-p 00000000 00:00 0 
7fcad88f8000-7fcad899d000 r-xp 00000000 08:03 49169639                   /usr/lib/libpixman-1.so.0.32.6
7fcad899d000-7fcad8b9c000 ---p 000a5000 08:03 49169639                   /usr/lib/libpixman-1.so.0.32.6
7fcad8b9c000-7fcad8ba4000 r--p 000a4000 08:03 49169639                   /usr/lib/libpixman-1.so.0.32.6
7fcad8ba4000-7fcad8ba5000 rw-p 000ac000 08:03 49169639                   /usr/lib/libpixman-1.so.0.32.6
7fcad8ba5000-7fcad8ba6000 r-xp 00000000 08:03 49172820                   /usr/lib/libgthread-2.0.so.0.4200.0
7fcad8ba6000-7fcad8da5000 ---p 00001000 08:03 49172820                   /usr/lib/libgthread-2.0.so.0.4200.0
7fcad8da5000-7fcad8da6000 r--p 00000000 08:03 49172820                   /usr/lib/libgthread-2.0.so.0.4200.0
7fcad8da6000-7fcad8da7000 rw-p 00001000 08:03 49172820                   /usr/lib/libgthread-2.0.so.0.4200.0
7fcad8da7000-7fcad8db8000 r-xp 00000000 08:03 49184189                   /usr/lib/libgpg-error.so.0.12.2
7fcad8db8000-7fcad8fb7000 ---p 00011000 08:03 49184189                   /usr/lib/libgpg-error.so.0.12.2
7fcad8fb7000-7fcad8fb8000 r--p 00010000 08:03 49184189                   /usr/lib/libgpg-error.so.0.12.2
7fcad8fb8000-7fcad8fb9000 rw-p 00011000 08:03 49184189                   /usr/lib/libgpg-error.so.0.12.2
7fcad8fb9000-7fcad9090000 r-xp 00000000 08:03 49184190                   /usr/lib/libgcrypt.so.20.0.2
7fcad9090000-7fcad9290000 ---p 000d7000 08:03 49184190                   /usr/lib/libgcrypt.so.20.0.2
7fcad9290000-7fcad9291000 r--p 000d7000 08:03 49184190                   /usr/lib/libgcrypt.so.20.0.2
7fcad9291000-7fcad929a000 rw-p 000d8000 08:03 49184190                   /usr/lib/libgcrypt.so.20.0.2
7fcad929a000-7fcad92b6000 r-xp 00000000 08:03 49173843                   /usr/lib/libgraphite2.so.3.0.1
7fcad92b6000-7fcad94b5000 ---p 0001c000 08:03 49173843                   /usr/lib/libgraphite2.so.3.0.1
7fcad94b5000-7fcad94b7000 r--p 0001b000 08:03 49173843                   /usr/lib/libgraphite2.so.3.0.1
7fcad94b7000-7fcad94b8000 rw-p 0001d000 08:03 49173843                   /usr/lib/libgraphite2.so.3.0.1
7fcad94b8000-7fcad94d9000 r-xp 00000000 08:03 49187318                   /usr/lib/libxcb.so.1.1.0
7fcad94d9000-7fcad96d8000 ---p 00021000 08:03 49187318                   /usr/lib/libxcb.so.1.1.0
7fcad96d8000-7fcad96d9000 r--p 00020000 08:03 49187318                   /usr/lib/libxcb.so.1.1.0
7fcad96d9000-7fcad96da000 rw-p 00021000 08:03 49187318                   /usr/lib/libxcb.so.1.1.0
7fcad96da000-7fcad9854000 r-xp 00000000 08:03 49155169                   /usr/lib/libpython2.7.so.1.0
7fcad9854000-7fcad9a54000 ---p 0017a000 08:03 49155169                   /usr/lib/libpython2.7.so.1.0
7fcad9a54000-7fcad9a55000 r--p 0017a000 08:03 49155169                   /usr/lib/libpython2.7.so.1.0
7fcad9a55000-7fcad9a98000 rw-p 0017b000 08:03 49155169                   /usr/lib/libpython2.7.so.1.0
7fcad9a98000-7fcad9aa7000 rw-p 00000000 00:00 0 
7fcad9aa7000-7fcad9abb000 r-xp 00000000 08:03 49189423                   /usr/lib/libtinyxml.so.0.2.6.2
7fcad9abb000-7fcad9cbb000 ---p 00014000 08:03 49189423                   /usr/lib/libtinyxml.so.0.2.6.2
7fcad9cbb000-7fcad9cbc000 rw-p 00014000 08:03 49189423                   /usr/lib/libtinyxml.so.0.2.6.2
7fcad9cbc000-7fcad9ea2000 r-xp 00000000 08:03 49191862                   /usr/lib/libcrypto.so.1.0.0
7fcad9ea2000-7fcada0a2000 ---p 001e6000 08:03 49191862                   /usr/lib/libcrypto.so.1.0.0
7fcada0a2000-7fcada0be000 r--p 001e6000 08:03 49191862                   /usr/lib/libcrypto.so.1.0.0
7fcada0be000-7fcada0ca000 rw-p 00202000 08:03 49191862                   /usr/lib/libcrypto.so.1.0.0
7fcada0ca000-7fcada0ce000 rw-p 00000000 00:00 0 
7fcada0ce000-7fcada133000 r-xp 00000000 08:03 49191861                   /usr/lib/libssl.so.1.0.0
7fcada133000-7fcada332000 ---p 00065000 08:03 49191861                   /usr/lib/libssl.so.1.0.0
7fcada332000-7fcada336000 r--p 00064000 08:03 49191861                   /usr/lib/libssl.so.1.0.0
7fcada336000-7fcada33d000 rw-p 00068000 08:03 49191861                   /usr/lib/libssl.so.1.0.0
7fcada33d000-7fcada358000 r-xp 00000000 08:03 49163928                   /usr/lib/libsasl2.so.3.0.0
7fcada358000-7fcada558000 ---p 0001b000 08:03 49163928                   /usr/lib/libsasl2.so.3.0.0
7fcada558000-7fcada559000 r--p 0001b000 08:03 49163928                   /usr/lib/libsasl2.so.3.0.0
7fcada559000-7fcada55a000 rw-p 0001c000 08:03 49163928                   /usr/lib/libsasl2.so.3.0.0
7fcada55a000-7fcada670000 r-xp 00000000 08:03 49191941                   /usr/lib/libgnutls.so.28.41.1
7fcada670000-7fcada86f000 ---p 00116000 08:03 49191941                   /usr/lib/libgnutls.so.28.41.1
7fcada86f000-7fcada879000 r--p 00115000 08:03 49191941                   /usr/lib/libgnutls.so.28.41.1
7fcada879000-7fcada87b000 rw-p 0011f000 08:03 49191941                   /usr/lib/libgnutls.so.28.41.1
7fcada87b000-7fcada87c000 rw-p 00000000 00:00 0 
7fcada87c000-7fcada8b0000 r-xp 00000000 08:03 49187183                   /usr/lib/libbluray.so.1.6.2
7fcada8b0000-7fcadaab0000 ---p 00034000 08:03 49187183                   /usr/lib/libbluray.so.1.6.2
7fcadaab0000-7fcadaab1000 r--p 00034000 08:03 49187183                   /usr/lib/libbluray.so.1.6.2
7fcadaab1000-7fcadaab2000 rw-p 00035000 08:03 49187183                   /usr/lib/libbluray.so.1.6.2
7fcadaab2000-7fcadaafe000 r-xp 00000000 08:03 49179272                   /usr/lib/libmodplug.so.1.0.0
7fcadaafe000-7fcadacfd000 ---p 0004c000 08:03 49179272                   /usr/lib/libmodplug.so.1.0.0
7fcadacfd000-7fcadacfe000 r--p 0004b000 08:03 49179272                   /usr/lib/libmodplug.so.1.0.0
7fcadacfe000-7fcadacff000 rw-p 0004c000 08:03 49179272                   /usr/lib/libmodplug.so.1.0.0
7fcadacff000-7fcadae3e000 rw-p 00000000 00:00 0 
7fcadae3e000-7fcadae59000 r-xp 00000000 08:03 49187184                   /usr/lib/librtmp.so.1
7fcadae59000-7fcadb058000 ---p 0001b000 08:03 49187184                   /usr/lib/librtmp.so.1
7fcadb058000-7fcadb05a000 rw-p 0001a000 08:03 49187184                   /usr/lib/librtmp.so.1
7fcadb05a000-7fcadb065000 r-xp 00000000 08:03 49179519                   /usr/lib/libgsm.so.1.0.13
7fcadb065000-7fcadb264000 ---p 0000b000 08:03 49179519                   /usr/lib/libgsm.so.1.0.13
7fcadb264000-7fcadb265000 rw-p 0000a000 08:03 49179519                   /usr/lib/libgsm.so.1.0.13
7fcadb265000-7fcadb2ad000 r-xp 00000000 08:03 49179941                   /usr/lib/libmp3lame.so.0.0.0
7fcadb2ad000-7fcadb4ac000 ---p 00048000 08:03 49179941                   /usr/lib/libmp3lame.so.0.0.0
7fcadb4ac000-7fcadb4ad000 r--p 00047000 08:03 49179941                   /usr/lib/libmp3lame.so.0.0.0
7fcadb4ad000-7fcadb4ae000 rw-p 00048000 08:03 49179941                   /usr/lib/libmp3lame.so.0.0.0
7fcadb4ae000-7fcadb4dc000 rw-p 00000000 00:00 0 
7fcadb4dc000-7fcadb504000 r-xp 00000000 08:03 49184280                   /usr/lib/libopencore-amrnb.so.0.0.3
7fcadb504000-7fcadb704000 ---p 00028000 08:03 49184280                   /usr/lib/libopencore-amrnb.so.0.0.3
7fcadb704000-7fcadb705000 r--p 00028000 08:03 49184280                   /usr/lib/libopencore-amrnb.so.0.0.3
7fcadb705000-7fcadb706000 rw-p 00029000 08:03 49184280                   /usr/lib/libopencore-amrnb.so.0.0.3
7fcadb706000-7fcadb719000 r-xp 00000000 08:03 49179997                   /usr/lib/libopencore-amrwb.so.0.0.3
7fcadb719000-7fcadb918000 ---p 00013000 08:03 49179997                   /usr/lib/libopencore-amrwb.so.0.0.3
7fcadb918000-7fcadb919000 r--p 00012000 08:03 49179997                   /usr/lib/libopencore-amrwb.so.0.0.3
7fcadb919000-7fcadb91a000 rw-p 00013000 08:03 49179997                   /usr/lib/libopencore-amrwb.so.0.0.3
7fcadb91a000-7fcadb942000 r-xp 00000000 08:03 49180015                   /usr/lib/libopenjpeg.so.1.5.2
7fcadb942000-7fcadbb41000 ---p 00028000 08:03 49180015                   /usr/lib/libopenjpeg.so.1.5.2
7fcadbb41000-7fcadbb42000 r--p 00027000 08:03 49180015                   /usr/lib/libopenjpeg.so.1.5.2
7fcadbb42000-7fcadbb43000 rw-p 00028000 08:03 49180015                   /usr/lib/libopenjpeg.so.1.5.2
7fcadbb43000-7fcadbb8d000 r-xp 00000000 08:03 49183640                   /usr/lib/libopus.so.0.5.0
7fcadbb8d000-7fcadbd8d000 ---p 0004a000 08:03 49183640                   /usr/lib/libopus.so.0.5.0
7fcadbd8d000-7fcadbd8e000 r--p 0004a000 08:03 49183640                   /usr/lib/libopus.so.0.5.0
7fcadbd8e000-7fcadbd8f000 rw-p 0004b000 08:03 49183640                   /usr/lib/libopus.so.0.5.0
7fcadbd8f000-7fcadbe53000 r-xp 00000000 08:03 49179509                   /usr/lib/libschroedinger-1.0.so.0.11.0
7fcadbe53000-7fcadc053000 ---p 000c4000 08:03 49179509                   /usr/lib/libschroedinger-1.0.so.0.11.0
7fcadc053000-7fcadc055000 r--p 000c4000 08:03 49179509                   /usr/lib/libschroedinger-1.0.so.0.11.0
7fcadc055000-7fcadc057000 rw-p 000c6000 08:03 49179509                   /usr/lib/libschroedinger-1.0.so.0.11.0
7fcadc057000-7fcadc058000 rw-p 00000000 00:00 0 
7fcadc058000-7fcadc06f000 r-xp 00000000 08:03 49180032                   /usr/lib/libspeex.so.1.5.0
7fcadc06f000-7fcadc26f000 ---p 00017000 08:03 49180032                   /usr/lib/libspeex.so.1.5.0
7fcadc26f000-7fcadc270000 r--p 00017000 08:03 49180032                   /usr/lib/libspeex.so.1.5.0
7fcadc270000-7fcadc271000 rw-p 00018000 08:03 49180032                   /usr/lib/libspeex.so.1.5.0
7fcadc271000-7fcadc289000 r-xp 00000000 08:03 49179956                   /usr/lib/libtheoradec.so.1.1.4
7fcadc289000-7fcadc488000 ---p 00018000 08:03 49179956                   /usr/lib/libtheoradec.so.1.1.4
7fcadc488000-7fcadc489000 r--p 00017000 08:03 49179956                   /usr/lib/libtheoradec.so.1.1.4
7fcadc489000-7fcadc48a000 rw-p 00018000 08:03 49179956                   /usr/lib/libtheoradec.so.1.1.4
7fcadc48a000-7fcadc4c9000 r-xp 00000000 08:03 49179957                   /usr/lib/libtheoraenc.so.1.1.2
7fcadc4c9000-7fcadc6c9000 ---p 0003f000 08:03 49179957                   /usr/lib/libtheoraenc.so.1.1.2
7fcadc6c9000-7fcadc6ca000 r--p 0003f000 08:03 49179957                   /usr/lib/libtheoraenc.so.1.1.2
7fcadc6ca000-7fcadc6cb000 rw-p 00040000 08:03 49179957                   /usr/lib/libtheoraenc.so.1.1.2
7fcadc6cb000-7fcadc6f7000 r-xp 00000000 08:03 49169521                   /usr/lib/libvorbis.so.0.4.7
7fcadc6f7000-7fcadc8f6000 ---p 0002c000 08:03 49169521                   /usr/lib/libvorbis.so.0.4.7
7fcadc8f6000-7fcadc8f7000 r--p 0002b000 08:03 49169521                   /usr/lib/libvorbis.so.0.4.7
7fcadc8f7000-7fcadc8f8000 rw-p 0002c000 08:03 49169521                   /usr/lib/libvorbis.so.0.4.7
7fcadc8f8000-7fcadc985000 r-xp 00000000 08:03 49169523                   /usr/lib/libvorbisenc.so.2.0.10
7fcadc985000-7fcadcb84000 ---p 0008d000 08:03 49169523                   /usr/lib/libvorbisenc.so.2.0.10
7fcadcb84000-7fcadcba0000 r--p 0008c000 08:03 49169523                   /usr/lib/libvorbisenc.so.2.0.10
7fcadcba0000-7fcadcba1000 rw-p 000a8000 08:03 49169523                   /usr/lib/libvorbisenc.so.2.0.10
7fcadcba1000-7fcadcd3c000 r-xp 00000000 08:03 49184262                   /usr/lib/libvpx.so.1.3.0
7fcadcd3c000-7fcadcf3b000 ---p 0019b000 08:03 49184262                   /usr/lib/libvpx.so.1.3.0
7fcadcf3b000-7fcadcf3e000 r--p 0019a000 08:03 49184262                   /usr/lib/libvpx.so.1.3.0
7fcadcf3e000-7fcadcf3f000 rw-p 0019d000 08:03 49184262                   /usr/lib/libvpx.so.1.3.0
7fcadcf3f000-7fcadcf85000 rw-p 00000000 00:00 0 
7fcadcf85000-7fcadd07c000 r-xp 00000000 08:03 49192206                   /usr/lib/libx264.so.142
7fcadd07c000-7fcadd27c000 ---p 000f7000 08:03 49192206                   /usr/lib/libx264.so.142
7fcadd27c000-7fcadd27d000 r--p 000f7000 08:03 49192206                   /usr/lib/libx264.so.142
7fcadd27d000-7fcadd27e000 rw-p 000f8000 08:03 49192206                   /usr/lib/libx264.so.142
7fcadd27e000-7fcadd2f9000 rw-p 00000000 00:00 0 
7fcadd2f9000-7fcadd55f000 r-xp 00000000 08:03 49189152                   /usr/lib/libx265.so.35
7fcadd55f000-7fcadd75e000 ---p 00266000 08:03 49189152                   /usr/lib/libx265.so.35
7fcadd75e000-7fcadd760000 r--p 00265000 08:03 49189152                   /usr/lib/libx265.so.35
7fcadd760000-7fcadd761000 rw-p 00267000 08:03 49189152                   /usr/lib/libx265.so.35
7fcadd761000-7fcadd766000 rw-p 00000000 00:00 0 
7fcadd766000-7fcadd806000 r-xp 00000000 08:03 49178483                   /usr/lib/libxvidcore.so.4.3
7fcadd806000-7fcadda06000 ---p 000a0000 08:03 49178483                   /usr/lib/libxvidcore.so.4.3
7fcadda06000-7fcadda07000 r--p 000a0000 08:03 49178483                   /usr/lib/libxvidcore.so.4.3
7fcadda07000-7fcadda11000 rw-p 000a1000 08:03 49178483                   /usr/lib/libxvidcore.so.4.3
7fcadda11000-7fcadda7a000 rw-p 00000000 00:00 0 
7fcadda7a000-7fcadda8f000 r-xp 00000000 08:03 49179988                   /usr/lib/libva.so.1.3600.0
7fcadda8f000-7fcaddc8f000 ---p 00015000 08:03 49179988                   /usr/lib/libva.so.1.3600.0
7fcaddc8f000-7fcaddc90000 r--p 00015000 08:03 49179988                   /usr/lib/libva.so.1.3600.0
7fcaddc90000-7fcaddc91000 rw-p 00016000 08:03 49179988                   /usr/lib/libva.so.1.3600.0
7fcaddc91000-7fcaddca7000 r-xp 00000000 08:03 49180065                   /usr/lib/libswresample.so.1.1.100
7fcaddca7000-7fcaddea6000 ---p 00016000 08:03 49180065                   /usr/lib/libswresample.so.1.1.100
7fcaddea6000-7fcaddea8000 r--p 00015000 08:03 49180065                   /usr/lib/libswresample.so.1.1.100
7fcaddea8000-7fcaddea9000 rw-p 00017000 08:03 49180065                   /usr/lib/libswresample.so.1.1.100
7fcaddea9000-7fcaddeb2000 r-xp 00000000 08:03 49178437                   /usr/lib/libv4l2.so.0.0.0
7fcaddeb2000-7fcade0b1000 ---p 00009000 08:03 49178437                   /usr/lib/libv4l2.so.0.0.0
7fcade0b1000-7fcade0b2000 r--p 00008000 08:03 49178437                   /usr/lib/libv4l2.so.0.0.0
7fcade0b2000-7fcade0b7000 rw-p 00009000 08:03 49178437                   /usr/lib/libv4l2.so.0.0.0
7fcade0b7000-7fcade0cc000 r-xp 00000000 08:03 49155128                   /usr/lib/libnsl-2.20.so
7fcade0cc000-7fcade2cb000 ---p 00015000 08:03 49155128                   /usr/lib/libnsl-2.20.so
7fcade2cb000-7fcade2cc000 r--p 00014000 08:03 49155128                   /usr/lib/libnsl-2.20.so
7fcade2cc000-7fcade2cd000 rw-p 00015000 08:03 49155128                   /usr/lib/libnsl-2.20.so
7fcade2cd000-7fcade2cf000 rw-p 00000000 00:00 0 
7fcade2cf000-7fcade2e3000 r-xp 00000000 08:03 49155133                   /usr/lib/libresolv-2.20.so
7fcade2e3000-7fcade4e2000 ---p 00014000 08:03 49155133                   /usr/lib/libresolv-2.20.so
7fcade4e2000-7fcade4e3000 r--p 00013000 08:03 49155133                   /usr/lib/libresolv-2.20.so
7fcade4e3000-7fcade4e4000 rw-p 00014000 08:03 49155133                   /usr/lib/libresolv-2.20.so
7fcade4e4000-7fcade4e6000 rw-p 00000000 00:00 0 
7fcade4e6000-7fcade4fd000 r-xp 00000000 08:03 49187815                   /usr/lib/libusb-1.0.so.0.1.0
7fcade4fd000-7fcade6fc000 ---p 00017000 08:03 49187815                   /usr/lib/libusb-1.0.so.0.1.0
7fcade6fc000-7fcade6fd000 r--p 00016000 08:03 49187815                   /usr/lib/libusb-1.0.so.0.1.0
7fcade6fd000-7fcade6fe000 rw-p 00017000 08:03 49187815                   /usr/lib/libusb-1.0.so.0.1.0
7fcade6fe000-7fcade70c000 r-xp 00000000 08:03 49178754                   /usr/lib/libraw1394.so.11.1.0
7fcade70c000-7fcade90c000 ---p 0000e000 08:03 49178754                   /usr/lib/libraw1394.so.11.1.0
7fcade90c000-7fcade90d000 r--p 0000e000 08:03 49178754                   /usr/lib/libraw1394.so.11.1.0
7fcade90d000-7fcade90e000 rw-p 0000f000 08:03 49178754                   /usr/lib/libraw1394.so.11.1.0
7fcade90e000-7fcade92d000 r-xp 00000000 08:03 49189343                   /usr/lib/libpangox-1.0.so.0.0.0
7fcade92d000-7fcadeb2c000 ---p 0001f000 08:03 49189343                   /usr/lib/libpangox-1.0.so.0.0.0
7fcadeb2c000-7fcadeb2d000 r--p 0001e000 08:03 49189343                   /usr/lib/libpangox-1.0.so.0.0.0
7fcadeb2d000-7fcadeb2e000 rw-p 0001f000 08:03 49189343                   /usr/lib/libpangox-1.0.so.0.0.0
7fcadeb2e000-7fcadeb8e000 r-xp 00000000 08:03 49173300                   /usr/lib/libXt.so.6.0.0
7fcadeb8e000-7fcaded8e000 ---p 00060000 08:03 49173300                   /usr/lib/libXt.so.6.0.0
7fcaded8e000-7fcaded8f000 r--p 00060000 08:03 49173300                   /usr/lib/libXt.so.6.0.0
7fcaded8f000-7fcaded94000 rw-p 00061000 08:03 49173300                   /usr/lib/libXt.so.6.0.0
7fcaded94000-7fcaded95000 rw-p 00000000 00:00 0 
7fcaded95000-7fcadedad000 r-xp 00000000 08:03 49173307                   /usr/lib/libXmu.so.6.2.0
7fcadedad000-7fcadefad000 ---p 00018000 08:03 49173307                   /usr/lib/libXmu.so.6.2.0
7fcadefad000-7fcadefae000 r--p 00018000 08:03 49173307                   /usr/lib/libXmu.so.6.2.0
7fcadefae000-7fcadefaf000 rw-p 00019000 08:03 49173307                   /usr/lib/libXmu.so.6.2.0
7fcadefaf000-7fcadefb0000 rw-p 00000000 00:00 0 
7fcadefb0000-7fcadefb7000 r-xp 00000000 08:03 49159750                   /usr/lib/libffi.so.6.0.2
7fcadefb7000-7fcadf1b6000 ---p 00007000 08:03 49159750                   /usr/lib/libffi.so.6.0.2
7fcadf1b6000-7fcadf1b7000 r--p 00006000 08:03 49159750                   /usr/lib/libffi.so.6.0.2
7fcadf1b7000-7fcadf1b8000 rw-p 00007000 08:03 49159750                   /usr/lib/libffi.so.6.0.2
7fcadf1b8000-7fcadf226000 r-xp 00000000 08:03 49159551                   /usr/lib/libpcre.so.1.2.4
7fcadf226000-7fcadf425000 ---p 0006e000 08:03 49159551                   /usr/lib/libpcre.so.1.2.4
7fcadf425000-7fcadf426000 r--p 0006d000 08:03 49159551                   /usr/lib/libpcre.so.1.2.4
7fcadf426000-7fcadf427000 rw-p 0006e000 08:03 49159551                   /usr/lib/libpcre.so.1.2.4
7fcadf427000-7fcadf429000 r-xp 00000000 08:03 49184273                   /usr/lib/libXdamage.so.1.1.0
7fcadf429000-7fcadf628000 ---p 00002000 08:03 49184273                   /usr/lib/libXdamage.so.1.1.0
7fcadf628000-7fcadf629000 r--p 00001000 08:03 49184273                   /usr/lib/libXdamage.so.1.1.0
7fcadf629000-7fcadf62a000 rw-p 00002000 08:03 49184273                   /usr/lib/libXdamage.so.1.1.0
7fcadf62a000-7fcadf62c000 r-xp 00000000 08:03 49173888                   /usr/lib/libXcomposite.so.1.0.0
7fcadf62c000-7fcadf82b000 ---p 00002000 08:03 49173888                   /usr/lib/libXcomposite.so.1.0.0
7fcadf82b000-7fcadf82c000 r--p 00001000 08:03 49173888                   /usr/lib/libXcomposite.so.1.0.0
7fcadf82c000-7fcadf82d000 rw-p 00002000 08:03 49173888                   /usr/lib/libXcomposite.so.1.0.0
7fcadf82d000-7fcadf837000 r-xp 00000000 08:03 49184331                   /usr/lib/libXcursor.so.1.0.2
7fcadf837000-7fcadfa36000 ---p 0000a000 08:03 49184331                   /usr/lib/libXcursor.so.1.0.2
7fcadfa36000-7fcadfa37000 r--p 00009000 08:03 49184331                   /usr/lib/libXcursor.so.1.0.2
7fcadfa37000-7fcadfa38000 rw-p 0000a000 08:03 49184331                   /usr/lib/libXcursor.so.1.0.2
7fcadfa38000-7fcadfa3a000 r-xp 00000000 08:03 49173419                   /usr/lib/libXinerama.so.1.0.0
7fcadfa3a000-7fcadfc39000 ---p 00002000 08:03 49173419                   /usr/lib/libXinerama.so.1.0.0
7fcadfc39000-7fcadfc3a000 r--p 00001000 08:03 49173419                   /usr/lib/libXinerama.so.1.0.0
7fcadfc3a000-7fcadfc3b000 rw-p 00002000 08:03 49173419                   /usr/lib/libXinerama.so.1.0.0
7fcadfc3b000-7fcadfc84000 r-xp 00000000 08:03 49186554                   /usr/lib/libpango-1.0.so.0.3600.8
7fcadfc84000-7fcadfe84000 ---p 00049000 08:03 49186554                   /usr/lib/libpango-1.0.so.0.3600.8
7fcadfe84000-7fcadfe86000 r--p 00049000 08:03 49186554                   /usr/lib/libpango-1.0.so.0.3600.8
7fcadfe86000-7fcadfe87000 rw-p 0004b000 08:03 49186554                   /usr/lib/libpango-1.0.so.0.3600.8
7fcadfe87000-7fcadfe9b000 r-xp 00000000 08:03 49186556                   /usr/lib/libpangoft2-1.0.so.0.3600.8
7fcadfe9b000-7fcae009b000 ---p 00014000 08:03 49186556                   /usr/lib/libpangoft2-1.0.so.0.3600.8
7fcae009b000-7fcae009c000 r--p 00014000 08:03 49186556                   /usr/lib/libpangoft2-1.0.so.0.3600.8
7fcae009c000-7fcae009d000 rw-p 00015000 08:03 49186556                   /usr/lib/libpangoft2-1.0.so.0.3600.8
7fcae009d000-7fcae020c000 r-xp 00000000 08:03 49172822                   /usr/lib/libgio-2.0.so.0.4200.0
7fcae020c000-7fcae040c000 ---p 0016f000 08:03 49172822                   /usr/lib/libgio-2.0.so.0.4200.0
7fcae040c000-7fcae0410000 r--p 0016f000 08:03 49172822                   /usr/lib/libgio-2.0.so.0.4200.0
7fcae0410000-7fcae0412000 rw-p 00173000 08:03 49172822                   /usr/lib/libgio-2.0.so.0.4200.0
7fcae0412000-7fcae0414000 rw-p 00000000 00:00 0 
7fcae0414000-7fcae0438000 r-xp 00000000 08:03 49184343                   /usr/lib/libgdk_pixbuf-2.0.so.0.3100.1
7fcae0438000-7fcae0637000 ---p 00024000 08:03 49184343                   /usr/lib/libgdk_pixbuf-2.0.so.0.3100.1
7fcae0637000-7fcae0638000 r--p 00023000 08:03 49184343                   /usr/lib/libgdk_pixbuf-2.0.so.0.3100.1
7fcae0638000-7fcae0639000 rw-p 00024000 08:03 49184343                   /usr/lib/libgdk_pixbuf-2.0.so.0.3100.1
7fcae0639000-7fcae0763000 r-xp 00000000 08:03 49155304                   /usr/lib/libcairo.so.2.11400.0
7fcae0763000-7fcae0963000 ---p 0012a000 08:03 49155304                   /usr/lib/libcairo.so.2.11400.0
7fcae0963000-7fcae0966000 r--p 0012a000 08:03 49155304                   /usr/lib/libcairo.so.2.11400.0
7fcae0966000-7fcae0968000 rw-p 0012d000 08:03 49155304                   /usr/lib/libcairo.so.2.11400.0
7fcae0968000-7fcae0969000 rw-p 00000000 00:00 0 
7fcae0969000-7fcae098c000 r-xp 00000000 08:03 49187399                   /usr/lib/libatk-1.0.so.0.21409.1
7fcae098c000-7fcae0b8b000 ---p 00023000 08:03 49187399                   /usr/lib/libatk-1.0.so.0.21409.1
7fcae0b8b000-7fcae0b8e000 r--p 00022000 08:03 49187399                   /usr/lib/libatk-1.0.so.0.21409.1
7fcae0b8e000-7fcae0b8f000 rw-p 00025000 08:03 49187399                   /usr/lib/libatk-1.0.so.0.21409.1
7fcae0b8f000-7fcae0b94000 r-xp 00000000 08:03 49172987                   /usr/lib/libXfixes.so.3.1.0
7fcae0b94000-7fcae0d93000 ---p 00005000 08:03 49172987                   /usr/lib/libXfixes.so.3.1.0
7fcae0d93000-7fcae0d94000 r--p 00004000 08:03 49172987                   /usr/lib/libXfixes.so.3.1.0
7fcae0d94000-7fcae0d95000 rw-p 00005000 08:03 49172987                   /usr/lib/libXfixes.so.3.1.0
7fcae0d95000-7fcae0da1000 r-xp 00000000 08:03 49190233                   /usr/lib/libpangocairo-1.0.so.0.3600.8
7fcae0da1000-7fcae0fa0000 ---p 0000c000 08:03 49190233                   /usr/lib/libpangocairo-1.0.so.0.3600.8
7fcae0fa0000-7fcae0fa1000 r--p 0000b000 08:03 49190233                   /usr/lib/libpangocairo-1.0.so.0.3600.8
7fcae0fa1000-7fcae0fa2000 rw-p 0000c000 08:03 49190233                   /usr/lib/libpangocairo-1.0.so.0.3600.8
7fcae0fa2000-7fcae0fa5000 r-xp 00000000 08:03 49172819                   /usr/lib/libgmodule-2.0.so.0.4200.0
7fcae0fa5000-7fcae11a4000 ---p 00003000 08:03 49172819                   /usr/lib/libgmodule-2.0.so.0.4200.0
7fcae11a4000-7fcae11a5000 r--p 00002000 08:03 49172819                   /usr/lib/libgmodule-2.0.so.0.4200.0
7fcae11a5000-7fcae11a6000 rw-p 00003000 08:03 49172819                   /usr/lib/libgmodule-2.0.so.0.4200.0
7fcae11a6000-7fcae11ac000 r-xp 00000000 08:03 49182162                   /usr/lib/libIlmThread-2_1.so.11.0.0
7fcae11ac000-7fcae13ab000 ---p 00006000 08:03 49182162                   /usr/lib/libIlmThread-2_1.so.11.0.0
7fcae13ab000-7fcae13ac000 r--p 00005000 08:03 49182162                   /usr/lib/libIlmThread-2_1.so.11.0.0
7fcae13ac000-7fcae13ad000 rw-p 00006000 08:03 49182162                   /usr/lib/libIlmThread-2_1.so.11.0.0
7fcae13ad000-7fcae13c9000 r-xp 00000000 08:03 49182159                   /usr/lib/libIex-2_1.so.11.0.0
7fcae13c9000-7fcae15c9000 ---p 0001c000 08:03 49182159                   /usr/lib/libIex-2_1.so.11.0.0
7fcae15c9000-7fcae15cd000 r--p 0001c000 08:03 49182159                   /usr/lib/libIex-2_1.so.11.0.0
7fcae15cd000-7fcae15ce000 rw-p 00020000 08:03 49182159                   /usr/lib/libIex-2_1.so.11.0.0
7fcae15ce000-7fcae15df000 r-xp 00000000 08:03 49182161                   /usr/lib/libImath-2_1.so.11.0.0
7fcae15df000-7fcae17de000 ---p 00011000 08:03 49182161                   /usr/lib/libImath-2_1.so.11.0.0
7fcae17de000-7fcae17df000 r--p 00010000 08:03 49182161                   /usr/lib/libImath-2_1.so.11.0.0
7fcae17df000-7fcae17e0000 rw-p 00011000 08:03 49182161                   /usr/lib/libImath-2_1.so.11.0.0
7fcae17e0000-7fcae1802000 r-xp 00000000 08:03 49160747                   /usr/lib/liblzma.so.5.0.7
7fcae1802000-7fcae1a01000 ---p 00022000 08:03 49160747                   /usr/lib/liblzma.so.5.0.7
7fcae1a01000-7fcae1a02000 r--p 00021000 08:03 49160747                   /usr/lib/liblzma.so.5.0.7
7fcae1a02000-7fcae1a03000 rw-p 00022000 08:03 49160747                   /usr/lib/liblzma.so.5.0.7
7fcae1a03000-7fcae1a66000 r-xp 00000000 08:03 49159552                   /usr/lib/libpcre16.so.0.2.4
7fcae1a66000-7fcae1c65000 ---p 00063000 08:03 49159552                   /usr/lib/libpcre16.so.0.2.4
7fcae1c65000-7fcae1c66000 r--p 00062000 08:03 49159552                   /usr/lib/libpcre16.so.0.2.4
7fcae1c66000-7fcae1c67000 rw-p 00063000 08:03 49159552                   /usr/lib/libpcre16.so.0.2.4
7fcae1c67000-7fcae1cbd000 r-xp 00000000 08:03 49186552                   /usr/lib/libharfbuzz.so.0.935.0
7fcae1cbd000-7fcae1ebc000 ---p 00056000 08:03 49186552                   /usr/lib/libharfbuzz.so.0.935.0
7fcae1ebc000-7fcae1ebe000 r--p 00055000 08:03 49186552                   /usr/lib/libharfbuzz.so.0.935.0
7fcae1ebe000-7fcae1ebf000 rw-p 00057000 08:03 49186552                   /usr/lib/libharfbuzz.so.0.935.0
7fcae1ebf000-7fcae1ec4000 r-xp 00000000 08:03 49173020                   /usr/lib/libXxf86vm.so.1.0.0
7fcae1ec4000-7fcae20c3000 ---p 00005000 08:03 49173020                   /usr/lib/libXxf86vm.so.1.0.0
7fcae20c3000-7fcae20c4000 r--p 00004000 08:03 49173020                   /usr/lib/libXxf86vm.so.1.0.0
7fcae20c4000-7fcae20c5000 rw-p 00005000 08:03 49173020                   /usr/lib/libXxf86vm.so.1.0.0
7fcae20c5000-7fcae20ce000 r-xp 00000000 08:03 49173397                   /usr/lib/libXrandr.so.2.2.0
7fcae20ce000-7fcae22cd000 ---p 00009000 08:03 49173397                   /usr/lib/libXrandr.so.2.2.0
7fcae22cd000-7fcae22ce000 r--p 00008000 08:03 49173397                   /usr/lib/libXrandr.so.2.2.0
7fcae22ce000-7fcae22cf000 rw-p 00009000 08:03 49173397                   /usr/lib/libXrandr.so.2.2.0
7fcae22cf000-7fcae22de000 r-xp 00000000 08:03 49172982                   /usr/lib/libXi.so.6.1.0
7fcae22de000-7fcae24de000 ---p 0000f000 08:03 49172982                   /usr/lib/libXi.so.6.1.0
7fcae24de000-7fcae24df000 r--p 0000f000 08:03 49172982                   /usr/lib/libXi.so.6.1.0
7fcae24df000-7fcae24e0000 rw-p 00010000 08:03 49172982                   /usr/lib/libXi.so.6.1.0
7fcae24e0000-7fcae3ec9000 r-xp 00000000 08:03 49190069                   /usr/lib/libnvidia-glcore.so.343.22
7fcae3ec9000-7fcae3ee7000 rwxp 019e9000 08:03 49190069                   /usr/lib/libnvidia-glcore.so.343.22
7fcae3ee7000-7fcae4375000 r-xp 01a07000 08:03 49190069                   /usr/lib/libnvidia-glcore.so.343.22
7fcae4375000-7fcae4574000 ---p 01e95000 08:03 49190069                   /usr/lib/libnvidia-glcore.so.343.22
7fcae4574000-7fcae512b000 rw-p 01e94000 08:03 49190069                   /usr/lib/libnvidia-glcore.so.343.22
7fcae512b000-7fcae5148000 rw-p 00000000 00:00 0 
7fcae5148000-7fcae514b000 r-xp 00000000 08:03 49190067                   /usr/lib/libnvidia-tls.so.343.22
7fcae514b000-7fcae534a000 ---p 00003000 08:03 49190067                   /usr/lib/libnvidia-tls.so.343.22
7fcae534a000-7fcae534b000 rw-p 00002000 08:03 49190067                   /usr/lib/libnvidia-tls.so.343.22
7fcae534b000-7fcae535c000 r-xp 00000000 08:03 49172959                   /usr/lib/libXext.so.6.4.0
7fcae535c000-7fcae555b000 ---p 00011000 08:03 49172959                   /usr/lib/libXext.so.6.4.0
7fcae555b000-7fcae555c000 r--p 00010000 08:03 49172959                   /usr/lib/libXext.so.6.4.0
7fcae555c000-7fcae555d000 rw-p 00011000 08:03 49172959                   /usr/lib/libXext.so.6.4.0
7fcae555d000-7fcae5598000 r-xp 00000000 08:03 49184168                   /usr/lib/libfontconfig.so.1.8.0
7fcae5598000-7fcae5797000 ---p 0003b000 08:03 49184168                   /usr/lib/libfontconfig.so.1.8.0
7fcae5797000-7fcae5799000 r--p 0003a000 08:03 49184168                   /usr/lib/libfontconfig.so.1.8.0
7fcae5799000-7fcae579a000 rw-p 0003c000 08:03 49184168                   /usr/lib/libfontconfig.so.1.8.0
7fcae579a000-7fcae57b2000 r-xp 00000000 08:03 49179946                   /usr/lib/libICE.so.6.3.0
7fcae57b2000-7fcae59b1000 ---p 00018000 08:03 49179946                   /usr/lib/libICE.so.6.3.0
7fcae59b1000-7fcae59b2000 r--p 00017000 08:03 49179946                   /usr/lib/libICE.so.6.3.0
7fcae59b2000-7fcae59b3000 rw-p 00018000 08:03 49179946                   /usr/lib/libICE.so.6.3.0
7fcae59b3000-7fcae59b7000 rw-p 00000000 00:00 0 
7fcae59b7000-7fcae59be000 r-xp 00000000 08:03 49173025                   /usr/lib/libSM.so.6.0.1
7fcae59be000-7fcae5bbd000 ---p 00007000 08:03 49173025                   /usr/lib/libSM.so.6.0.1
7fcae5bbd000-7fcae5bbe000 r--p 00006000 08:03 49173025                   /usr/lib/libSM.so.6.0.1
7fcae5bbe000-7fcae5bbf000 rw-p 00007000 08:03 49173025                   /usr/lib/libSM.so.6.0.1
7fcae5bbf000-7fcae5cfa000 r-xp 00000000 08:03 49172846                   /usr/lib/libX11.so.6.3.0
7fcae5cfa000-7fcae5ef9000 ---p 0013b000 08:03 49172846                   /usr/lib/libX11.so.6.3.0
7fcae5ef9000-7fcae5efb000 r--p 0013a000 08:03 49172846                   /usr/lib/libX11.so.6.3.0
7fcae5efb000-7fcae5f00000 rw-p 0013c000 08:03 49172846                   /usr/lib/libX11.so.6.3.0
7fcae5f00000-7fcae5f01000 rw-p 00000000 00:00 0 
7fcae5f01000-7fcae5f0a000 r-xp 00000000 08:03 49173394                   /usr/lib/libXrender.so.1.3.0
7fcae5f0a000-7fcae6109000 ---p 00009000 08:03 49173394                   /usr/lib/libXrender.so.1.3.0
7fcae6109000-7fcae610a000 r--p 00008000 08:03 49173394                   /usr/lib/libXrender.so.1.3.0
7fcae610a000-7fcae610b000 rw-p 00009000 08:03 49173394                   /usr/lib/libXrender.so.1.3.0
7fcae610b000-7fcae61b8000 r-xp 00000000 08:03 49169293                   /usr/lib/libfreetype.so.6.10.1
7fcae61b8000-7fcae63b7000 ---p 000ad000 08:03 49169293                   /usr/lib/libfreetype.so.6.10.1
7fcae63b7000-7fcae63bd000 r--p 000ac000 08:03 49169293                   /usr/lib/libfreetype.so.6.10.1
7fcae63bd000-7fcae63be000 rw-p 000b2000 08:03 49169293                   /usr/lib/libfreetype.so.6.10.1
7fcae63be000-7fcae6400000 r-xp 00000000 08:03 55584800                   /opt/ros/indigo/lib/librospack.so
7fcae6400000-7fcae6600000 ---p 00042000 08:03 55584800                   /opt/ros/indigo/lib/librospack.so
7fcae6600000-7fcae6601000 r--p 00042000 08:03 55584800                   /opt/ros/indigo/lib/librospack.so
7fcae6601000-7fcae6602000 rw-p 00043000 08:03 55584800                   /opt/ros/indigo/lib/librospack.so
7fcae6602000-7fcae7e2c000 r--p 00000000 08:03 49179349                   /usr/lib/libicudata.so.54.1
7fcae7e2c000-7fcae802b000 ---p 0182a000 08:03 49179349                   /usr/lib/libicudata.so.54.1
7fcae802b000-7fcae802c000 r--p 01829000 08:03 49179349                   /usr/lib/libicudata.so.54.1
7fcae802c000-7fcae8270000 r-xp 00000000 08:03 49179327                   /usr/lib/libicui18n.so.54.1
7fcae8270000-7fcae8470000 ---p 00244000 08:03 49179327                   /usr/lib/libicui18n.so.54.1
7fcae8470000-7fcae8480000 r--p 00244000 08:03 49179327                   /usr/lib/libicui18n.so.54.1
7fcae8480000-7fcae8482000 rw-p 00254000 08:03 49179327                   /usr/lib/libicui18n.so.54.1
7fcae8482000-7fcae8483000 rw-p 00000000 00:00 0 
7fcae8483000-7fcae85fd000 r-xp 00000000 08:03 49179332                   /usr/lib/libicuuc.so.54.1
7fcae85fd000-7fcae87fd000 ---p 0017a000 08:03 49179332                   /usr/lib/libicuuc.so.54.1
7fcae87fd000-7fcae880e000 r--p 0017a000 08:03 49179332                   /usr/lib/libicuuc.so.54.1
7fcae880e000-7fcae880f000 rw-p 0018b000 08:03 49179332                   /usr/lib/libicuuc.so.54.1
7fcae880f000-7fcae8813000 rw-p 00000000 00:00 0 
7fcae8813000-7fcae881b000 r-xp 00000000 08:03 49155211                   /usr/lib/libcrypt-2.20.so
7fcae881b000-7fcae8a1b000 ---p 00008000 08:03 49155211                   /usr/lib/libcrypt-2.20.so
7fcae8a1b000-7fcae8a1c000 r--p 00008000 08:03 49155211                   /usr/lib/libcrypt-2.20.so
7fcae8a1c000-7fcae8a1d000 rw-p 00009000 08:03 49155211                   /usr/lib/libcrypt-2.20.so
7fcae8a1d000-7fcae8a4b000 rw-p 00000000 00:00 0 
7fcae8a4b000-7fcae8a4f000 r-xp 00000000 08:03 49192332                   /usr/lib/libuuid.so.1.3.0
7fcae8a4f000-7fcae8c4e000 ---p 00004000 08:03 49192332                   /usr/lib/libuuid.so.1.3.0
7fcae8c4e000-7fcae8c4f000 r--p 00003000 08:03 49192332                   /usr/lib/libuuid.so.1.3.0
7fcae8c4f000-7fcae8c50000 rw-p 00004000 08:03 49192332                   /usr/lib/libuuid.so.1.3.0
7fcae8c50000-7fcae8c82000 r-xp 00000000 08:03 49188604                   /usr/lib/libapr-1.so.0.5.1
7fcae8c82000-7fcae8e82000 ---p 00032000 08:03 49188604                   /usr/lib/libapr-1.so.0.5.1
7fcae8e82000-7fcae8e83000 r--p 00032000 08:03 49188604                   /usr/lib/libapr-1.so.0.5.1
7fcae8e83000-7fcae8e84000 rw-p 00033000 08:03 49188604                   /usr/lib/libapr-1.so.0.5.1
7fcae8e84000-7fcae8eab000 r-xp 00000000 08:03 49159476                   /usr/lib/libexpat.so.1.6.0
7fcae8eab000-7fcae90ab000 ---p 00027000 08:03 49159476                   /usr/lib/libexpat.so.1.6.0
7fcae90ab000-7fcae90ad000 r--p 00027000 08:03 49159476                   /usr/lib/libexpat.so.1.6.0
7fcae90ad000-7fcae90ae000 rw-p 00029000 08:03 49159476                   /usr/lib/libexpat.so.1.6.0
7fcae90ae000-7fcae90b8000 r-xp 00000000 08:03 49187771                   /usr/lib/libgdbm.so.4.0.0
7fcae90b8000-7fcae92b8000 ---p 0000a000 08:03 49187771                   /usr/lib/libgdbm.so.4.0.0
7fcae92b8000-7fcae92b9000 r--p 0000a000 08:03 49187771                   /usr/lib/libgdbm.so.4.0.0
7fcae92b9000-7fcae92ba000 rw-p 0000b000 08:03 49187771                   /usr/lib/libgdbm.so.4.0.0
7fcae92ba000-7fcae946f000 r-xp 00000000 08:03 49158386                   /usr/lib/libdb-5.3.so
7fcae946f000-7fcae966f000 ---p 001b5000 08:03 49158386                   /usr/lib/libdb-5.3.so
7fcae966f000-7fcae9677000 r--p 001b5000 08:03 49158386                   /usr/lib/libdb-5.3.so
7fcae9677000-7fcae967a000 rw-p 001bd000 08:03 49158386                   /usr/lib/libdb-5.3.so
7fcae967a000-7fcae9688000 r-xp 00000000 08:03 49164127                   /usr/lib/liblber-2.4.so.2.10.3
7fcae9688000-7fcae9887000 ---p 0000e000 08:03 49164127                   /usr/lib/liblber-2.4.so.2.10.3
7fcae9887000-7fcae9888000 r--p 0000d000 08:03 49164127                   /usr/lib/liblber-2.4.so.2.10.3
7fcae9888000-7fcae9889000 rw-p 0000e000 08:03 49164127                   /usr/lib/liblber-2.4.so.2.10.3
7fcae9889000-7fcae98d2000 r-xp 00000000 08:03 49192334                   /usr/lib/libldap-2.4.so.2.10.3
7fcae98d2000-7fcae9ad2000 ---p 00049000 08:03 49192334                   /usr/lib/libldap-2.4.so.2.10.3
7fcae9ad2000-7fcae9ad3000 r--p 00049000 08:03 49192334                   /usr/lib/libldap-2.4.so.2.10.3
7fcae9ad3000-7fcae9ad5000 rw-p 0004a000 08:03 49192334                   /usr/lib/libldap-2.4.so.2.10.3
7fcae9ad5000-7fcae9afc000 r-xp 00000000 08:03 49182058                   /usr/lib/libaprutil-1.so.0.5.4
7fcae9afc000-7fcae9cfb000 ---p 00027000 08:03 49182058                   /usr/lib/libaprutil-1.so.0.5.4
7fcae9cfb000-7fcae9cfc000 r--p 00026000 08:03 49182058                   /usr/lib/libaprutil-1.so.0.5.4
7fcae9cfc000-7fcae9cfd000 rw-p 00027000 08:03 49182058                   /usr/lib/libaprutil-1.so.0.5.4
7fcae9cfd000-7fcae9d0c000 r-xp 00000000 08:03 49158320                   /usr/lib/libbz2.so.1.0.6
7fcae9d0c000-7fcae9f0b000 ---p 0000f000 08:03 49158320                   /usr/lib/libbz2.so.1.0.6
7fcae9f0b000-7fcae9f0d000 rw-p 0000e000 08:03 49158320                   /usr/lib/libbz2.so.1.0.6
7fcae9f0d000-7fcae9f25000 r-xp 00000000 08:03 49194859                   /usr/lib/libboost_thread.so.1.55.0
7fcae9f25000-7fcaea124000 ---p 00018000 08:03 49194859                   /usr/lib/libboost_thread.so.1.55.0
7fcaea124000-7fcaea126000 rw-p 00017000 08:03 49194859                   /usr/lib/libboost_thread.so.1.55.0
7fcaea126000-7fcaea22f000 r-xp 00000000 08:03 49193972                   /usr/lib/libboost_regex.so.1.55.0
7fcaea22f000-7fcaea42e000 ---p 00109000 08:03 49193972                   /usr/lib/libboost_regex.so.1.55.0
7fcaea42e000-7fcaea435000 rw-p 00108000 08:03 49193972                   /usr/lib/libboost_regex.so.1.55.0
7fcaea435000-7fcaea44b000 r-xp 00000000 08:03 49194860                   /usr/lib/libboost_filesystem.so.1.55.0
7fcaea44b000-7fcaea64b000 ---p 00016000 08:03 49194860                   /usr/lib/libboost_filesystem.so.1.55.0
7fcaea64b000-7fcaea64c000 rw-p 00016000 08:03 49194860                   /usr/lib/libboost_filesystem.so.1.55.0
7fcaea64c000-7fcaea64f000 r-xp 00000000 08:03 49194858                   /usr/lib/libboost_system.so.1.55.0
7fcaea64f000-7fcaea84e000 ---p 00003000 08:03 49194858                   /usr/lib/libboost_system.so.1.55.0
7fcaea84e000-7fcaea84f000 rw-p 00002000 08:03 49194858                   /usr/lib/libboost_system.so.1.55.0
7fcaea84f000-7fcaea856000 r-xp 00000000 08:03 49155170                   /usr/lib/librt-2.20.so
7fcaea856000-7fcaeaa55000 ---p 00007000 08:03 49155170                   /usr/lib/librt-2.20.so
7fcaeaa55000-7fcaeaa56000 r--p 00006000 08:03 49155170                   /usr/lib/librt-2.20.so
7fcaeaa56000-7fcaeaa57000 rw-p 00007000 08:03 49155170                   /usr/lib/librt-2.20.so
7fcaeaa57000-7fcaeaa6c000 r-xp 00000000 08:03 49158394                   /usr/lib/libz.so.1.2.8
7fcaeaa6c000-7fcaeac6b000 ---p 00015000 08:03 49158394                   /usr/lib/libz.so.1.2.8
7fcaeac6b000-7fcaeac6c000 r--p 00014000 08:03 49158394                   /usr/lib/libz.so.1.2.8
7fcaeac6c000-7fcaeac6d000 rw-p 00015000 08:03 49158394                   /usr/lib/libz.so.1.2.8
7fcaeac6d000-7fcaeacda000 r-xp 00000000 08:03 49180066                   /usr/lib/libswscale.so.3.0.100
7fcaeacda000-7fcaeaeda000 ---p 0006d000 08:03 49180066                   /usr/lib/libswscale.so.3.0.100
7fcaeaeda000-7fcaeaedb000 r--p 0006d000 08:03 49180066                   /usr/lib/libswscale.so.3.0.100
7fcaeaedb000-7fcaeaedc000 rw-p 0006e000 08:03 49180066                   /usr/lib/libswscale.so.3.0.100
7fcaeaedc000-7fcaeaee4000 rw-p 00000000 00:00 0 
7fcaeaee4000-7fcaeaf27000 r-xp 00000000 08:03 49180067                   /usr/lib/libavutil.so.54.7.100
7fcaeaf27000-7fcaeb126000 ---p 00043000 08:03 49180067                   /usr/lib/libavutil.so.54.7.100
7fcaeb126000-7fcaeb12c000 r--p 00042000 08:03 49180067                   /usr/lib/libavutil.so.54.7.100
7fcaeb12c000-7fcaeb12d000 rw-p 00048000 08:03 49180067                   /usr/lib/libavutil.so.54.7.100
7fcaeb12d000-7fcaeb13d000 rw-p 00000000 00:00 0 
7fcaeb13d000-7fcaeb2c6000 r-xp 00000000 08:03 49180053                   /usr/lib/libavformat.so.56.4.101
7fcaeb2c6000-7fcaeb4c5000 ---p 00189000 08:03 49180053                   /usr/lib/libavformat.so.56.4.101
7fcaeb4c5000-7fcaeb4d6000 r--p 00188000 08:03 49180053                   /usr/lib/libavformat.so.56.4.101
7fcaeb4d6000-7fcaeb4eb000 rw-p 00199000 08:03 49180053                   /usr/lib/libavformat.so.56.4.101
7fcaeb4eb000-7fcaebe18000 r-xp 00000000 08:03 49180057                   /usr/lib/libavcodec.so.56.1.100
7fcaebe18000-7fcaec018000 ---p 0092d000 08:03 49180057                   /usr/lib/libavcodec.so.56.1.100
7fcaec018000-7fcaec03d000 r--p 0092d000 08:03 49180057                   /usr/lib/libavcodec.so.56.1.100
7fcaec03d000-7fcaec05b000 rw-p 00952000 08:03 49180057                   /usr/lib/libavcodec.so.56.1.100
7fcaec05b000-7fcaec6a9000 rw-p 00000000 00:00 0 
7fcaec6a9000-7fcaec6ae000 r-xp 00000000 08:03 49178438                   /usr/lib/libv4l1.so.0.0.0
7fcaec6ae000-7fcaec8ad000 ---p 00005000 08:03 49178438                   /usr/lib/libv4l1.so.0.0.0
7fcaec8ad000-7fcaec8ae000 r--p 00004000 08:03 49178438                   /usr/lib/libv4l1.so.0.0.0
7fcaec8ae000-7fcaec8af000 rw-p 00005000 08:03 49178438                   /usr/lib/libv4l1.so.0.0.0
7fcaec8af000-7fcaec915000 r-xp 00000000 08:03 49189338                   /usr/lib/libxine.so.2.5.0
7fcaec915000-7fcaecb15000 ---p 00066000 08:03 49189338                   /usr/lib/libxine.so.2.5.0
7fcaecb15000-7fcaecb19000 r--p 00066000 08:03 49189338                   /usr/lib/libxine.so.2.5.0
7fcaecb19000-7fcaecb1a000 rw-p 0006a000 08:03 49189338                   /usr/lib/libxine.so.2.5.0
7fcaecb1a000-7fcaecb1e000 rw-p 00000000 00:00 0 
7fcaecb1e000-7fcaecb52000 r-xp 00000000 08:03 49178772                   /usr/lib/libdc1394.so.22.1.8
7fcaecb52000-7fcaecd51000 ---p 00034000 08:03 49178772                   /usr/lib/libdc1394.so.22.1.8
7fcaecd51000-7fcaecd52000 r--p 00033000 08:03 49178772                   /usr/lib/libdc1394.so.22.1.8
7fcaecd52000-7fcaecd53000 rw-p 00034000 08:03 49178772                   /usr/lib/libdc1394.so.22.1.8
7fcaecd53000-7fcaecd93000 rw-p 00000000 00:00 0 
7fcaecd93000-7fcaecdf0000 r-xp 00000000 08:03 49189350                   /usr/lib/libgdkglext-x11-1.0.so.0.0.0
7fcaecdf0000-7fcaecfef000 ---p 0005d000 08:03 49189350                   /usr/lib/libgdkglext-x11-1.0.so.0.0.0
7fcaecfef000-7fcaecff1000 r--p 0005c000 08:03 49189350                   /usr/lib/libgdkglext-x11-1.0.so.0.0.0
7fcaecff1000-7fcaecff7000 rw-p 0005e000 08:03 49189350                   /usr/lib/libgdkglext-x11-1.0.so.0.0.0
7fcaecff7000-7fcaecffa000 r-xp 00000000 08:03 49189351                   /usr/lib/libgtkglext-x11-1.0.so.0.0.0
7fcaecffa000-7fcaed1f9000 ---p 00003000 08:03 49189351                   /usr/lib/libgtkglext-x11-1.0.so.0.0.0
7fcaed1f9000-7fcaed1fa000 r--p 00002000 08:03 49189351                   /usr/lib/libgtkglext-x11-1.0.so.0.0.0
7fcaed1fa000-7fcaed1fb000 rw-p 00003000 08:03 49189351                   /usr/lib/libgtkglext-x11-1.0.so.0.0.0
7fcaed1fb000-7fcaed307000 r-xp 00000000 08:03 49172818                   /usr/lib/libglib-2.0.so.0.4200.0
7fcaed307000-7fcaed506000 ---p 0010c000 08:03 49172818                   /usr/lib/libglib-2.0.so.0.4200.0
7fcaed506000-7fcaed507000 r--p 0010b000 08:03 49172818                   /usr/lib/libglib-2.0.so.0.4200.0
7fcaed507000-7fcaed508000 rw-p 0010c000 08:03 49172818                   /usr/lib/libglib-2.0.so.0.4200.0
7fcaed508000-7fcaed509000 rw-p 00000000 00:00 0 
7fcaed509000-7fcaed558000 r-xp 00000000 08:03 49172821                   /usr/lib/libgobject-2.0.so.0.4200.0
7fcaed558000-7fcaed758000 ---p 0004f000 08:03 49172821                   /usr/lib/libgobject-2.0.so.0.4200.0
7fcaed758000-7fcaed759000 r--p 0004f000 08:03 49172821                   /usr/lib/libgobject-2.0.so.0.4200.0
7fcaed759000-7fcaed75a000 rw-p 00050000 08:03 49172821                   /usr/lib/libgobject-2.0.so.0.4200.0
7fcaed75a000-7fcaed80a000 r-xp 00000000 08:03 49173366                   /usr/lib/libgdk-x11-2.0.so.0.2400.25
7fcaed80a000-7fcaeda09000 ---p 000b0000 08:03 49173366                   /usr/lib/libgdk-x11-2.0.so.0.2400.25
7fcaeda09000-7fcaeda0d000 r--p 000af000 08:03 49173366                   /usr/lib/libgdk-x11-2.0.so.0.2400.25
7fcaeda0d000-7fcaeda0f000 rw-p 000b3000 08:03 49173366                   /usr/lib/libgdk-x11-2.0.so.0.2400.25
7fcaeda0f000-7fcaede44000 r-xp 00000000 08:03 49173367                   /usr/lib/libgtk-x11-2.0.so.0.2400.25
7fcaede44000-7fcaee044000 ---p 00435000 08:03 49173367                   /usr/lib/libgtk-x11-2.0.so.0.2400.25
7fcaee044000-7fcaee04b000 r--p 00435000 08:03 49173367                   /usr/lib/libgtk-x11-2.0.so.0.2400.25
7fcaee04b000-7fcaee04f000 rw-p 0043c000 08:03 49173367                   /usr/lib/libgtk-x11-2.0.so.0.2400.25
7fcaee04f000-7fcaee052000 rw-p 00000000 00:00 0 
7fcaee052000-7fcaee094000 r-xp 00000000 08:03 49182158                   /usr/lib/libHalf.so.11.0.0
7fcaee094000-7fcaee293000 ---p 00042000 08:03 49182158                   /usr/lib/libHalf.so.11.0.0
7fcaee293000-7fcaee294000 r--p 00041000 08:03 49182158                   /usr/lib/libHalf.so.11.0.0
7fcaee294000-7fcaee295000 rw-p 00042000 08:03 49182158                   /usr/lib/libHalf.so.11.0.0
7fcaee295000-7fcaee3a6000 r-xp 00000000 08:03 49182174                   /usr/lib/libIlmImf-Imf_2_1.so.21.0.0
7fcaee3a6000-7fcaee5a5000 ---p 00111000 08:03 49182174                   /usr/lib/libIlmImf-Imf_2_1.so.21.0.0
7fcaee5a5000-7fcaee5a9000 r--p 00110000 08:03 49182174                   /usr/lib/libIlmImf-Imf_2_1.so.21.0.0
7fcaee5a9000-7fcaee5ab000 rw-p 00114000 08:03 49182174                   /usr/lib/libIlmImf-Imf_2_1.so.21.0.0
7fcaee5ab000-7fcaee5ac000 rw-p 00000000 00:00 0 
7fcaee5ac000-7fcaee5fa000 r-xp 00000000 08:03 49175219                   /usr/lib/libjasper.so.1.0.0
7fcaee5fa000-7fcaee7fa000 ---p 0004e000 08:03 49175219                   /usr/lib/libjasper.so.1.0.0
7fcaee7fa000-7fcaee7fb000 r--p 0004e000 08:03 49175219                   /usr/lib/libjasper.so.1.0.0
7fcaee7fb000-7fcaee7ff000 rw-p 0004f000 08:03 49175219                   /usr/lib/libjasper.so.1.0.0
7fcaee7ff000-7fcaee806000 rw-p 00000000 00:00 0 
7fcaee806000-7fcaee882000 r-xp 00000000 08:03 49175062                   /usr/lib/libtiff.so.5.2.0
7fcaee882000-7fcaeea82000 ---p 0007c000 08:03 49175062                   /usr/lib/libtiff.so.5.2.0
7fcaeea82000-7fcaeea83000 r--p 0007c000 08:03 49175062                   /usr/lib/libtiff.so.5.2.0
7fcaeea83000-7fcaeea89000 rw-p 0007d000 08:03 49175062                   /usr/lib/libtiff.so.5.2.0
7fcaeea89000-7fcaeea8a000 rw-p 00000000 00:00 0 
7fcaeea8a000-7fcaeeabf000 r-xp 00000000 08:03 49155322                   /usr/lib/libpng16.so.16.13.0
7fcaeeabf000-7fcaeecbe000 ---p 00035000 08:03 49155322                   /usr/lib/libpng16.so.16.13.0
7fcaeecbe000-7fcaeecbf000 r--p 00034000 08:03 49155322                   /usr/lib/libpng16.so.16.13.0
7fcaeecbf000-7fcaeecc0000 rw-p 00035000 08:03 49155322                   /usr/lib/libpng16.so.16.13.0
7fcaeecc0000-7fcaeed03000 r-xp 00000000 08:03 49174943                   /usr/lib/libjpeg.so.8.0.2
7fcaeed03000-7fcaeef03000 ---p 00043000 08:03 49174943                   /usr/lib/libjpeg.so.8.0.2
7fcaeef03000-7fcaeef04000 r--p 00043000 08:03 49174943                   /usr/lib/libjpeg.so.8.0.2
7fcaeef04000-7fcaeef05000 rw-p 00044000 08:03 49174943                   /usr/lib/libjpeg.so.8.0.2
7fcaeef05000-7fcaeef15000 rw-p 00000000 00:00 0 
7fcaeef15000-7fcaeef4a000 r-xp 00000000 08:03 49180098                   /usr/lib/libtbb.so.2
7fcaeef4a000-7fcaef149000 ---p 00035000 08:03 49180098                   /usr/lib/libtbb.so.2
7fcaef149000-7fcaef14b000 r--p 00034000 08:03 49180098                   /usr/lib/libtbb.so.2
7fcaef14b000-7fcaef14d000 rw-p 00036000 08:03 49180098                   /usr/lib/libtbb.so.2
7fcaef14d000-7fcaef150000 rw-p 00000000 00:00 0 
7fcaef150000-7fcaef153000 r-xp 00000000 08:03 49155132                   /usr/lib/libdl-2.20.so
7fcaef153000-7fcaef352000 ---p 00003000 08:03 49155132                   /usr/lib/libdl-2.20.so
7fcaef352000-7fcaef353000 r--p 00002000 08:03 49155132                   /usr/lib/libdl-2.20.so
7fcaef353000-7fcaef354000 rw-p 00003000 08:03 49155132                   /usr/lib/libdl-2.20.so
7fcaef354000-7fcaef814000 r-xp 00000000 08:03 49188154                   /usr/lib/libQt5Core.so.5.3.2
7fcaef814000-7fcaefa14000 ---p 004c0000 08:03 49188154                   /usr/lib/libQt5Core.so.5.3.2
7fcaefa14000-7fcaefa1f000 r--p 004c0000 08:03 49188154                   /usr/lib/libQt5Core.so.5.3.2
7fcaefa1f000-7fcaefa20000 rw-p 004cb000 08:03 49188154                   /usr/lib/libQt5Core.so.5.3.2
7fcaefa20000-7fcaefa22000 rw-p 00000000 00:00 0 
7fcaefa22000-7fcaeff37000 r-xp 00000000 08:03 49188161                   /usr/lib/libQt5Gui.so.5.3.2
7fcaeff37000-7fcaf0137000 ---p 00515000 08:03 49188161                   /usr/lib/libQt5Gui.so.5.3.2
7fcaf0137000-7fcaf014d000 r--p 00515000 08:03 49188161                   /usr/lib/libQt5Gui.so.5.3.2
7fcaf014d000-7fcaf0154000 rw-p 0052b000 08:03 49188161                   /usr/lib/libQt5Gui.so.5.3.2
7fcaf0154000-7fcaf0156000 rw-p 00000000 00:00 0 
7fcaf0156000-7fcaf0191000 r-xp 00000000 08:03 49188155                   /usr/lib/libQt5Xml.so.5.3.2
7fcaf0191000-7fcaf0390000 ---p 0003b000 08:03 49188155                   /usr/lib/libQt5Xml.so.5.3.2
7fcaf0390000-7fcaf0392000 r--p 0003a000 08:03 49188155                   /usr/lib/libQt5Xml.so.5.3.2
7fcaf0392000-7fcaf0393000 rw-p 0003c000 08:03 49188155                   /usr/lib/libQt5Xml.so.5.3.2
7fcaf0393000-7fcaf09b2000 r-xp 00000000 08:03 49188164                   /usr/lib/libQt5Widgets.so.5.3.2
7fcaf09b2000-7fcaf0bb1000 ---p 0061f000 08:03 49188164                   /usr/lib/libQt5Widgets.so.5.3.2
7fcaf0bb1000-7fcaf0bdd000 r--p 0061e000 08:03 49188164                   /usr/lib/libQt5Widgets.so.5.3.2
7fcaf0bdd000-7fcaf0be2000 rw-p 0064a000 08:03 49188164                   /usr/lib/libQt5Widgets.so.5.3.2
7fcaf0be2000-7fcaf0c3a000 r-xp 00000000 08:03 49188166                   /usr/lib/libQt5OpenGL.so.5.3.2
7fcaf0c3a000-7fcaf0e39000 ---p 00058000 08:03 49188166                   /usr/lib/libQt5OpenGL.so.5.3.2
7fcaf0e39000-7fcaf0e3b000 r--p 00057000 08:03 49188166                   /usr/lib/libQt5OpenGL.so.5.3.2
7fcaf0e3b000-7fcaf0e3c000 rw-p 00059000 08:03 49188166                   /usr/lib/libQt5OpenGL.so.5.3.2
7fcaf0e3c000-7fcaf0e3d000 rw-p 00000000 00:00 0 
7fcaf0e3d000-7fcaf0fd6000 r-xp 00000000 08:03 49155159                   /usr/lib/libc-2.20.so
7fcaf0fd6000-7fcaf11d6000 ---p 00199000 08:03 49155159                   /usr/lib/libc-2.20.so
7fcaf11d6000-7fcaf11da000 r--p 00199000 08:03 49155159                   /usr/lib/libc-2.20.so
7fcaf11da000-7fcaf11dc000 rw-p 0019d000 08:03 49155159                   /usr/lib/libc-2.20.so
7fcaf11dc000-7fcaf11e0000 rw-p 00000000 00:00 0 
7fcaf11e0000-7fcaf11f6000 r-xp 00000000 08:03 49158328                   /usr/lib/libgcc_s.so.1
7fcaf11f6000-7fcaf13f5000 ---p 00016000 08:03 49158328                   /usr/lib/libgcc_s.so.1
7fcaf13f5000-7fcaf13f6000 rw-p 00015000 08:03 49158328                   /usr/lib/libgcc_s.so.1
7fcaf13f6000-7fcaf14f9000 r-xp 00000000 08:03 49155158                   /usr/lib/libm-2.20.so
7fcaf14f9000-7fcaf16f9000 ---p 00103000 08:03 49155158                   /usr/lib/libm-2.20.so
7fcaf16f9000-7fcaf16fa000 r--p 00103000 08:03 49155158                   /usr/lib/libm-2.20.so
7fcaf16fa000-7fcaf16fb000 rw-p 00104000 08:03 49155158                   /usr/lib/libm-2.20.so
7fcaf16fb000-7fcaf17eb000 r-xp 00000000 08:03 49172696                   /usr/lib/libstdc++.so.6.0.20
7fcaf17eb000-7fcaf19eb000 ---p 000f0000 08:03 49172696                   /usr/lib/libstdc++.so.6.0.20
7fcaf19eb000-7fcaf19f3000 r--p 000f0000 08:03 49172696                   /usr/lib/libstdc++.so.6.0.20
7fcaf19f3000-7fcaf19f5000 rw-p 000f8000 08:03 49172696                   /usr/lib/libstdc++.so.6.0.20
7fcaf19f5000-7fcaf1a0a000 rw-p 00000000 00:00 0 
7fcaf1a0a000-7fcaf1a89000 r-xp 00000000 08:03 49175208                   /usr/lib/libGLU.so.1.3.1
7fcaf1a89000-7fcaf1c88000 ---p 0007f000 08:03 49175208                   /usr/lib/libGLU.so.1.3.1
7fcaf1c88000-7fcaf1c8a000 r--p 0007e000 08:03 49175208                   /usr/lib/libGLU.so.1.3.1
7fcaf1c8a000-7fcaf1c8b000 rw-p 00080000 08:03 49175208                   /usr/lib/libGLU.so.1.3.1
7fcaf1c8b000-7fcaf1cce000 r-xp 00000000 08:03 49160198                   /usr/lib/libglut.so.3.9.0
7fcaf1cce000-7fcaf1ecd000 ---p 00043000 08:03 49160198                   /usr/lib/libglut.so.3.9.0
7fcaf1ecd000-7fcaf1ed1000 r--p 00042000 08:03 49160198                   /usr/lib/libglut.so.3.9.0
7fcaf1ed1000-7fcaf1ed6000 rw-p 00046000 08:03 49160198                   /usr/lib/libglut.so.3.9.0
7fcaf1ed6000-7fcaf1ed7000 rw-p 00000000 00:00 0 
7fcaf1ed7000-7fcaf1f9f000 r-xp 00000000 08:03 49685941                   /usr/lib/nvidia/libGL.so.343.22
7fcaf1f9f000-7fcaf1fce000 rwxp 000c8000 08:03 49685941                   /usr/lib/nvidia/libGL.so.343.22
7fcaf1fce000-7fcaf1fea000 r-xp 000f7000 08:03 49685941                   /usr/lib/nvidia/libGL.so.343.22
7fcaf1fea000-7fcaf21ea000 ---p 00113000 08:03 49685941                   /usr/lib/nvidia/libGL.so.343.22
7fcaf21ea000-7fcaf220e000 rw-p 00113000 08:03 49685941                   /usr/lib/nvidia/libGL.so.343.22
7fcaf220e000-7fcaf2225000 rw-p 00000000 00:00 0 
7fcaf2225000-7fcaf2506000 r-xp 00000000 08:03 49178392                   /usr/lib/libQtCore.so.4.8.6
7fcaf2506000-7fcaf2706000 ---p 002e1000 08:03 49178392                   /usr/lib/libQtCore.so.4.8.6
7fcaf2706000-7fcaf2711000 r--p 002e1000 08:03 49178392                   /usr/lib/libQtCore.so.4.8.6
7fcaf2711000-7fcaf2712000 rw-p 002ec000 08:03 49178392                   /usr/lib/libQtCore.so.4.8.6
7fcaf2712000-7fcaf2713000 rw-p 00000000 00:00 0 
7fcaf2713000-7fcaf2756000 r-xp 00000000 08:03 49178393                   /usr/lib/libQtXml.so.4.8.6
7fcaf2756000-7fcaf2956000 ---p 00043000 08:03 49178393                   /usr/lib/libQtXml.so.4.8.6
7fcaf2956000-7fcaf2958000 r--p 00043000 08:03 49178393                   /usr/lib/libQtXml.so.4.8.6
7fcaf2958000-7fcaf2959000 rw-p 00045000 08:03 49178393                   /usr/lib/libQtXml.so.4.8.6
7fcaf2959000-7fcaf33f8000 r-xp 00000000 08:03 49178398                   /usr/lib/libQtGui.so.4.8.6
7fcaf33f8000-7fcaf35f7000 ---p 00a9f000 08:03 49178398                   /usr/lib/libQtGui.so.4.8.6
7fcaf35f7000-7fcaf363a000 r--p 00a9e000 08:03 49178398                   /usr/lib/libQtGui.so.4.8.6
7fcaf363a000-7fcaf3642000 rw-p 00ae1000 08:03 49178398                   /usr/lib/libQtGui.so.4.8.6
7fcaf3642000-7fcaf3645000 rw-p 00000000 00:00 0 
7fcaf3645000-7fcaf373d000 r-xp 00000000 08:03 49178400                   /usr/lib/libQtOpenGL.so.4.8.6
7fcaf373d000-7fcaf393c000 ---p 000f8000 08:03 49178400                   /usr/lib/libQtOpenGL.so.4.8.6
7fcaf393c000-7fcaf3940000 r--p 000f7000 08:03 49178400                   /usr/lib/libQtOpenGL.so.4.8.6
7fcaf3940000-7fcaf3945000 rw-p 000fb000 08:03 49178400                   /usr/lib/libQtOpenGL.so.4.8.6
7fcaf3945000-7fcaf3946000 rw-p 00000000 00:00 0 
7fcaf3946000-7fcaf3955000 r-xp 00000000 08:03 55586466                   /opt/ros/indigo/lib/libroslib.so
7fcaf3955000-7fcaf3b55000 ---p 0000f000 08:03 55586466                   /opt/ros/indigo/lib/libroslib.so
7fcaf3b55000-7fcaf3b56000 r--p 0000f000 08:03 55586466                   /opt/ros/indigo/lib/libroslib.so
7fcaf3b56000-7fcaf3b57000 rw-p 00010000 08:03 55586466                   /opt/ros/indigo/lib/libroslib.so
7fcaf3b57000-7fcaf3b5f000 r-xp 00000000 08:03 49189275                   /usr/lib/libconsole_bridge.so
7fcaf3b5f000-7fcaf3d5f000 ---p 00008000 08:03 49189275                   /usr/lib/libconsole_bridge.so
7fcaf3d5f000-7fcaf3d60000 r--p 00008000 08:03 49189275                   /usr/lib/libconsole_bridge.so
7fcaf3d60000-7fcaf3d61000 rw-p 00009000 08:03 49189275                   /usr/lib/libconsole_bridge.so
7fcaf3d61000-7fcaf3d82000 r-xp 00000000 08:03 49181866                   /usr/lib/libboost_thread.so.1.56.0
7fcaf3d82000-7fcaf3f82000 ---p 00021000 08:03 49181866                   /usr/lib/libboost_thread.so.1.56.0
7fcaf3f82000-7fcaf3f84000 r--p 00021000 08:03 49181866                   /usr/lib/libboost_thread.so.1.56.0
7fcaf3f84000-7fcaf3f85000 rw-p 00023000 08:03 49181866                   /usr/lib/libboost_thread.so.1.56.0
7fcaf3f85000-7fcaf3f88000 r-xp 00000000 08:03 49181862                   /usr/lib/libboost_system.so.1.56.0
7fcaf3f88000-7fcaf4187000 ---p 00003000 08:03 49181862                   /usr/lib/libboost_system.so.1.56.0
7fcaf4187000-7fcaf4188000 r--p 00002000 08:03 49181862                   /usr/lib/libboost_system.so.1.56.0
7fcaf4188000-7fcaf4189000 rw-p 00003000 08:03 49181862                   /usr/lib/libboost_system.so.1.56.0
7fcaf4189000-7fcaf4191000 r-xp 00000000 08:03 55586445                   /opt/ros/indigo/lib/libcpp_common.so
7fcaf4191000-7fcaf4390000 ---p 00008000 08:03 55586445                   /opt/ros/indigo/lib/libcpp_common.so
7fcaf4390000-7fcaf4391000 r--p 00007000 08:03 55586445                   /opt/ros/indigo/lib/libcpp_common.so
7fcaf4391000-7fcaf4392000 rw-p 00008000 08:03 55586445                   /opt/ros/indigo/lib/libcpp_common.so
7fcaf4392000-7fcaf43b0000 r-xp 00000000 08:03 55586494                   /opt/ros/indigo/lib/libxmlrpcpp.so
7fcaf43b0000-7fcaf45af000 ---p 0001e000 08:03 55586494                   /opt/ros/indigo/lib/libxmlrpcpp.so
7fcaf45af000-7fcaf45b0000 r--p 0001d000 08:03 55586494                   /opt/ros/indigo/lib/libxmlrpcpp.so
7fcaf45b0000-7fcaf45b1000 rw-p 0001e000 08:03 55586494                   /opt/ros/indigo/lib/libxmlrpcpp.so
7fcaf45b1000-7fcaf45c1000 r-xp 00000000 08:03 49181868                   /usr/lib/libboost_date_time.so.1.56.0
7fcaf45c1000-7fcaf47c1000 ---p 00010000 08:03 49181868                   /usr/lib/libboost_date_time.so.1.56.0
7fcaf47c1000-7fcaf47c2000 r--p 00010000 08:03 49181868                   /usr/lib/libboost_date_time.so.1.56.0
7fcaf47c2000-7fcaf47c3000 rw-p 00011000 08:03 49181868                   /usr/lib/libboost_date_time.so.1.56.0
7fcaf47c3000-7fcaf47ec000 r-xp 00000000 08:03 55586447                   /opt/ros/indigo/lib/librostime.so
7fcaf47ec000-7fcaf49ec000 ---p 00029000 08:03 55586447                   /opt/ros/indigo/lib/librostime.so
7fcaf49ec000-7fcaf49ee000 r--p 00029000 08:03 55586447                   /opt/ros/indigo/lib/librostime.so
7fcaf49ee000-7fcaf49ef000 rw-p 0002b000 08:03 55586447                   /opt/ros/indigo/lib/librostime.so
7fcaf49ef000-7fcaf49f1000 r-xp 00000000 08:03 55586450                   /opt/ros/indigo/lib/libroscpp_serialization.so
7fcaf49f1000-7fcaf4bf0000 ---p 00002000 08:03 55586450                   /opt/ros/indigo/lib/libroscpp_serialization.so
7fcaf4bf0000-7fcaf4bf1000 r--p 00001000 08:03 55586450                   /opt/ros/indigo/lib/libroscpp_serialization.so
7fcaf4bf1000-7fcaf4bf2000 rw-p 00002000 08:03 55586450                   /opt/ros/indigo/lib/libroscpp_serialization.so
7fcaf4bf2000-7fcaf4cfe000 r-xp 00000000 08:03 49181877                   /usr/lib/libboost_regex.so.1.56.0
7fcaf4cfe000-7fcaf4efd000 ---p 0010c000 08:03 49181877                   /usr/lib/libboost_regex.so.1.56.0
7fcaf4efd000-7fcaf4f02000 r--p 0010b000 08:03 49181877                   /usr/lib/libboost_regex.so.1.56.0
7fcaf4f02000-7fcaf4f04000 rw-p 00110000 08:03 49181877                   /usr/lib/libboost_regex.so.1.56.0
7fcaf4f04000-7fcaf4f05000 rw-p 00000000 00:00 0 
7fcaf4f05000-7fcaf50bb000 r-xp 00000000 08:03 49189416                   /usr/lib/liblog4cxx.so.10.0.0
7fcaf50bb000-7fcaf52bb000 ---p 001b6000 08:03 49189416                   /usr/lib/liblog4cxx.so.10.0.0
7fcaf52bb000-7fcaf52e7000 r--p 001b6000 08:03 49189416                   /usr/lib/liblog4cxx.so.10.0.0
7fcaf52e7000-7fcaf52ea000 rw-p 001e2000 08:03 49189416                   /usr/lib/liblog4cxx.so.10.0.0
7fcaf52ea000-7fcaf52ec000 rw-p 00000000 00:00 0 
7fcaf52ec000-7fcaf52ed000 r-xp 00000000 08:03 55586475                   /opt/ros/indigo/lib/librosconsole_backend_interface.so
7fcaf52ed000-7fcaf54ec000 ---p 00001000 08:03 55586475                   /opt/ros/indigo/lib/librosconsole_backend_interface.so
7fcaf54ec000-7fcaf54ed000 r--p 00000000 08:03 55586475                   /opt/ros/indigo/lib/librosconsole_backend_interface.so
7fcaf54ed000-7fcaf54ee000 rw-p 00001000 08:03 55586475                   /opt/ros/indigo/lib/librosconsole_backend_interface.so
7fcaf54ee000-7fcaf5502000 r-xp 00000000 08:03 55586474                   /opt/ros/indigo/lib/librosconsole_log4cxx.so
7fcaf5502000-7fcaf5701000 ---p 00014000 08:03 55586474                   /opt/ros/indigo/lib/librosconsole_log4cxx.so
7fcaf5701000-7fcaf5703000 r--p 00013000 08:03 55586474                   /opt/ros/indigo/lib/librosconsole_log4cxx.so
7fcaf5703000-7fcaf5704000 rw-p 00015000 08:03 55586474                   /opt/ros/indigo/lib/librosconsole_log4cxx.so
7fcaf5704000-7fcaf572e000 r-xp 00000000 08:03 55586473                   /opt/ros/indigo/lib/librosconsole.so
7fcaf572e000-7fcaf592e000 ---p 0002a000 08:03 55586473                   /opt/ros/indigo/lib/librosconsole.so
7fcaf592e000-7fcaf5930000 r--p 0002a000 08:03 55586473                   /opt/ros/indigo/lib/librosconsole.so
7fcaf5930000-7fcaf5931000 rw-p 0002c000 08:03 55586473                   /opt/ros/indigo/lib/librosconsole.so
7fcaf5931000-7fcaf5948000 r-xp 00000000 08:03 49181871                   /usr/lib/libboost_filesystem.so.1.56.0
7fcaf5948000-7fcaf5b48000 ---p 00017000 08:03 49181871                   /usr/lib/libboost_filesystem.so.1.56.0
7fcaf5b48000-7fcaf5b49000 r--p 00017000 08:03 49181871                   /usr/lib/libboost_filesystem.so.1.56.0
7fcaf5b49000-7fcaf5b4a000 rw-p 00018000 08:03 49181871                   /usr/lib/libboost_filesystem.so.1.56.0
7fcaf5b4a000-7fcaf5b61000 r-xp 00000000 08:03 49191923                   /usr/lib/libboost_signals.so.1.56.0
7fcaf5b61000-7fcaf5d60000 ---p 00017000 08:03 49191923                   /usr/lib/libboost_signals.so.1.56.0
7fcaf5d60000-7fcaf5d61000 r--p 00016000 08:03 49191923                   /usr/lib/libboost_signals.so.1.56.0
7fcaf5d61000-7fcaf5d62000 rw-p 00017000 08:03 49191923                   /usr/lib/libboost_signals.so.1.56.0
7fcaf5d62000-7fcaf5d79000 r-xp 00000000 08:03 49155139                   /usr/lib/libpthread-2.20.so
7fcaf5d79000-7fcaf5f78000 ---p 00017000 08:03 49155139                   /usr/lib/libpthread-2.20.so
7fcaf5f78000-7fcaf5f79000 r--p 00016000 08:03 49155139                   /usr/lib/libpthread-2.20.so
7fcaf5f79000-7fcaf5f7a000 rw-p 00017000 08:03 49155139                   /usr/lib/libpthread-2.20.so
7fcaf5f7a000-7fcaf5f7e000 rw-p 00000000 00:00 0 
7fcaf5f7e000-7fcaf60e6000 r-xp 00000000 08:03 55586251                   /opt/ros/indigo/lib/libroscpp.so
7fcaf60e6000-7fcaf62e6000 ---p 00168000 08:03 55586251                   /opt/ros/indigo/lib/libroscpp.so
7fcaf62e6000-7fcaf62ed000 r--p 00168000 08:03 55586251                   /opt/ros/indigo/lib/libroscpp.so
7fcaf62ed000-7fcaf62f1000 rw-p 0016f000 08:03 55586251                   /opt/ros/indigo/lib/libroscpp.so
7fcaf62f1000-7fcaf62f5000 r-xp 00000000 08:03 55586608                   /opt/ros/indigo/lib/libtopic_tools.so
7fcaf62f5000-7fcaf64f4000 ---p 00004000 08:03 55586608                   /opt/ros/indigo/lib/libtopic_tools.so
7fcaf64f4000-7fcaf64f5000 r--p 00003000 08:03 55586608                   /opt/ros/indigo/lib/libtopic_tools.so
7fcaf64f5000-7fcaf64f6000 rw-p 00004000 08:03 55586608                   /opt/ros/indigo/lib/libtopic_tools.so
7fcaf64f6000-7fcaf64ff000 r-xp 00000000 08:03 49189742                   /usr/lib/liblz4.so.1.3.1
7fcaf64ff000-7fcaf66fe000 ---p 00009000 08:03 49189742                   /usr/lib/liblz4.so.1.3.1
7fcaf66fe000-7fcaf66ff000 r--p 00008000 08:03 49189742                   /usr/lib/liblz4.so.1.3.1
7fcaf66ff000-7fcaf6700000 rw-p 00009000 08:03 49189742                   /usr/lib/liblz4.so.1.3.1
7fcaf6700000-7fcaf6704000 r-xp 00000000 08:03 55586603                   /opt/ros/indigo/lib/libroslz4.so
7fcaf6704000-7fcaf6903000 ---p 00004000 08:03 55586603                   /opt/ros/indigo/lib/libroslz4.so
7fcaf6903000-7fcaf6904000 r--p 00003000 08:03 55586603                   /opt/ros/indigo/lib/libroslz4.so
7fcaf6904000-7fcaf6905000 rw-p 00004000 08:03 55586603                   /opt/ros/indigo/lib/libroslz4.so
7fcaf6905000-7fcaf6979000 r-xp 00000000 08:03 49184915                   /usr/lib/libboost_program_options.so.1.56.0
7fcaf6979000-7fcaf6b78000 ---p 00074000 08:03 49184915                   /usr/lib/libboost_program_options.so.1.56.0
7fcaf6b78000-7fcaf6b7c000 r--p 00073000 08:03 49184915                   /usr/lib/libboost_program_options.so.1.56.0
7fcaf6b7c000-7fcaf6b7d000 rw-p 00077000 08:03 49184915                   /usr/lib/libboost_program_options.so.1.56.0
7fcaf6b7d000-7fcaf6bc6000 r-xp 00000000 08:03 55586606                   /opt/ros/indigo/lib/librosbag_storage.so
7fcaf6bc6000-7fcaf6dc5000 ---p 00049000 08:03 55586606                   /opt/ros/indigo/lib/librosbag_storage.so
7fcaf6dc5000-7fcaf6dc7000 r--p 00048000 08:03 55586606                   /opt/ros/indigo/lib/librosbag_storage.so
7fcaf6dc7000-7fcaf6dc8000 rw-p 0004a000 08:03 55586606                   /opt/ros/indigo/lib/librosbag_storage.so
7fcaf6dc8000-7fcaf6e43000 r-xp 00000000 08:03 55586611                   /opt/ros/indigo/lib/librosbag.so
7fcaf6e43000-7fcaf7042000 ---p 0007b000 08:03 55586611                   /opt/ros/indigo/lib/librosbag.so
7fcaf7042000-7fcaf7047000 r--p 0007a000 08:03 55586611                   /opt/ros/indigo/lib/librosbag.so
7fcaf7047000-7fcaf7049000 rw-p 0007f000 08:03 55586611                   /opt/ros/indigo/lib/librosbag.so
7fcaf7049000-7fcaf704e000 r-xp 00000000 08:03 55586623                   /opt/ros/indigo/lib/libdynamic_reconfigure_config_init_mutex.so
7fcaf704e000-7fcaf724d000 ---p 00005000 08:03 55586623                   /opt/ros/indigo/lib/libdynamic_reconfigure_config_init_mutex.so
7fcaf724d000-7fcaf724e000 r--p 00004000 08:03 55586623                   /opt/ros/indigo/lib/libdynamic_reconfigure_config_init_mutex.so
7fcaf724e000-7fcaf724f000 rw-p 00005000 08:03 55586623                   /opt/ros/indigo/lib/libdynamic_reconfigure_config_init_mutex.so
7fcaf724f000-7fcaf72f1000 r-xp 00000000 08:03 49189387                   /usr/lib/libopencv_calib3d.so.2.4.9
7fcaf72f1000-7fcaf74f0000 ---p 000a2000 08:03 49189387                   /usr/lib/libopencv_calib3d.so.2.4.9
7fcaf74f0000-7fcaf74f1000 r--p 000a1000 08:03 49189387                   /usr/lib/libopencv_calib3d.so.2.4.9
7fcaf74f1000-7fcaf74f2000 rw-p 000a2000 08:03 49189387                   /usr/lib/libopencv_calib3d.so.2.4.9
7fcaf74f2000-7fcaf75de000 r-xp 00000000 08:03 49189396                   /usr/lib/libopencv_contrib.so.2.4.9
7fcaf75de000-7fcaf77dd000 ---p 000ec000 08:03 49189396                   /usr/lib/libopencv_contrib.so.2.4.9
7fcaf77dd000-7fcaf77df000 r--p 000eb000 08:03 49189396                   /usr/lib/libopencv_contrib.so.2.4.9
7fcaf77df000-7fcaf77e1000 rw-p 000ed000 08:03 49189396                   /usr/lib/libopencv_contrib.so.2.4.9
7fcaf77e1000-7fcaf7aa5000 r-xp 00000000 08:03 49189382                   /usr/lib/libopencv_core.so.2.4.9
7fcaf7aa5000-7fcaf7ca5000 ---p 002c4000 08:03 49189382                   /usr/lib/libopencv_core.so.2.4.9
7fcaf7ca5000-7fcaf7ca9000 r--p 002c4000 08:03 49189382                   /usr/lib/libopencv_core.so.2.4.9
7fcaf7ca9000-7fcaf7cb2000 rw-p 002c8000 08:03 49189382                   /usr/lib/libopencv_core.so.2.4.9
7fcaf7cb2000-7fcaf7cb4000 rw-p 00000000 00:00 0 
7fcaf7cb4000-7fcaf7d5e000 r-xp 00000000 08:03 49189386                   /usr/lib/libopencv_features2d.so.2.4.9
7fcaf7d5e000-7fcaf7f5d000 ---p 000aa000 08:03 49189386                   /usr/lib/libopencv_features2d.so.2.4.9
7fcaf7f5d000-7fcaf7f61000 r--p 000a9000 08:03 49189386                   /usr/lib/libopencv_features2d.so.2.4.9
7fcaf7f61000-7fcaf7f63000 rw-p 000ad000 08:03 49189386                   /usr/lib/libopencv_features2d.so.2.4.9
7fcaf7f63000-7fcaf7f64000 rw-p 00000000 00:00 0 
7fcaf7f64000-7fcaf7fda000 r-xp 00000000 08:03 49189383                   /usr/lib/libopencv_flann.so.2.4.9
7fcaf7fda000-7fcaf81da000 ---p 00076000 08:03 49189383                   /usr/lib/libopencv_flann.so.2.4.9
7fcaf81da000-7fcaf81dd000 r--p 00076000 08:03 49189383                   /usr/lib/libopencv_flann.so.2.4.9
7fcaf81dd000-7fcaf81de000 rw-p 00079000 08:03 49189383                   /usr/lib/libopencv_flann.so.2.4.9
7fcaf81de000-7fcaf8232000 r-xp 00000000 08:03 49189393                   /usr/lib/libopencv_gpu.so.2.4.9
7fcaf8232000-7fcaf8431000 ---p 00054000 08:03 49189393                   /usr/lib/libopencv_gpu.so.2.4.9
7fcaf8431000-7fcaf8432000 r--p 00053000 08:03 49189393                   /usr/lib/libopencv_gpu.so.2.4.9
7fcaf8432000-7fcaf8433000 rw-p 00054000 08:03 49189393                   /usr/lib/libopencv_gpu.so.2.4.9
7fcaf8433000-7fcaf8488000 r-xp 00000000 08:03 49189385                   /usr/lib/libopencv_highgui.so.2.4.9
7fcaf8488000-7fcaf8688000 ---p 00055000 08:03 49189385                   /usr/lib/libopencv_highgui.so.2.4.9
7fcaf8688000-7fcaf868a000 r--p 00055000 08:03 49189385                   /usr/lib/libopencv_highgui.so.2.4.9
7fcaf868a000-7fcaf868c000 rw-p 00057000 08:03 49189385                   /usr/lib/libopencv_highgui.so.2.4.9
7fcaf868c000-7fcaf8907000 r-xp 00000000 08:03 49189384                   /usr/lib/libopencv_imgproc.so.2.4.9
7fcaf8907000-7fcaf8b07000 ---p 0027b000 08:03 49189384                   /usr/lib/libopencv_imgproc.so.2.4.9
7fcaf8b07000-7fcaf8b0e000 r--p 0027b000 08:03 49189384                   /usr/lib/libopencv_imgproc.so.2.4.9
7fcaf8b0e000-7fcaf8b10000 rw-p 00282000 08:03 49189384                   /usr/lib/libopencv_imgproc.so.2.4.9
7fcaf8b10000-7fcaf8ba5000 rw-p 00000000 00:00 0 
7fcaf8ba5000-7fcaf8cce000 r-xp 00000000 08:03 49189390                   /usr/lib/libopencv_legacy.so.2.4.9
7fcaf8cce000-7fcaf8ece000 ---p 00129000 08:03 49189390                   /usr/lib/libopencv_legacy.so.2.4.9
7fcaf8ece000-7fcaf8ed1000 r--p 00129000 08:03 49189390                   /usr/lib/libopencv_legacy.so.2.4.9
7fcaf8ed1000-7fcaf8ed3000 rw-p 0012c000 08:03 49189390                   /usr/lib/libopencv_legacy.so.2.4.9
7fcaf8ed3000-7fcaf8ed5000 rw-p 00000000 00:00 0 
7fcaf8ed5000-7fcaf8f64000 r-xp 00000000 08:03 49189388                   /usr/lib/libopencv_ml.so.2.4.9
7fcaf8f64000-7fcaf9164000 ---p 0008f000 08:03 49189388                   /usr/lib/libopencv_ml.so.2.4.9
7fcaf9164000-7fcaf9166000 r--p 0008f000 08:03 49189388                   /usr/lib/libopencv_ml.so.2.4.9
7fcaf9166000-7fcaf9168000 rw-p 00091000 08:03 49189388                   /usr/lib/libopencv_ml.so.2.4.9
7fcaf9168000-7fcaf91a5000 r-xp 00000000 08:03 49189395                   /usr/lib/libopencv_nonfree.so.2.4.9
7fcaf91a5000-7fcaf93a4000 ---p 0003d000 08:03 49189395                   /usr/lib/libopencv_nonfree.so.2.4.9
7fcaf93a4000-7fcaf93a6000 r--p 0003c000 08:03 49189395                   /usr/lib/libopencv_nonfree.so.2.4.9
7fcaf93a6000-7fcaf93a7000 rw-p 0003e000 08:03 49189395                   /usr/lib/libopencv_nonfree.so.2.4.9
7fcaf93a7000-7fcaf942c000 r-xp 00000000 08:03 49189391                   /usr/lib/libopencv_objdetect.so.2.4.9
7fcaf942c000-7fcaf962b000 ---p 00085000 08:03 49189391                   /usr/lib/libopencv_objdetect.so.2.4.9
7fcaf962b000-7fcaf962c000 r--p 00084000 08:03 49189391                   /usr/lib/libopencv_objdetect.so.2.4.9
7fcaf962c000-7fcaf962d000 rw-p 00085000 08:03 49189391                   /usr/lib/libopencv_objdetect.so.2.4.9
7fcaf962d000-7fcaf962e000 rw-p 00000000 00:00 0 
7fcaf962e000-7fcaf9815000 r-xp 00000000 08:03 49189394                   /usr/lib/libopencv_ocl.so.2.4.9
7fcaf9815000-7fcaf9a14000 ---p 001e7000 08:03 49189394                   /usr/lib/libopencv_ocl.so.2.4.9
7fcaf9a14000-7fcaf9a17000 r--p 001e6000 08:03 49189394                   /usr/lib/libopencv_ocl.so.2.4.9
7fcaf9a17000-7fcaf9a19000 rw-p 001e9000 08:03 49189394                   /usr/lib/libopencv_ocl.so.2.4.9
7fcaf9a19000-7fcaf9a1a000 rw-p 00000000 00:00 0 
7fcaf9a1a000-7fcaf9a3b000 r-xp 00000000 08:03 49189392                   /usr/lib/libopencv_photo.so.2.4.9
7fcaf9a3b000-7fcaf9c3a000 ---p 00021000 08:03 49189392                   /usr/lib/libopencv_photo.so.2.4.9
7fcaf9c3a000-7fcaf9c3b000 r--p 00020000 08:03 49189392                   /usr/lib/libopencv_photo.so.2.4.9
7fcaf9c3b000-7fcaf9c3c000 rw-p 00021000 08:03 49189392                   /usr/lib/libopencv_photo.so.2.4.9
7fcaf9c3c000-7fcaf9cc4000 r-xp 00000000 08:03 49189397                   /usr/lib/libopencv_stitching.so.2.4.9
7fcaf9cc4000-7fcaf9ec4000 ---p 00088000 08:03 49189397                   /usr/lib/libopencv_stitching.so.2.4.9
7fcaf9ec4000-7fcaf9ec6000 r--p 00088000 08:03 49189397                   /usr/lib/libopencv_stitching.so.2.4.9
7fcaf9ec6000-7fcaf9ec7000 rw-p 0008a000 08:03 49189397                   /usr/lib/libopencv_stitching.so.2.4.9
7fcaf9ec7000-7fcaf9f0a000 r-xp 00000000 08:03 49189398                   /usr/lib/libopencv_superres.so.2.4.9
7fcaf9f0a000-7fcafa109000 ---p 00043000 08:03 49189398                   /usr/lib/libopencv_superres.so.2.4.9
7fcafa109000-7fcafa10b000 r--p 00042000 08:03 49189398                   /usr/lib/libopencv_superres.so.2.4.9
7fcafa10b000-7fcafa10c000 rw-p 00044000 08:03 49189398                   /usr/lib/libopencv_superres.so.2.4.9
7fcafa10c000-7fcafa168000 r-xp 00000000 08:03 49189389                   /usr/lib/libopencv_video.so.2.4.9
7fcafa168000-7fcafa367000 ---p 0005c000 08:03 49189389                   /usr/lib/libopencv_video.so.2.4.9
7fcafa367000-7fcafa368000 r--p 0005b000 08:03 49189389                   /usr/lib/libopencv_video.so.2.4.9
7fcafa368000-7fcafa369000 rw-p 0005c000 08:03 49189389                   /usr/lib/libopencv_video.so.2.4.9
7fcafa369000-7fcafa3a6000 r-xp 00000000 08:03 49189400                   /usr/lib/libopencv_videostab.so.2.4.9
7fcafa3a6000-7fcafa5a5000 ---p 0003d000 08:03 49189400                   /usr/lib/libopencv_videostab.so.2.4.9
7fcafa5a5000-7fcafa5a7000 r--p 0003c000 08:03 49189400                   /usr/lib/libopencv_videostab.so.2.4.9
7fcafa5a7000-7fcafa5a8000 rw-p 0003e000 08:03 49189400                   /usr/lib/libopencv_videostab.so.2.4.9
7fcafa5a8000-7fcafa5b6000 r-xp 00000000 08:03 55586478                   /opt/ros/indigo/lib/libcv_bridge.so
7fcafa5b6000-7fcafa7b5000 ---p 0000e000 08:03 55586478                   /opt/ros/indigo/lib/libcv_bridge.so
7fcafa7b5000-7fcafa7b6000 r--p 0000d000 08:03 55586478                   /opt/ros/indigo/lib/libcv_bridge.so
7fcafa7b6000-7fcafa7b7000 rw-p 0000e000 08:03 55586478                   /opt/ros/indigo/lib/libcv_bridge.so
7fcafa7b7000-7fcafa859000 r-xp 00000000 08:03 49189989                   /usr/lib/libQGLViewer.so.2.5.3
7fcafa859000-7fcafaa58000 ---p 000a2000 08:03 49189989                   /usr/lib/libQGLViewer.so.2.5.3
7fcafaa58000-7fcafaa5b000 r--p 000a1000 08:03 49189989                   /usr/lib/libQGLViewer.so.2.5.3
7fcafaa5b000-7fcafaa5e000 rw-p 000a4000 08:03 49189989                   /usr/lib/libQGLViewer.so.2.5.3
7fcafaa5e000-7fcafaa5f000 rw-p 00000000 00:00 0 
7fcafaa5f000-7fcafaa6e000 r-xp 00000000 08:03 49155136                   /usr/lib/ld-2.20.so
7fcafaa6e000-7fcafaa6f000 r-xp 0000f000 08:03 49155136                   /usr/lib/ld-2.20.so
7fcafaa6f000-7fcafaa81000 r-xp 00010000 08:03 49155136                   /usr/lib/ld-2.20.so
7fcafabac000-7fcafabcf000 rw-p 00000000 00:00 0 
7fcafabcf000-7fcafabdd000 r-xp 00000000 08:03 49184203                   /usr/lib/libudev.so.1.6.0
7fcafabdd000-7fcafabde000 ---p 0000e000 08:03 49184203                   /usr/lib/libudev.so.1.6.0
7fcafabde000-7fcafabdf000 r--p 0000e000 08:03 49184203                   /usr/lib/libudev.so.1.6.0
7fcafabdf000-7fcafabe0000 rw-p 0000f000 08:03 49184203                   /usr/lib/libudev.so.1.6.0
7fcafabe0000-7fcafabf8000 rw-p 00000000 00:00 0 
7fcafabf8000-7fcafac1a000 r-xp 00000000 08:03 49184201                   /usr/lib/libsystemd.so.0.4.0
7fcafac1a000-7fcafac1b000 r--p 00021000 08:03 49184201                   /usr/lib/libsystemd.so.0.4.0
7fcafac1b000-7fcafac1c000 rw-p 00022000 08:03 49184201                   /usr/lib/libsystemd.so.0.4.0
7fcafac1c000-7fcafac44000 rw-p 00000000 00:00 0 
7fcafac6f000-7fcafac7b000 rw-p 00000000 00:00 0 
7fcafac7b000-7fcafac7c000 rw-p 00000000 00:00 0 
7fcafac7c000-7fcafac7d000 r--p 00000000 00:00 0 
7fcafac7d000-7fcafac7e000 rw-p 00000000 00:00 0 
7fcafac7e000-7fcafac7f000 r--p 00000000 00:00 0 
7fcafac7f000-7fcafac80000 rw-p 00000000 00:00 0 
7fcafac80000-7fcafac81000 r--p 00021000 08:03 49155136                   /usr/lib/ld-2.20.so
7fcafac81000-7fcafac82000 rw-p 00022000 08:03 49155136                   /usr/lib/ld-2.20.so
7fcafac82000-7fcafac83000 rw-p 00000000 00:00 0 
7fffbf958000-7fffbf979000 rw-p 00000000 00:00 0                          [stack]
7fffbf9fc000-7fffbf9fe000 r--p 00000000 00:00 0                          [vvar]
7fffbf9fe000-7fffbfa00000 r-xp 00000000 00:00 0                          [vdso]
ffffffffff600000-ffffffffff601000 r-xp 00000000 00:00 0                  [vsyscall]
Aborted (core dumped)

Issues Initializing/ Mapping point cloud,

Greetings,

I'm attempting to get LSD-SLAM running so that I may intergrate it into my research,

I'm using Ubuntu 14.04 with the ros system Indigo,
And I'm pipelining my monochrome image into lsd_slam_core, however, I'm greeted with

damien-r@waffleiron:~/ros_packages/lsd_slam$ rosrun lsd_slam_core live_slam image:=/image_mono _calib:=pinhole_example_calib.cfg
Reading Calibration from file pinhole_example_calib.cfg ... not found!
Trying /home/damien-r/ros_packages/lsd_slam/lsd_slam_core/calib/pinhole_example_calib.cfg ... found!
found ATAN camera model, building rectifier.
Input resolution: 640 480
In: 0.527334 0.827306 0.473568 0.499436 0.000000
NO RECTIFICATION
Output resolution: 640 480
Prepped Warp matrices
Started constraint search thread!
Started mapping thread!
Started optimization thread
Doing Random initialization!
init done
opengl support available
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
QMetaMethod::invoke: Unable to invoke methods with return values in queued connections
Done Random initialization!
TRACKING LOST for frame 367 (0.01% good Points, which is 100.00% of available points, DIVERGED)!

Only sometimes does the image initialize properly (about 0.2 percent of the time) usually the output window freezes.

I'm unsure the reason why, and would like some help,

Thanks for the patience ^_^

Tracking Lost problems

Hi everybody,

I'm using Kinect RGB Mono as live camera in LSD-SLAM and I have found this error:

$ rosrun lsd_slam_viewer viewer
$ rosrun lsd_slam_core live_slam /image:=/camera/rgb/image_mono _calib:=calib_kinect.cfg

TRACKING LOST for frame 218 (10,69% good Points, which is 48,68% of available points, NOT DIVERGED)!

My calibration file:
520.323830 521.287893 323.751970 275.976601 0.171381 -0.309677 0.004476 0.004649
640 480
full
640 480

How can I solve this problem?

Thanks.

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.