Coder Social home page Coder Social logo

gazebosim / gz-sim Goto Github PK

View Code? Open in Web Editor NEW
582.0 18.0 246.0 122.71 MB

Open source robotics simulator. The latest version of Gazebo.

Home Page: https://gazebosim.org

License: Apache License 2.0

CMake 1.00% Shell 0.10% C++ 91.99% QML 5.68% Ruby 0.42% Python 0.44% HTML 0.21% C 0.16%
ignition-gazebo ignition-robotics graphical-interface ignition-libraries robotics simulation robotics-simulation cpp gazebo physics

gz-sim's Introduction

Gazebo Sim : A Robotic Simulator

Maintainer: michael AT openrobotics DOT org

GitHub open issues GitHub open pull requests Discourse topics Hex.pm

Build Status
Test coverage codecov
Ubuntu Jammy Build Status
Homebrew Build Status
Windows Build Status

Gazebo Sim is an open source robotics simulator. Through Gazebo Sim, users have access to high fidelity physics, rendering, and sensor models. Additionally, users and developers have multiple points of entry to simulation including a graphical user interface, plugins, and asynchronous message passing and services.

Gazebo Sim is derived from Gazebo Classic and represents over 16 years of development and experience in robotics and simulation. This library is part of the Gazebo project.

Table of Contents

Features

Install

Usage

Documentation

Testing

Folder Structure

Code of Conduct

Contributing

Versioning

License

Features

  • Dynamics simulation: Access multiple high-performance physics engines through Gazebo Physics.

  • Advanced 3D graphics: Through Gazebo Rendering, it's possible to use rendering engines such as OGRE v2 for realistic rendering of environments with high-quality lighting, shadows, and textures.

  • Sensors and noise models: Generate sensor data, optionally with noise, from laser range finders, 2D/3D cameras, Kinect style sensors, contact sensors, force-torque, IMU, GPS, and more, all powered by Gazebo Sensors

  • Plugins: Develop custom plugins for robot, sensor, and environment control.

  • Graphical interface: Create, introspect and interact with your simulations through plugin-based graphical interfaces powered by Gazebo GUI.

  • Simulation models: Access numerous robots including PR2, Pioneer2 DX, iRobot Create, and TurtleBot, and construct environments using other physically accurate models available through Gazebo Fuel. You can also build a new model using SDF.

  • TCP/IP Transport: Run simulation on remote servers and interface to Gazebo Sim through socket-based message passing using Gazebo Transport.

  • Command line tools: Extensive command line tools for increased simulation introspection and control.

Install

See the installation tutorial.

Usage

Gazebo Sim can be run from the command line, once installed, using:

gz sim

For help, and command line options use:

gz sim -h

Known issue of command line tools

In the event that the installation is a mix of Debian and from source, command line tools from gz-tools may not work correctly.

A workaround for a single package is to define the environment variable GZ_CONFIG_PATH to point to the location of the Gazebo library installation, where the YAML file for the package is found, such as

export GZ_CONFIG_PATH=/usr/local/share/gz

However, that environment variable only takes a single path, which means if the installations from source are in different locations, only one can be specified.

Another workaround for working with multiple Gazebo libraries on the command line is using symbolic links to each library's YAML file.

mkdir ~/.gz/tools/configs -p
cd ~/.gz/tools/configs/
ln -s /usr/local/share/gz/fuel8.yaml .
ln -s /usr/local/share/gz/transport13.yaml .
ln -s /usr/local/share/gz/transportlog13.yaml .
...
export GZ_CONFIG_PATH=$HOME/.gz/tools/configs

This issue is tracked here.

Documentation

See the installation tutorial.

Testing

See the installation tutorial.

See the Writing Tests section of the contributor guide for help creating or modifying tests.

Folder Structure

Refer to the following table for information about important directories and files in this repository.

gz-sim
├── examples                     Various examples that can be run against binary or source installs of gz-sim.
│   ├── plugin                   Example plugins.
│   ├── standalone               Example standalone programs that use gz-sim as a library.
│   └── worlds                   Example SDF world files.
├── include/gz/sim               Header files that downstream users are expected to use.
│   └── detail                   Header files that are not intended for downstream use, mainly template implementations.
├── python                       Python wrappers
├── src                          Source files and unit tests.
│   ├── gui                      Graphical interface source code.
│   └── systems                  System source code.
├── test
│   ├── integration              Integration tests.
│   ├── performance              Performance tests.
│   ├── plugins                  Plugins used in tests.
│   ├── regression               Regression tests.
│   └── tutorials                Tutorials, written in markdown.
├── Changelog.md                 Changelog.
├── CMakeLists.txt               CMake build script.
├── Migration.md                 Migration guide.
└── README.md                    This readme.

Contributing

Please see CONTRIBUTING.md.

Code of Conduct

Please see CODE_OF_CONDUCT.md.

Versioning

This library uses Semantic Versioning. Additionally, this library is part of the Gazebo project which periodically releases a versioned set of compatible and complimentary libraries. See the Gazebo website for version and release information.

License

This library is licensed under Apache 2.0. See also the LICENSE file.

gz-sim's People

Contributors

adityapande-1995 avatar adlarkin avatar ahcorde avatar andrejorsula avatar arjo129 avatar atharva-18 avatar azeey avatar azulradio avatar blast545 avatar bperseghetti avatar caguero avatar chapulina avatar diegoferigo avatar henrique-bo avatar iche033 avatar j-rivero avatar jennuine avatar luca-della-vedova avatar mabelzhang avatar maryab-osr avatar mcres avatar methyldragon avatar mingfeisun avatar mjcarroll avatar nkoenig avatar peci1 avatar scpeters avatar shokman avatar traversaro avatar voldivh 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

gz-sim's Issues

Add ogre2 support in CI

Original report (archived issue) by Ian Chen (Bitbucket: Ian Chen, GitHub: iche033).


Summary

Add ogre 2.1 dependency to CI systems

Motivation

Some rendering tests are using ogre and we should start switching them to use ogre2. To do this, we need to first add ogre2.1 dependency to our CI systems otherwise the tests will fail with a warning msg about not being able to find the ogre2 render engine.

Don't fail silently when trying to load a world without -f

Original report (archived issue) by Michael Grey (Bitbucket: mxgrey, GitHub: mxgrey).


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

Using all the latest ignition branches, nothing seems to render when I try to run a world in ign-gazebo. I haven't tried to run a full ign-gazebo pipeline in a while, so it's hard to say how long this has been going on, but it was working fine as recently as mid-January.

Steps to Reproduce

For me this happens when trying to run any world using ign-gazebo. E.g. from the ign-gazebo root directory:

$ ign-gazebo -v 4 test/worlds/mesh.sdf

I get this:

Screenshot from 2019-02-07 12-53-51.png

And the following prints to the terminal:

[Msg] Ignition Gazebo        v0.1.0~pre1
[Msg] Ignition Gazebo GUI    v0.1.0~pre1
[Msg] Ignition Gazebo Server v0.1.0~pre1
[Dbg] [EntityComponentManager.cc:502] Register new component type 515269944612530032.
[Dbg] [EntityComponentManager.cc:502] Register new component type 17314316377527280772.
[Dbg] [EntityComponentManager.cc:502] Register new component type 17116448167660919050.
[Dbg] [EntityComponentManager.cc:502] Register new component type 5229559171816935132.
[Dbg] [EntityComponentManager.cc:502] Register new component type 4730666468951701659.
[Dbg] [EntityComponentManager.cc:502] Register new component type 13669903581159109821.
[Dbg] [Application.cc:87] Initializing application.
[GUI] [Dbg] [Application.cc:395] Create main window
[Msg] Serving scene information on [/world/default/scene/info]
[Msg] Serving graph information on [/world/default/scene/graph]
[Msg] Serving scene information on [/world/default/scene/info]
[Msg] Publishing entity deletions on [/world/default/scene/deletion]
[Msg] Publishing pose messages on [/world/default/pose/info]
[Msg] Serving GUI information on [/world/default/gui/info]
[Msg] World [default] initialized with [default_physics] physics profile.
[GUI] [Msg] Loading config [/home/grey/projects/gz11/install/ignition-gazebo/share/ignition/gazebo0/gui/gui.config]
[GUI] [Dbg] [Application.cc:267] Loading window config
[GUI] [Dbg] [Application.cc:409] Applying config
[GUI] [Dbg] [gui_main.cc:179] Requesting list of world names...
[GUI] [Dbg] [gui_main.cc:200] Requesting GUI from [/world/default/gui/info]...
[GUI] [Msg] Loading plugin [Scene3D]
[GUI] [Msg] Added plugin [3D View] to main window
[GUI] [Msg] Loading plugin [WorldControl]
[GUI] [Msg] Added plugin [World control] to main window
[GUI] [Msg] Loading plugin [WorldStats]
[GUI] [Msg] Added plugin [World stats] to main window
[GUI] [Msg] Loading plugin [ignition-rendering1-ogre]
[GUI] [Dbg] [Scene3D.cc:883] Create scene [scene]
Topic [] is not valid.
[GUI] [Err] [Scene3D.cc:416] Error subscribing to deletion topic: 
Topic [] is not valid.
[GUI] [Err] [Scene3D.cc:421] Error subscribing to scene topic: 

And then during teardown:

[GUI] [Dbg] [gui_main.cc:230] Shutting down ign-gazebo-gui
[GUI] [Dbg] [Application.cc:130] Terminating application.
[GUI] [Dbg] [Scene3D.cc:933] Destroy scene [scene]
[Dbg] [SignalHandler.cc:141] Received signal[2].
[Dbg] [SignalHandler.cc:141] Received signal[2].
[Dbg] [ServerPrivate.cc:55] Server received signal[2]
[Dbg] [server_main.cc:167] Shutting down ign-gazebo-server
[Dbg] [main.cc:276] Shutting down ign-gazebo

Versions

I'm using all the gz11 branches, or default for repos that don't have a gz11 branch (but the ign-plugin1 branch for ign-plugin).

Additional Information

I'm using Ubuntu 18.04 with an AMD graphics card. I've found AMD graphics cards to be a bit unreliable with OGRE, so maybe that's the culprit? But this issue only emerged recently.

Also worth noting, all of the tests pass on my machine for ign-gazebo, ign-gui, and ign-rendering.

Current performance of ignition robotic libraries

Original report (archived issue) by Diego Ferigo (Bitbucket: dgferigo).

The original report had attachments: cachegrind.png, callgrind_2.png, callgrind_5.png


Summary

The overhead introduced by ignition gazebo seems significant. The time spent to compute physics is a small fraction of the total time.

Description

First off, thanks for all the work you're doing! Despite their early development status, ignition libraries are amazing.

I am currently developing an application based on ignition robotics. Starting by saying that it is still at a very early stage of development, I tried to evaluate its performance in order to catch initial bottlenecks. The test I did is a simple cart pole simulation with ignition configured in such a way that it tries to go as fast as it can. Currently, there's only one thread, and I can see that the CPU goes to 100% when the application is executing.

Referring to the attached cachegrind image, I am surprised to see that only the ~11% of the time passed inside the ignition libraries (the entry point is Server::Run) is actually spent in the physics engine (currently, dart). This means that the remaining 89% is computation overhead.

Is this behavior normal to your eyes? I saw that you performed in the past some profiling, maybe you have some insights on it.

Note: this is a headless simulation, I do not use the ign-gazebo-gui process

Altimeter test is flaky on pipelines

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Prerequisites

  • [X ] Put an X between the brackets on this line if you have done all of the following:

Description

I've noticed the altimeter test fails on pipelines from time to time

Steps to Reproduce

  1. Run pipelines
  2. Check results (doesn't fail often)

Expected behavior:

Never fails

Actual behavior:

Fails sometimes

Reproduces how often:

Hard to estimate, 10% of the time?

Versions

Latest default branch

Additional Information

From pipelines:

33: Test command: /opt/atlassian/pipelines/agent/build/build/bin/INTEGRATION_altimeter_system "--gtest_output=xml:/opt/atlassian/pipelines/agent/build/build/test_results/INTEGRATION_altimeter_system.xml"
33: Test timeout computed to be: 240
33: Running main() from gtest_main.cc
33: [==========] Running 1 test from 1 test case.
33: [----------] Global test environment set-up.
33: [----------] 1 test from AltimeterTest
33: [ RUN      ] AltimeterTest.ModelFalling
33: [Dbg] [NetworkConfig.cc:58] IGN_GAZEBO_NETWORK_ROLE not set, distributed sim disabled
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 16089617886205856687.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 9299799230608006382.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 5348032369490841638.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 4877458260665438445.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 10827637380694563212.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 9205898875573865017.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 11132550027708908945.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 15691989502342742202.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 15151032318371607903.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 1798680698263801960.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 13860058984175278834.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 13354021245895791950.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 6486582422464405424.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 6288009175724330448.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 11055179093498036598.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 4774264443171537962.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 11846705962609178476.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 15524275727504131414.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 13640904926720274575.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 10167934449656658255.
33: [Dbg] [EntityComponentManager.cc:502] Register new component type 87071902518537034011;36
33/66 Test #33: INTEGRATION_altimeter_system .............***Exception: SegFault  9.52 sec

Follow model on the GUI

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Summary

It would be convenient to click on a model and have the user camera track it.

Motivation

Helps debugging models moving in large environments

Describe alternatives you've considered

  • Right-click model -> follow / ESC to leave
  • Follow service that can be called from command line
  • Setup follow from startup through SDF's track_visual tag

Additional context

Setting initial velocity

Original report (archived issue) by Til Hoff (Bitbucket: turakar).


I am trying to set the initial velocity of a model in the .sdf file. Therefore I defined a state according to the sdformat spec. This setting seems to be ignored by gazebo. Is there a different way of doing this? Or is there something wrong? The SDF file:

<?xml version="1.0" ?>

<sdf version="1.6">
  <world name="foobar">

    <physics name="1ms" type="ode">
      <max_step_size>0.001</max_step_size>
      <real_time_factor>1.0</real_time_factor>
    </physics>
    <plugin
            filename="libignition-gazebo-scene-broadcaster-system.so"
            name="ignition::gazebo::systems::SceneBroadcaster">
    </plugin>
    <plugin
      filename="libignition-gazebo-physics-system.so"
      name="ignition::gazebo::systems::Physics">
    </plugin>

    <gui fullscreen="0">

      <!-- 3D scene -->
      <plugin filename="GzScene3D" name="3D View">
        <ignition-gui>
          <title>3D View</title>
          <property type="bool" key="showTitleBar">false</property>
          <property type="string" key="state">docked</property>
        </ignition-gui>

        <engine>ogre2</engine>
        <scene>scene</scene>
        <ambient_light>0.4 0.4 0.4</ambient_light>
        <background_color>0.8 0.8 0.8</background_color>
        <camera_pose>-6 0 6 0 0.5 0</camera_pose>
      </plugin>

      <!-- World control -->
      <plugin filename="WorldControl" name="World control">
        <ignition-gui>
          <title>World control</title>
          <property type="bool" key="showTitleBar">false</property>
          <property type="bool" key="resizable">false</property>
          <property type="double" key="height">72</property>
          <property type="double" key="width">121</property>
          <property type="double" key="z">1</property>

          <property type="string" key="state">floating</property>
          <anchors target="3D View">
            <line own="left" target="left"/>
            <line own="bottom" target="bottom"/>
          </anchors>
        </ignition-gui>

        <play_pause>true</play_pause>
        <step>true</step>
        <start_paused>true</start_paused>
        <service>/world/foobar/control</service>
        <stats_topic>/world/foobar/stats</stats_topic>

      </plugin>

      <!-- World statistics -->
      <plugin filename="WorldStats" name="World stats">
        <ignition-gui>
          <title>World stats</title>
          <property type="bool" key="showTitleBar">false</property>
          <property type="bool" key="resizable">false</property>
          <property type="double" key="height">110</property>
          <property type="double" key="width">290</property>
          <property type="double" key="z">1</property>

          <property type="string" key="state">floating</property>
          <anchors target="3D View">
            <line own="right" target="right"/>
            <line own="bottom" target="bottom"/>
          </anchors>
        </ignition-gui>

        <sim_time>true</sim_time>
        <real_time>true</real_time>
        <real_time_factor>true</real_time_factor>
        <iterations>true</iterations>
        <topic>/world/foobar/stats</topic>
      </plugin>

    </gui>

    <light type="directional" name="sun">
      <cast_shadows>true</cast_shadows>
      <pose>0 0 10 0 0 0</pose>
      <diffuse>1 1 1 1</diffuse>
      <specular>0.5 0.5 0.5 1</specular>
      <attenuation>
        <range>1000</range>
        <constant>0.9</constant>
        <linear>0.01</linear>
        <quadratic>0.001</quadratic>
      </attenuation>
      <direction>-0.5 0.1 -0.9</direction>
    </light>

    <gravity>0 0 0</gravity>

    <model name="probe">
      <link name="link">
        <inertial>
          <mass>30</mass>
          <inertia>
            <ixx>12</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>12</iyy>
            <iyz>0</iyz>
            <izz>12</izz>
          </inertia>
        </inertial>
        <visual name="visual">
          <geometry>
            <sphere>
              <radius>1</radius>
            </sphere>
          </geometry>
          <material>
            <ambient>0.5 0.5 1.0 1</ambient>
            <diffuse>0.5 0.5 1.0 1</diffuse>
            <specular>0.0 0.0 1.0 1</specular>
          </material>
        </visual>
        <collision name="collision">
          <geometry>
            <sphere>
              <radius>1</radius>
            </sphere>
          </geometry>
        </collision>
      </link>
    </model>

    <state world_name="foobar">
      <model name="probe">
        <pose>0 0 0 0 -0 0</pose>
        <link name="link">
          <pose>0 0 0 0 0 0</pose>
          <velocity>10 0 0 0 0 0</velocity>
        </link>
      </model>
    </state>

  </world>
</sdf>

Pose components

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


This issue is meant to discuss the frame of reference, and more generally pose components, within the ECS.

Current implementation

Currently, ignition::gazebo::components::Pose holds an ignition::math::Pose3d for an entity, but its frame of reference is not clear from the component itself. For now, the physics and rendering systems have been assuming the SDF spec:

Entity Pose frame
Model Parent entity (world or parent model)
Link Parent model
Collision Parent link
Visual Parent link
Joint (not on ign-gazebo yet) Child link

Related discussions

Before any considerations, it would be interesting to be aware of previous documents:

Use cases

Several parts of ign-gazebo will handle pose components, and each of them has different use cases. For example:

  • Server: Must be able to parse SDF to create pose components.
  • Physics system: Creates its internal representation based on pose components, and updates them as time elapses.
  • Rendering system: Creates its scene based on pose components and updates the scene as the pose changes.
  • GUI: Displays entity poses to users, and also lets users edit the pose. For increased usability, the user should be able to choose which frame of reference to use, the units, and convention (i.e. Euler / quaternion).

Proposals

Here are some solutions I can think of, please feel free to discuss and propose alternatives below.

"Pose manager"

It looks like it would be convenient to have a central API which allows converting from any frame of reference to any other at any given time, and is accessible by all systems. This would be akin to the TF framework on ROS, but thinner and more specific to the ECS. This way, systems don't need to worry about keeping track of frames, they could just query as needed.

Some considerations:

  • The manager could be implemented as a system, which gathers all pose information and exposes that to other systems on demand.
  • A synchronous interface would be ideal, so systems can make fast queries within their update callbacks. But we also need an asynchronous interface for when systems are spread across processes. So I think it makes sense to use Ignition Transport to provide pose query services, and it would be interesting to use sync/async as needed.
  • ignition::gazebo::systems::SceneBroadcaster already implemented some features which could be moved to the pose manager, like a pose/info publisher and a pose/graph service.

Pose component's frame

It has been suggested before that the pose component carry two pieces of information:

  • The ignition::math::Pose3d
  • The reference frame

This way, each entity could be explicit about what frame its pose is being expressed about.

I think this adds complexity, as all systems will need to handle poses with arbitrary frames.

So my first proposal is: The pose component should not carry frame information, instead, that is defined by convention.

Then the question is about what should the convention be. I lean towards the pose always being expressed w.r.t. the parent entity, as opposed to any other ancestor closer to the root (like the world or the root model). The main reason being that an entity knows who their immediate parent entity is, but it would necessary to crawl the entity tree to figure our who the other descendant would be.

Using the pose manager, any systems which use different conventions should be able to easily get the pose in the frame they're interested in.

Unanswered questions

  • Who is the parent of a joint entity and how does its pose get defined?

Apple support for ign command line tool

Original report (archived issue) by Nate Koenig (Bitbucket: Nathan Koenig).


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

The UNIT_ign_TEST fails on Apple, through homebrew, when using the ign gazebo command line tool. In general, the ign gazebo command line tool fails to load the libignition-gazebo2-ign.dylib. Other packages, such as ign-transport and ign-msgs work fine. There might be a problem associated with loading a component library.

Steps to Reproduce

  1. Change the src/ign_TEST.cc to use ign gazebo instead of ign-gazebo.
  2. Install gazebo on homebrew
  3. Run the /bin/UNIT_ign_TEST test.

Expected behavior:

The test should pass.

Actual behavior:

The test fails

Reproduces how often:

All the time.

Versions

Gazebo 2+

Additional Information

Possible log playback memory leak

Original report (archived issue) by Ian Chen (Bitbucket: Ian Chen, GitHub: iche033).

The original report had attachments: state.tlog


Description

Log playback consumes a lot of memory. It was observed that when playing back the attached state.tlog (2.7MB) recorded in levels.sdf world, memory usage grew consistently over time to roughly >300MB by the end of the playback (~46s sim time)

Steps to Reproduce

  1. Playback the attached state.tlog (or any other log file), e.g. ign gazebo -v 4 -p [path_to_log_dir]
  2. Hit Play on ign-gazebo gui
  3. Open top and observe memory usage

Expected behavior:

It is expected that memory may grow as states get loaded but it should be at a slower pace. There should also be a cap on how much memory that can be consumed.

Actual behavior:

High memory usage ( >300MB over 46s sim time)

Reproduces how often:

All the time

Versions

ign-gazebo 2.0

Additional Information

Related subt issue. It was reported that playback used up all 32GB of RAM

Automatically generate bounding volume for performers

Original report (archived issue) by Addisu Z. Taddese (Bitbucket: azeey, GitHub: azeey).


Summary

Currently, users have to specify the bounding volume of a performer in the <performer> tag.

Motivation

Automatic generation of bounding volumes would help users avoid manually calculating the bounding volumes of their models for all possible configurations of their links and joints.

Segmentation fault when running with old OpenGL version

Original report (archived issue) by Anonymous.


Expected behavior:
Was following the tutorial written here

However ignition gazebo segfaults when running

ign gazebo -r camera_sensor.sdf

Here are the logs:

$ ign gazebo -r camera_sensor.sdf
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:732]  Unable to create the rendering window
[GUI] [Err] [Ogre2RenderEngine.cc:739] Unable to create the rendering window

/usr/lib/ruby/ignition/cmdgazebo2.rb:308: [BUG] Segmentation fault at 0x00000000000002a8
ruby 2.5.1p57 (2018-03-29 revision 63029) [x86_64-linux-gnu]

-- Control frame information -----------------------------------------------
c:0007 p:---- s:0054 e:000053 CFUNC  :call
c:0006 p:0017 s:0050 e:000049 METHOD /usr/lib/ruby/ignition/cmdgazebo2.rb:308
c:0005 p:0038 s:0044 e:000043 BLOCK  /usr/lib/ruby/ignition/cmdgazebo2.rb:325 [FINISH]
c:0004 p:---- s:0041 e:000040 CFUNC  :fork
c:0003 p:0605 s:0037 e:000036 METHOD /usr/lib/ruby/ignition/cmdgazebo2.rb:322
c:0002 p:0628 s:0019 E:0007c8 EVAL   /usr/bin/ign:267 [FINISH]
c:0001 p:0000 s:0003 E:000770 (none) [FINISH]

-- Ruby level backtrace information ----------------------------------------
/usr/bin/ign:267:in `<main>'
/usr/lib/ruby/ignition/cmdgazebo2.rb:322:in `execute'
/usr/lib/ruby/ignition/cmdgazebo2.rb:322:in `fork'
/usr/lib/ruby/ignition/cmdgazebo2.rb:325:in `block in execute'
/usr/lib/ruby/ignition/cmdgazebo2.rb:308:in `runGui'
/usr/lib/ruby/ignition/cmdgazebo2.rb:308:in `call'

-- Machine register context ------------------------------------------------
 RIP: 0x00007f295b5e8940 RBP: 0x00007f295404ad60 RSP: 0x00007f2960a5c150
 RAX: 0x0000000000000000 RBX: 0x00007f2954075520 RCX: 0x0000000000000040
 RDX: 0x0000000000000000 RDI: 0x00007f2954075520 RSI: 0x00007f295404ad60
  R8: 0x0000000000000004  R9: 0x0000000000000000 R10: 0x000000000000003d
 R11: 0x00007f295b670820 R12: 0x00007f29540751b0 R13: 0x00007f2954075520
 R14: 0x00007f2954001780 R15: 0x00007f2960a5c3b0 EFL: 0x0000000000010246

-- C level backtrace information -------------------------------------------
/usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5(0x7f29bf89baa5) [0x7f29bf89baa5]
/usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5(0x7f29bf89bcdc) [0x7f29bf89bcdc]
/usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5(0x7f29bf765884) [0x7f29bf765884]
/usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5(0x7f29bf82bab2) [0x7f29bf82bab2]
/lib/x86_64-linux-gnu/libc.so.6(0x7f29bf32bf20) [0x7f29bf32bf20]
/usr/lib/x86_64-linux-gnu/libOgreMain.so.2.1.0(_ZN4Ogre15ConstBufferPool19_changeRenderSystemEPNS_12RenderSystemE+0x60) [0x7f295b5e8940]
/usr/lib/x86_64-linux-gnu/libOgreHlmsUnlit.so.2.1.0(_ZN4Ogre9HlmsUnlit19_changeRenderSystemEPNS_12RenderSystemE+0x3a) [0x7f295b0101aa]
/usr/lib/x86_64-linux-gnu/libOgreMain.so.2.1.0(_ZN4Ogre11HlmsManager12registerHlmsEPNS_4HlmsEb+0x59) [0x7f295b670879]
/usr/lib/x86_64-linux-gnu/libignition-rendering2-ogre2.so(_ZN8ignition9rendering2v217Ogre2RenderEngine15CreateResourcesEv+0xf43) [0x7f295bd7f543]
/usr/lib/x86_64-linux-gnu/libignition-rendering2-ogre2.so(_ZN8ignition9rendering2v217Ogre2RenderEngine11LoadAttemptEv+0xa2) [0x7f295bd82422]
/usr/lib/x86_64-linux-gnu/libignition-rendering2-ogre2.so(_ZN8ignition9rendering2v217Ogre2RenderEngine8LoadImplERKSt3mapINSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEES9_St4lessIS9_ESaISt4pairIKS9_S9_EEE+0x30b) [0x7f295bd8277b]
/usr/lib/x86_64-linux-gnu/libignition-rendering2.so.2(_ZN8ignition9rendering2v216BaseRenderEngine4LoadERKSt3mapINSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEES9_St4lessIS9_ESaISt4pairIKS9_S9_EEE+0x2e) [0x7f297049742e]
/usr/lib/x86_64-linux-gnu/libignition-rendering2.so.2(_ZN8ignition9rendering2v226RenderEngineManagerPrivate6EngineESt17_Rb_tree_iteratorISt4pairIKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEEPNS1_12RenderEngineEEERKSt3mapISA_SA_St4lessISA_ESaIS4_ISB_SA_EEERSB_+0x41) [0x7f297048d3e1]
/usr/lib/x86_64-linux-gnu/libignition-rendering2.so.2(_ZN8ignition9rendering2v219RenderEngineManager6EngineERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEERKSt3mapIS8_S8_St4lessIS8_ESaISt4pairIS9_S8_EEESA_+0x4a) [0x7f297048d53a]
/usr/lib/x86_64-linux-gnu/libignition-gazebo2-rendering.so.2(_ZN8ignition6gazebo2v210RenderUtil4InitEv+0x161) [0x7f29706e82a1]
/usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/libGzScene3D.so(_ZN8ignition6gazebo2v211IgnRenderer10InitializeEv+0x7e) [0x7f2970950eae]
/usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/libGzScene3D.so(_ZN8ignition6gazebo2v212RenderThread10RenderNextEv+0x88) [0x7f29709542d8]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(_ZN7QObject5eventEP6QEvent+0xe2) [0x7f29b94641b2]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(_ZN16QCoreApplication6notifyEP7QObjectP6QEvent+0x5a) [0x7f29b943485a]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(_ZN16QCoreApplication15notifyInternal2EP7QObjectP6QEvent+0x118) [0x7f29b94349c8]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(_ZN23QCoreApplicationPrivate16sendPostedEventsEP7QObjectiP11QThreadData+0x1ed) [0x7f29b943713d]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(0x7f29b948e353) [0x7f29b948e353]
/usr/lib/x86_64-linux-gnu/libglib-2.0.so.0(g_main_context_dispatch+0x2e7) [0x7f29b5ef2417]
/usr/lib/x86_64-linux-gnu/libglib-2.0.so.0(0x7f29b5ef2650) [0x7f29b5ef2650]
/usr/lib/x86_64-linux-gnu/libglib-2.0.so.0(g_main_context_iteration+0x2c) [0x7f29b5ef26dc]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(_ZN20QEventDispatcherGlib13processEventsE6QFlagsIN10QEventLoop17ProcessEventsFlagEE+0x5f) [0x7f29b948d97f]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(_ZN10QEventLoop4execE6QFlagsINS_17ProcessEventsFlagEE+0x13a) [0x7f29b94329fa]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(_ZN7QThread4execEv+0x6a) [0x7f29b925123a]
/usr/lib/x86_64-linux-gnu/libQt5Core.so.5(0x7f29b925617d) [0x7f29b925617d]
/lib/x86_64-linux-gnu/libpthread.so.0(start_thread+0xdb) [0x7f29bf0d56db]
/lib/x86_64-linux-gnu/libc.so.6(clone+0x3f) [0x7f29bf40e88f] ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

-- Other runtime information -----------------------------------------------

* Loaded script: /usr/bin/ign

* Loaded features:

    0 enumerator.so
    1 thread.rb
    2 rational.so
    3 complex.so
    4 /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/encdb.so
    5 /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/trans/transdb.so
    6 /usr/lib/x86_64-linux-gnu/ruby/2.5.0/rbconfig.rb
    7 /usr/lib/ruby/2.5.0/rubygems/compatibility.rb
    8 /usr/lib/ruby/2.5.0/rubygems/defaults.rb
    9 /usr/lib/ruby/2.5.0/rubygems/deprecate.rb
   10 /usr/lib/ruby/2.5.0/rubygems/errors.rb
   11 /usr/lib/ruby/2.5.0/rubygems/version.rb
   12 /usr/lib/ruby/2.5.0/rubygems/requirement.rb
   13 /usr/lib/ruby/2.5.0/rubygems/platform.rb
   14 /usr/lib/ruby/2.5.0/rubygems/basic_specification.rb
   15 /usr/lib/ruby/2.5.0/rubygems/stub_specification.rb
   16 /usr/lib/ruby/2.5.0/rubygems/util/list.rb
   17 /usr/lib/x86_64-linux-gnu/ruby/2.5.0/stringio.so
   18 /usr/lib/ruby/2.5.0/uri/rfc2396_parser.rb
   19 /usr/lib/ruby/2.5.0/uri/rfc3986_parser.rb
   20 /usr/lib/ruby/2.5.0/uri/common.rb
   21 /usr/lib/ruby/2.5.0/uri/generic.rb
   22 /usr/lib/ruby/2.5.0/uri/ftp.rb
   23 /usr/lib/ruby/2.5.0/uri/http.rb
   24 /usr/lib/ruby/2.5.0/uri/https.rb
   25 /usr/lib/ruby/2.5.0/uri/ldap.rb
   26 /usr/lib/ruby/2.5.0/uri/ldaps.rb
   27 /usr/lib/ruby/2.5.0/uri/mailto.rb
   28 /usr/lib/ruby/2.5.0/uri.rb
   29 /usr/lib/ruby/2.5.0/rubygems/specification.rb
   30 /usr/lib/ruby/2.5.0/rubygems/exceptions.rb
   31 /usr/lib/ruby/vendor_ruby/rubygems/defaults/operating_system.rb
   32 /usr/lib/ruby/2.5.0/rubygems/dependency.rb
   33 /usr/lib/ruby/2.5.0/rubygems/core_ext/kernel_gem.rb
   34 /usr/lib/ruby/2.5.0/monitor.rb
   35 /usr/lib/ruby/2.5.0/rubygems/core_ext/kernel_require.rb
   36 /usr/lib/ruby/2.5.0/rubygems.rb
   37 /usr/lib/ruby/2.5.0/rubygems/path_support.rb
   38 /usr/lib/ruby/vendor_ruby/did_you_mean/version.rb
   39 /usr/lib/ruby/vendor_ruby/did_you_mean/core_ext/name_error.rb
   40 /usr/lib/ruby/vendor_ruby/did_you_mean/levenshtein.rb
   41 /usr/lib/ruby/vendor_ruby/did_you_mean/jaro_winkler.rb
   42 /usr/lib/ruby/vendor_ruby/did_you_mean/spell_checker.rb
   43 /usr/lib/ruby/2.5.0/delegate.rb
   44 /usr/lib/ruby/vendor_ruby/did_you_mean/spell_checkers/name_error_checkers/class_name_checker.rb
   45 /usr/lib/ruby/vendor_ruby/did_you_mean/spell_checkers/name_error_checkers/variable_name_checker.rb
   46 /usr/lib/ruby/vendor_ruby/did_you_mean/spell_checkers/name_error_checkers.rb
   47 /usr/lib/ruby/vendor_ruby/did_you_mean/spell_checkers/method_name_checker.rb
   48 /usr/lib/ruby/vendor_ruby/did_you_mean/spell_checkers/key_error_checker.rb
   49 /usr/lib/ruby/vendor_ruby/did_you_mean/spell_checkers/null_checker.rb
   50 /usr/lib/ruby/vendor_ruby/did_you_mean/formatters/plain_formatter.rb
   51 /usr/lib/ruby/vendor_ruby/did_you_mean.rb
   52 /usr/lib/ruby/2.5.0/optparse.rb
   53 /usr/lib/ruby/2.5.0/psych/versions.rb
   54 /usr/lib/ruby/2.5.0/rubygems/bundler_version_finder.rb
   55 /usr/lib/ruby/2.5.0/psych/exception.rb
   56 /usr/lib/ruby/2.5.0/psych/syntax_error.rb
   57 /usr/lib/x86_64-linux-gnu/ruby/2.5.0/psych.so
   58 /usr/lib/ruby/2.5.0/psych/omap.rb
   59 /usr/lib/ruby/2.5.0/psych/set.rb
   60 /usr/lib/ruby/2.5.0/psych/class_loader.rb
   61 /usr/lib/x86_64-linux-gnu/ruby/2.5.0/strscan.so
   62 /usr/lib/ruby/2.5.0/psych/scalar_scanner.rb
   63 /usr/lib/ruby/2.5.0/psych/nodes/node.rb
   64 /usr/lib/ruby/2.5.0/psych/nodes/stream.rb
   65 /usr/lib/ruby/2.5.0/psych/nodes/document.rb
   66 /usr/lib/ruby/2.5.0/psych/nodes/sequence.rb
   67 /usr/lib/ruby/2.5.0/psych/nodes/scalar.rb
   68 /usr/lib/ruby/2.5.0/psych/nodes/mapping.rb
   69 /usr/lib/ruby/2.5.0/psych/nodes/alias.rb
   70 /usr/lib/ruby/2.5.0/psych/nodes.rb
   71 /usr/lib/ruby/2.5.0/psych/streaming.rb
   72 /usr/lib/ruby/2.5.0/psych/visitors/visitor.rb
   73 /usr/lib/ruby/2.5.0/psych/visitors/to_ruby.rb
   74 /usr/lib/ruby/2.5.0/psych/visitors/emitter.rb
   75 /usr/lib/ruby/2.5.0/psych/handler.rb
   76 /usr/lib/ruby/2.5.0/psych/tree_builder.rb
   77 /usr/lib/ruby/2.5.0/psych/visitors/yaml_tree.rb
   78 /usr/lib/ruby/2.5.0/psych/json/ruby_events.rb
   79 /usr/lib/ruby/2.5.0/psych/visitors/json_tree.rb
   80 /usr/lib/ruby/2.5.0/psych/visitors/depth_first.rb
   81 /usr/lib/ruby/2.5.0/psych/visitors.rb
   82 /usr/lib/ruby/2.5.0/psych/parser.rb
   83 /usr/lib/ruby/2.5.0/psych/coder.rb
   84 /usr/lib/ruby/2.5.0/psych/core_ext.rb
   85 /usr/lib/ruby/2.5.0/psych/stream.rb
   86 /usr/lib/ruby/2.5.0/psych/json/yaml_events.rb
   87 /usr/lib/ruby/2.5.0/psych/json/tree_builder.rb
   88 /usr/lib/ruby/2.5.0/psych/json/stream.rb
   89 /usr/lib/ruby/2.5.0/psych/handlers/document_stream.rb
   90 /usr/lib/ruby/2.5.0/psych.rb
   91 /usr/lib/ruby/2.5.0/yaml.rb
   92 /usr/lib/x86_64-linux-gnu/ruby/2.5.0/fiddle.so
   93 /usr/lib/ruby/2.5.0/fiddle/function.rb
   94 /usr/lib/ruby/2.5.0/fiddle/closure.rb
   95 /usr/lib/ruby/2.5.0/fiddle.rb
   96 /usr/lib/ruby/2.5.0/fiddle/value.rb
   97 /usr/lib/ruby/2.5.0/fiddle/pack.rb
   98 /usr/lib/ruby/2.5.0/fiddle/struct.rb
   99 /usr/lib/ruby/2.5.0/fiddle/cparser.rb
  100 /usr/lib/ruby/2.5.0/fiddle/import.rb
  101 /usr/lib/x86_64-linux-gnu/ruby/2.5.0/cgi/escape.so
  102 /usr/lib/ruby/2.5.0/cgi/util.rb
  103 /usr/lib/ruby/2.5.0/erb.rb
  104 /usr/lib/ruby/ignition/cmdgazebo2.rb

* Process memory map:

55cc02df5000-55cc02df6000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 394022                    /usr/bin/ruby2.5
55cc02ff5000-55cc02ff6000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 394022                    /usr/bin/ruby2.5
55cc02ff6000-55cc02ff7000 rw-p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 394022                    /usr/bin/ruby2.5
55cc0397a000-55cc041a1000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0                          [heap]
55cc041a1000-55cc085ad000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0                          [heap]
7f2953ab8000-7f2954000000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398866                    /usr/lib/x86_64-linux-gnu/libQt5Core.so.5.9.5
7f2954000000-7f2954084000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2954084000-7f2958000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f295813e000-7f2958254000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397216                    /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0.5600.4
7f2958254000-7f29583e5000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398998                    /usr/lib/x86_64-linux-gnu/libignition-rendering2-ogre2.so.2.1.2
7f29583e5000-7f29589d3000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399644                    /usr/lib/x86_64-linux-gnu/libOgreMain.so.2.1.0
7f29589d3000-7f29598f5000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 395428                    /usr/lib/debug/lib/x86_64-linux-gnu/libc-2.27.so
7f29598f5000-7f2959ae5000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840034                   /lib/x86_64-linux-gnu/libc-2.27.so
7f2959ae5000-7f2959d87000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 396941                    /usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5.1
7f2959d87000-7f2959dbe000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399637                    /usr/lib/x86_64-linux-gnu/OGRE-2.1/OGRE/Plugin_ParticleFX.so.2.1.0
7f2959dbe000-7f2959fbd000 ---p 00037000 103:09 399637                    /usr/lib/x86_64-linux-gnu/OGRE-2.1/OGRE/Plugin_ParticleFX.so.2.1.0
7f2959fbd000-7f2959fc0000 r--p 00036000 103:09 399637                    /usr/lib/x86_64-linux-gnu/OGRE-2.1/OGRE/Plugin_ParticleFX.so.2.1.0
7f2959fc0000-7f2959fc1000 rw-p 00039000 103:09 399637                    /usr/lib/x86_64-linux-gnu/OGRE-2.1/OGRE/Plugin_ParticleFX.so.2.1.0
7f2959fc1000-7f295a088000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399638                    /usr/lib/x86_64-linux-gnu/OGRE-2.1/OGRE/RenderSystem_GL3Plus.so.2.1.0
7f295a088000-7f295a288000 ---p 000c7000 103:09 399638                    /usr/lib/x86_64-linux-gnu/OGRE-2.1/OGRE/RenderSystem_GL3Plus.so.2.1.0
7f295a288000-7f295a28f000 r--p 000c7000 103:09 399638                    /usr/lib/x86_64-linux-gnu/OGRE-2.1/OGRE/RenderSystem_GL3Plus.so.2.1.0
7f295a28f000-7f295a290000 rw-p 000ce000 103:09 399638                    /usr/lib/x86_64-linux-gnu/OGRE-2.1/OGRE/RenderSystem_GL3Plus.so.2.1.0
7f295a290000-7f295a291000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f295a291000-7f295a2a2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401318                    /usr/lib/x86_64-linux-gnu/libXpm.so.4.11.0
7f295a2a2000-7f295a4a1000 ---p 00011000 103:09 401318                    /usr/lib/x86_64-linux-gnu/libXpm.so.4.11.0
7f295a4a1000-7f295a4a2000 r--p 00010000 103:09 401318                    /usr/lib/x86_64-linux-gnu/libXpm.so.4.11.0
7f295a4a2000-7f295a4a3000 rw-p 00011000 103:09 401318                    /usr/lib/x86_64-linux-gnu/libXpm.so.4.11.0
7f295a4a3000-7f295a4bb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401314                    /usr/lib/x86_64-linux-gnu/libXmu.so.6.2.0
7f295a4bb000-7f295a6ba000 ---p 00018000 103:09 401314                    /usr/lib/x86_64-linux-gnu/libXmu.so.6.2.0
7f295a6ba000-7f295a6bb000 r--p 00017000 103:09 401314                    /usr/lib/x86_64-linux-gnu/libXmu.so.6.2.0
7f295a6bb000-7f295a6bc000 rw-p 00018000 103:09 401314                    /usr/lib/x86_64-linux-gnu/libXmu.so.6.2.0
7f295a6bc000-7f295a6c2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404834                    /usr/lib/x86_64-linux-gnu/libzzip-0.so.13.0.62
7f295a6c2000-7f295a8c1000 ---p 00006000 103:09 404834                    /usr/lib/x86_64-linux-gnu/libzzip-0.so.13.0.62
7f295a8c1000-7f295a8c2000 r--p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 404834                    /usr/lib/x86_64-linux-gnu/libzzip-0.so.13.0.62
7f295a8c2000-7f295a8c3000 rw-p 00006000 103:09 404834                    /usr/lib/x86_64-linux-gnu/libzzip-0.so.13.0.62
7f295a8c3000-7f295a92c000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401292                    /usr/lib/x86_64-linux-gnu/libXaw7.so.7.0.0
7f295a92c000-7f295ab2b000 ---p 00069000 103:09 401292                    /usr/lib/x86_64-linux-gnu/libXaw7.so.7.0.0
7f295ab2b000-7f295ab2c000 r--p 00068000 103:09 401292                    /usr/lib/x86_64-linux-gnu/libXaw7.so.7.0.0
7f295ab2c000-7f295ab36000 rw-p 00069000 103:09 401292                    /usr/lib/x86_64-linux-gnu/libXaw7.so.7.0.0
7f295ab36000-7f295ab37000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f295ab37000-7f295ab99000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401326                    /usr/lib/x86_64-linux-gnu/libXt.so.6.0.0
7f295ab99000-7f295ad99000 ---p 00062000 103:09 401326                    /usr/lib/x86_64-linux-gnu/libXt.so.6.0.0
7f295ad99000-7f295ad9a000 r--p 00062000 103:09 401326                    /usr/lib/x86_64-linux-gnu/libXt.so.6.0.0
7f295ad9a000-7f295ad9f000 rw-p 00063000 103:09 401326                    /usr/lib/x86_64-linux-gnu/libXt.so.6.0.0
7f295ad9f000-7f295ada0000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f295ada0000-7f295adfb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399646                    /usr/lib/x86_64-linux-gnu/libOgreOverlay.so.2.1.0
7f295adfb000-7f295affb000 ---p 0005b000 103:09 399646                    /usr/lib/x86_64-linux-gnu/libOgreOverlay.so.2.1.0
7f295affb000-7f295afff000 r--p 0005b000 103:09 399646                    /usr/lib/x86_64-linux-gnu/libOgreOverlay.so.2.1.0
7f295afff000-7f295b000000 rw-p 0005f000 103:09 399646                    /usr/lib/x86_64-linux-gnu/libOgreOverlay.so.2.1.0
7f295b000000-7f295b01e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399642                    /usr/lib/x86_64-linux-gnu/libOgreHlmsUnlit.so.2.1.0
7f295b01e000-7f295b21d000 ---p 0001e000 103:09 399642                    /usr/lib/x86_64-linux-gnu/libOgreHlmsUnlit.so.2.1.0
7f295b21d000-7f295b21f000 r--p 0001d000 103:09 399642                    /usr/lib/x86_64-linux-gnu/libOgreHlmsUnlit.so.2.1.0
7f295b21f000-7f295b220000 rw-p 0001f000 103:09 399642                    /usr/lib/x86_64-linux-gnu/libOgreHlmsUnlit.so.2.1.0
7f295b220000-7f295b275000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399640                    /usr/lib/x86_64-linux-gnu/libOgreHlmsPbs.so.2.1.0
7f295b275000-7f295b475000 ---p 00055000 103:09 399640                    /usr/lib/x86_64-linux-gnu/libOgreHlmsPbs.so.2.1.0
7f295b475000-7f295b477000 r--p 00055000 103:09 399640                    /usr/lib/x86_64-linux-gnu/libOgreHlmsPbs.so.2.1.0
7f295b477000-7f295b478000 rw-p 00057000 103:09 399640                    /usr/lib/x86_64-linux-gnu/libOgreHlmsPbs.so.2.1.0
7f295b478000-7f295ba40000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399644                    /usr/lib/x86_64-linux-gnu/libOgreMain.so.2.1.0
7f295ba40000-7f295bc3f000 ---p 005c8000 103:09 399644                    /usr/lib/x86_64-linux-gnu/libOgreMain.so.2.1.0
7f295bc3f000-7f295bc62000 r--p 005c7000 103:09 399644                    /usr/lib/x86_64-linux-gnu/libOgreMain.so.2.1.0
7f295bc62000-7f295bc65000 rw-p 005ea000 103:09 399644                    /usr/lib/x86_64-linux-gnu/libOgreMain.so.2.1.0
7f295bc65000-7f295bc6f000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f295bc6f000-7f295bdb7000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398998                    /usr/lib/x86_64-linux-gnu/libignition-rendering2-ogre2.so.2.1.2
7f295bdb7000-7f295bfb6000 ---p 00148000 103:09 398998                    /usr/lib/x86_64-linux-gnu/libignition-rendering2-ogre2.so.2.1.2
7f295bfb6000-7f295bffe000 r--p 00147000 103:09 398998                    /usr/lib/x86_64-linux-gnu/libignition-rendering2-ogre2.so.2.1.2
7f295bffe000-7f295bfff000 rw-p 0018f000 103:09 398998                    /usr/lib/x86_64-linux-gnu/libignition-rendering2-ogre2.so.2.1.2
7f295bfff000-7f295c000000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f295c000000-7f295c021000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f295c021000-7f2960000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2960028000-7f296004c000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840167                   /lib/x86_64-linux-gnu/libpthread-2.27.so
7f296004c000-7f2960093000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 952667                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/libGzScene3D.so
7f2960093000-7f2960107000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399055                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-rendering.so.2.11.0
7f2960107000-7f2960155000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398982                    /usr/lib/x86_64-linux-gnu/libignition-rendering2.so.2.1.2
7f2960155000-7f2960175000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399642                    /usr/lib/x86_64-linux-gnu/libOgreHlmsUnlit.so.2.1.0
7f2960175000-7f2960195000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9738939                   /home/jaeyoung/#9738939 (deleted)
7f2960195000-7f2960199000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3941                       /i915 (deleted)
7f2960199000-7f29601a9000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3940                       /i915 (deleted)
7f29601aa000-7f29601ac000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 394022                    /usr/bin/ruby2.5
7f29601ac000-7f29601b3000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 657242                    /usr/lib/x86_64-linux-gnu/gconv/gconv-modules.cache
7f29601b3000-7f29601d3000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9738939                   /home/jaeyoung/#9738939 (deleted)
7f29601d3000-7f29601f3000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3888                       /i915 (deleted)
7f29601f3000-7f29601f7000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4212                       /i915 (deleted)
7f29601f7000-7f29601fc000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4211                       /i915 (deleted)
7f29601fc000-7f296020c000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4161                       /i915 (deleted)
7f296020c000-7f296021c000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4090                       /i915 (deleted)
7f296021c000-7f2960220000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4089                       /i915 (deleted)
7f2960220000-7f2960225000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4083                       /i915 (deleted)
7f2960225000-7f2960241000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4063                       /i915 (deleted)
7f2960241000-7f2960251000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3976                       /i915 (deleted)
7f2960251000-7f296025d000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3951                       /i915 (deleted)
7f296025d000-7f296025e000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f296025e000-7f2960a5e000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2960a5e000-7f2960a63000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3947                       /i915 (deleted)
7f2960a63000-7f2960a67000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3935                       /i915 (deleted)
7f2960a67000-7f2960a6b000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3932                       /i915 (deleted)
7f2960a6b000-7f2960a80000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 829288                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libImageDisplay.so
7f2960a80000-7f2960c80000 ---p 00015000 103:09 829288                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libImageDisplay.so
7f2960c80000-7f2960c81000 r--p 00015000 103:09 829288                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libImageDisplay.so
7f2960c81000-7f2960c82000 rw-p 00016000 103:09 829288                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libImageDisplay.so
7f2960c82000-7f2960c95000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 829293                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libWorldStats.so
7f2960c95000-7f2960e94000 ---p 00013000 103:09 829293                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libWorldStats.so
7f2960e94000-7f2960e95000 r--p 00012000 103:09 829293                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libWorldStats.so
7f2960e95000-7f2960e96000 rw-p 00013000 103:09 829293                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libWorldStats.so
7f2960e96000-7f2960ea0000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2960ea0000-7f2960fc0000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2960fc0000-7f2961296000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2961296000-7f29612b0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 829292                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libWorldControl.so
7f29612b0000-7f29614b0000 ---p 0001a000 103:09 829292                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libWorldControl.so
7f29614b0000-7f29614b1000 r--p 0001a000 103:09 829292                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libWorldControl.so
7f29614b1000-7f29614b2000 rw-p 0001b000 103:09 829292                    /usr/lib/x86_64-linux-gnu/ign-gui-2/plugins/libWorldControl.so
7f29614b2000-7f2961504000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1312226                   /usr/share/fonts/truetype/ubuntu/Ubuntu-B.ttf
7f2961504000-7f2961510000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525666                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/private/libqtgraphicaleffectsprivate.so
7f2961510000-7f2961710000 ---p 0000c000 103:09 525666                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/private/libqtgraphicaleffectsprivate.so
7f2961710000-7f2961711000 r--p 0000c000 103:09 525666                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/private/libqtgraphicaleffectsprivate.so
7f2961711000-7f2961712000 rw-p 0000d000 103:09 525666                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/private/libqtgraphicaleffectsprivate.so
7f2961712000-7f2961724000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 952664                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/IgnGazebo/libEntityContextMenu.so
7f2961724000-7f2961923000 ---p 00012000 103:09 952664                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/IgnGazebo/libEntityContextMenu.so
7f2961923000-7f2961924000 r--p 00011000 103:09 952664                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/IgnGazebo/libEntityContextMenu.so
7f2961924000-7f2961925000 rw-p 00012000 103:09 952664                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/IgnGazebo/libEntityContextMenu.so
7f2961925000-7f2961927000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525645                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/libqtgraphicaleffectsplugin.so
7f2961927000-7f2961b26000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525645                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/libqtgraphicaleffectsplugin.so
7f2961b26000-7f2961b27000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525645                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/libqtgraphicaleffectsplugin.so
7f2961b27000-7f2961b28000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525645                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/libqtgraphicaleffectsplugin.so
7f2961b28000-7f2961b2d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401267                    /usr/lib/x86_64-linux-gnu/libIlmThread-2_2.so.12.0.0
7f2961b2d000-7f2961d2d000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401267                    /usr/lib/x86_64-linux-gnu/libIlmThread-2_2.so.12.0.0
7f2961d2d000-7f2961d2e000 r--p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401267                    /usr/lib/x86_64-linux-gnu/libIlmThread-2_2.so.12.0.0
7f2961d2e000-7f2961d2f000 rw-p 00006000 103:09 401267                    /usr/lib/x86_64-linux-gnu/libIlmThread-2_2.so.12.0.0
7f2961d2f000-7f2961d3a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401956                    /usr/lib/x86_64-linux-gnu/libjbig.so.0
7f2961d3a000-7f2961f39000 ---p 0000b000 103:09 401956                    /usr/lib/x86_64-linux-gnu/libjbig.so.0
7f2961f39000-7f2961f3a000 r--p 0000a000 103:09 401956                    /usr/lib/x86_64-linux-gnu/libjbig.so.0
7f2961f3a000-7f2961f3d000 rw-p 0000b000 103:09 401956                    /usr/lib/x86_64-linux-gnu/libjbig.so.0
7f2961f3d000-7f2961f6b000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 393937                    /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0
7f2961f6b000-7f296216a000 ---p 0002e000 103:09 393937                    /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0
7f296216a000-7f296216b000 r--p 0002d000 103:09 393937                    /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0
7f296216b000-7f296216c000 rw-p 0002e000 103:09 393937                    /usr/lib/x86_64-linux-gnu/libgomp.so.1.0.0
7f296216c000-7f29621be000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401980                    /usr/lib/x86_64-linux-gnu/liblcms2.so.2.0.8
7f29621be000-7f29623be000 ---p 00052000 103:09 401980                    /usr/lib/x86_64-linux-gnu/liblcms2.so.2.0.8
7f29623be000-7f29623c0000 r--p 00052000 103:09 401980                    /usr/lib/x86_64-linux-gnu/liblcms2.so.2.0.8
7f29623c0000-7f29623c3000 rw-p 00054000 103:09 401980                    /usr/lib/x86_64-linux-gnu/liblcms2.so.2.0.8
7f29623c3000-7f29623c4000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29623c4000-7f29623f7000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404807                    /usr/lib/x86_64-linux-gnu/libjpegxr.so.1.1
7f29623f7000-7f29625f6000 ---p 00033000 103:09 404807                    /usr/lib/x86_64-linux-gnu/libjpegxr.so.1.1
7f29625f6000-7f29625f7000 r--p 00032000 103:09 404807                    /usr/lib/x86_64-linux-gnu/libjpegxr.so.1.1
7f29625f7000-7f29625f8000 rw-p 00033000 103:09 404807                    /usr/lib/x86_64-linux-gnu/libjpegxr.so.1.1
7f29625f8000-7f296262f000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401507                    /usr/lib/x86_64-linux-gnu/libcroco-0.6.so.3.0.1
7f296262f000-7f296282f000 ---p 00037000 103:09 401507                    /usr/lib/x86_64-linux-gnu/libcroco-0.6.so.3.0.1
7f296282f000-7f2962832000 r--p 00037000 103:09 401507                    /usr/lib/x86_64-linux-gnu/libcroco-0.6.so.3.0.1
7f2962832000-7f2962833000 rw-p 0003a000 103:09 401507                    /usr/lib/x86_64-linux-gnu/libcroco-0.6.so.3.0.1
7f2962833000-7f296283d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 393666                    /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0
7f296283d000-7f2962a3c000 ---p 0000a000 103:09 393666                    /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0
7f2962a3c000-7f2962a3d000 r--p 00009000 103:09 393666                    /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0
7f2962a3d000-7f2962a3e000 rw-p 0000a000 103:09 393666                    /usr/lib/x86_64-linux-gnu/libnuma.so.1.0.0
7f2962a3e000-7f2962a6a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403419                    /usr/lib/x86_64-linux-gnu/libsoxr.so.0.1.1
7f2962a6a000-7f2962c69000 ---p 0002c000 103:09 403419                    /usr/lib/x86_64-linux-gnu/libsoxr.so.0.1.1
7f2962c69000-7f2962c6b000 r--p 0002b000 103:09 403419                    /usr/lib/x86_64-linux-gnu/libsoxr.so.0.1.1
7f2962c6b000-7f2962c6c000 rw-p 0002d000 103:09 403419                    /usr/lib/x86_64-linux-gnu/libsoxr.so.0.1.1
7f2962c6c000-7f2962ca1000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2962ca1000-7f2962cee000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402032                    /usr/lib/x86_64-linux-gnu/libmpg123.so.0.44.8
7f2962cee000-7f2962eee000 ---p 0004d000 103:09 402032                    /usr/lib/x86_64-linux-gnu/libmpg123.so.0.44.8
7f2962eee000-7f2962eef000 r--p 0004d000 103:09 402032                    /usr/lib/x86_64-linux-gnu/libmpg123.so.0.44.8
7f2962eef000-7f2962ef0000 rw-p 0004e000 103:09 402032                    /usr/lib/x86_64-linux-gnu/libmpg123.so.0.44.8
7f2962ef0000-7f2962f00000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2962f00000-7f2962f1b000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401259                    /usr/lib/x86_64-linux-gnu/libIex-2_2.so.12.0.0
7f2962f1b000-7f296311a000 ---p 0001b000 103:09 401259                    /usr/lib/x86_64-linux-gnu/libIex-2_2.so.12.0.0
7f296311a000-7f296311d000 r--p 0001a000 103:09 401259                    /usr/lib/x86_64-linux-gnu/libIex-2_2.so.12.0.0
7f296311d000-7f296311e000 rw-p 0001d000 103:09 401259                    /usr/lib/x86_64-linux-gnu/libIex-2_2.so.12.0.0
7f296311e000-7f2963160000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401253                    /usr/lib/x86_64-linux-gnu/libHalf.so.12.0.0
7f2963160000-7f296335f000 ---p 00042000 103:09 401253                    /usr/lib/x86_64-linux-gnu/libHalf.so.12.0.0
7f296335f000-7f2963360000 r--p 00041000 103:09 401253                    /usr/lib/x86_64-linux-gnu/libHalf.so.12.0.0
7f2963360000-7f2963361000 rw-p 00042000 103:09 401253                    /usr/lib/x86_64-linux-gnu/libHalf.so.12.0.0
7f2963361000-7f2963520000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403650                    /usr/lib/x86_64-linux-gnu/libIlmImf-2_2.so.22.0.0
7f2963520000-7f296371f000 ---p 001bf000 103:09 403650                    /usr/lib/x86_64-linux-gnu/libIlmImf-2_2.so.22.0.0
7f296371f000-7f2963722000 r--p 001be000 103:09 403650                    /usr/lib/x86_64-linux-gnu/libIlmImf-2_2.so.22.0.0
7f2963722000-7f2963823000 rw-p 001c1000 103:09 403650                    /usr/lib/x86_64-linux-gnu/libIlmImf-2_2.so.22.0.0
7f2963823000-7f2963824000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2963824000-7f2963897000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 395250                    /usr/lib/x86_64-linux-gnu/libtiff.so.5.3.0
7f2963897000-7f2963a96000 ---p 00073000 103:09 395250                    /usr/lib/x86_64-linux-gnu/libtiff.so.5.3.0
7f2963a96000-7f2963a9a000 r--p 00072000 103:09 395250                    /usr/lib/x86_64-linux-gnu/libtiff.so.5.3.0
7f2963a9a000-7f2963a9b000 rw-p 00076000 103:09 395250                    /usr/lib/x86_64-linux-gnu/libtiff.so.5.3.0
7f2963a9b000-7f2963b21000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 395890                    /usr/lib/x86_64-linux-gnu/libraw.so.16.0.0
7f2963b21000-7f2963d21000 ---p 00086000 103:09 395890                    /usr/lib/x86_64-linux-gnu/libraw.so.16.0.0
7f2963d21000-7f2963d2b000 r--p 00086000 103:09 395890                    /usr/lib/x86_64-linux-gnu/libraw.so.16.0.0
7f2963d2b000-7f2963d6e000 rw-p 00090000 103:09 395890                    /usr/lib/x86_64-linux-gnu/libraw.so.16.0.0
7f2963d6e000-7f2963d8b000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404808                    /usr/lib/x86_64-linux-gnu/libjxrglue.so.1.1
7f2963d8b000-7f2963f8a000 ---p 0001d000 103:09 404808                    /usr/lib/x86_64-linux-gnu/libjxrglue.so.1.1
7f2963f8a000-7f2963f8c000 r--p 0001c000 103:09 404808                    /usr/lib/x86_64-linux-gnu/libjxrglue.so.1.1
7f2963f8c000-7f2963f8d000 rw-p 0001e000 103:09 404808                    /usr/lib/x86_64-linux-gnu/libjxrglue.so.1.1
7f2963f8d000-7f2963f8e000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2963f8e000-7f2963f90000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403401                    /usr/lib/x86_64-linux-gnu/libva-drm.so.2.100.0
7f2963f90000-7f296418f000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 403401                    /usr/lib/x86_64-linux-gnu/libva-drm.so.2.100.0
7f296418f000-7f2964190000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 403401                    /usr/lib/x86_64-linux-gnu/libva-drm.so.2.100.0
7f2964190000-7f2964191000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 403401                    /usr/lib/x86_64-linux-gnu/libva-drm.so.2.100.0
7f2964191000-7f2964196000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403403                    /usr/lib/x86_64-linux-gnu/libva-x11.so.2.100.0
7f2964196000-7f2964395000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 403403                    /usr/lib/x86_64-linux-gnu/libva-x11.so.2.100.0
7f2964395000-7f2964396000 r--p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 403403                    /usr/lib/x86_64-linux-gnu/libva-x11.so.2.100.0
7f2964396000-7f2964397000 rw-p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 403403                    /usr/lib/x86_64-linux-gnu/libva-x11.so.2.100.0
7f2964397000-7f296439a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403405                    /usr/lib/x86_64-linux-gnu/libvdpau.so.1.0.0
7f296439a000-7f2964599000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 403405                    /usr/lib/x86_64-linux-gnu/libvdpau.so.1.0.0
7f2964599000-7f296459a000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 403405                    /usr/lib/x86_64-linux-gnu/libvdpau.so.1.0.0
7f296459a000-7f296459b000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 403405                    /usr/lib/x86_64-linux-gnu/libvdpau.so.1.0.0
7f296459b000-7f29645a7000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403411                    /usr/lib/x86_64-linux-gnu/libgsm.so.1.0.12
7f29645a7000-7f29647a6000 ---p 0000c000 103:09 403411                    /usr/lib/x86_64-linux-gnu/libgsm.so.1.0.12
7f29647a6000-7f29647a7000 r--p 0000b000 103:09 403411                    /usr/lib/x86_64-linux-gnu/libgsm.so.1.0.12
7f29647a7000-7f29647a8000 rw-p 0000c000 103:09 403411                    /usr/lib/x86_64-linux-gnu/libgsm.so.1.0.12
7f29647a8000-7f29647f1000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402024                    /usr/lib/x86_64-linux-gnu/libmp3lame.so.0.0.0
7f29647f1000-7f29649f0000 ---p 00049000 103:09 402024                    /usr/lib/x86_64-linux-gnu/libmp3lame.so.0.0.0
7f29649f0000-7f29649f1000 r--p 00048000 103:09 402024                    /usr/lib/x86_64-linux-gnu/libmp3lame.so.0.0.0
7f29649f1000-7f29649f2000 rw-p 00049000 103:09 402024                    /usr/lib/x86_64-linux-gnu/libmp3lame.so.0.0.0
7f29649f2000-7f2964a1f000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2964a1f000-7f2964a73000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397591                    /usr/lib/x86_64-linux-gnu/libopenjp2.so.2.3.0
7f2964a73000-7f2964c73000 ---p 00054000 103:09 397591                    /usr/lib/x86_64-linux-gnu/libopenjp2.so.2.3.0
7f2964c73000-7f2964c74000 r--p 00054000 103:09 397591                    /usr/lib/x86_64-linux-gnu/libopenjp2.so.2.3.0
7f2964c74000-7f2964c75000 rw-p 00055000 103:09 397591                    /usr/lib/x86_64-linux-gnu/libopenjp2.so.2.3.0
7f2964c75000-7f2964cbe000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402099                    /usr/lib/x86_64-linux-gnu/libopus.so.0.5.2
7f2964cbe000-7f2964ebd000 ---p 00049000 103:09 402099                    /usr/lib/x86_64-linux-gnu/libopus.so.0.5.2
7f2964ebd000-7f2964ebe000 r--p 00048000 103:09 402099                    /usr/lib/x86_64-linux-gnu/libopus.so.0.5.2
7f2964ebe000-7f2964ebf000 rw-p 00049000 103:09 402099                    /usr/lib/x86_64-linux-gnu/libopus.so.0.5.2
7f2964ebf000-7f2964ef5000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402234                    /usr/lib/x86_64-linux-gnu/librsvg-2.so.2.40.20
7f2964ef5000-7f29650f5000 ---p 00036000 103:09 402234                    /usr/lib/x86_64-linux-gnu/librsvg-2.so.2.40.20
7f29650f5000-7f29650f6000 r--p 00036000 103:09 402234                    /usr/lib/x86_64-linux-gnu/librsvg-2.so.2.40.20
7f29650f6000-7f29650f7000 rw-p 00037000 103:09 402234                    /usr/lib/x86_64-linux-gnu/librsvg-2.so.2.40.20
7f29650f7000-7f2965101000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403415                    /usr/lib/x86_64-linux-gnu/libshine.so.3.0.1
7f2965101000-7f2965300000 ---p 0000a000 103:09 403415                    /usr/lib/x86_64-linux-gnu/libshine.so.3.0.1
7f2965300000-7f2965301000 r--p 00009000 103:09 403415                    /usr/lib/x86_64-linux-gnu/libshine.so.3.0.1
7f2965301000-7f2965302000 rw-p 0000a000 103:09 403415                    /usr/lib/x86_64-linux-gnu/libshine.so.3.0.1
7f2965302000-7f2965309000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403417                    /usr/lib/x86_64-linux-gnu/libsnappy.so.1.1.7
7f2965309000-7f2965508000 ---p 00007000 103:09 403417                    /usr/lib/x86_64-linux-gnu/libsnappy.so.1.1.7
7f2965508000-7f2965509000 r--p 00006000 103:09 403417                    /usr/lib/x86_64-linux-gnu/libsnappy.so.1.1.7
7f2965509000-7f296550a000 rw-p 00007000 103:09 403417                    /usr/lib/x86_64-linux-gnu/libsnappy.so.1.1.7
7f296550a000-7f2965522000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402301                    /usr/lib/x86_64-linux-gnu/libspeex.so.1.5.0
7f2965522000-7f2965722000 ---p 00018000 103:09 402301                    /usr/lib/x86_64-linux-gnu/libspeex.so.1.5.0
7f2965722000-7f2965723000 r--p 00018000 103:09 402301                    /usr/lib/x86_64-linux-gnu/libspeex.so.1.5.0
7f2965723000-7f2965724000 rw-p 00019000 103:09 402301                    /usr/lib/x86_64-linux-gnu/libspeex.so.1.5.0
7f2965724000-7f2965741000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402341                    /usr/lib/x86_64-linux-gnu/libtheoradec.so.1.1.4
7f2965741000-7f2965940000 ---p 0001d000 103:09 402341                    /usr/lib/x86_64-linux-gnu/libtheoradec.so.1.1.4
7f2965940000-7f2965941000 r--p 0001c000 103:09 402341                    /usr/lib/x86_64-linux-gnu/libtheoradec.so.1.1.4
7f2965941000-7f2965942000 rw-p 0001d000 103:09 402341                    /usr/lib/x86_64-linux-gnu/libtheoradec.so.1.1.4
7f2965942000-7f2965980000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402343                    /usr/lib/x86_64-linux-gnu/libtheoraenc.so.1.1.2
7f2965980000-7f2965b7f000 ---p 0003e000 103:09 402343                    /usr/lib/x86_64-linux-gnu/libtheoraenc.so.1.1.2
7f2965b7f000-7f2965b80000 r--p 0003d000 103:09 402343                    /usr/lib/x86_64-linux-gnu/libtheoraenc.so.1.1.2
7f2965b80000-7f2965b81000 rw-p 0003e000 103:09 402343                    /usr/lib/x86_64-linux-gnu/libtheoraenc.so.1.1.2
7f2965b81000-7f2965b9e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402359                    /usr/lib/x86_64-linux-gnu/libtwolame.so.0.0.0
7f2965b9e000-7f2965d9e000 ---p 0001d000 103:09 402359                    /usr/lib/x86_64-linux-gnu/libtwolame.so.0.0.0
7f2965d9e000-7f2965d9f000 r--p 0001d000 103:09 402359                    /usr/lib/x86_64-linux-gnu/libtwolame.so.0.0.0
7f2965d9f000-7f2965da0000 rw-p 0001e000 103:09 402359                    /usr/lib/x86_64-linux-gnu/libtwolame.so.0.0.0
7f2965da0000-7f2965da4000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2965da4000-7f2965e31000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402406                    /usr/lib/x86_64-linux-gnu/libvorbisenc.so.2.0.11
7f2965e31000-7f2966030000 ---p 0008d000 103:09 402406                    /usr/lib/x86_64-linux-gnu/libvorbisenc.so.2.0.11
7f2966030000-7f296604c000 r--p 0008c000 103:09 402406                    /usr/lib/x86_64-linux-gnu/libvorbisenc.so.2.0.11
7f296604c000-7f296604d000 rw-p 000a8000 103:09 402406                    /usr/lib/x86_64-linux-gnu/libvorbisenc.so.2.0.11
7f296604d000-7f2966297000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402411                    /usr/lib/x86_64-linux-gnu/libvpx.so.5.0.0
7f2966297000-7f2966497000 ---p 0024a000 103:09 402411                    /usr/lib/x86_64-linux-gnu/libvpx.so.5.0.0
7f2966497000-7f2966499000 r--p 0024a000 103:09 402411                    /usr/lib/x86_64-linux-gnu/libvpx.so.5.0.0
7f2966499000-7f296649a000 rw-p 0024c000 103:09 402411                    /usr/lib/x86_64-linux-gnu/libvpx.so.5.0.0
7f296649a000-7f296649c000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f296649c000-7f29664c5000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 395801                    /usr/lib/x86_64-linux-gnu/libwavpack.so.1.2.0
7f29664c5000-7f29666c4000 ---p 00029000 103:09 395801                    /usr/lib/x86_64-linux-gnu/libwavpack.so.1.2.0
7f29666c4000-7f29666c5000 r--p 00028000 103:09 395801                    /usr/lib/x86_64-linux-gnu/libwavpack.so.1.2.0
7f29666c5000-7f29666c6000 rw-p 00029000 103:09 395801                    /usr/lib/x86_64-linux-gnu/libwavpack.so.1.2.0
7f29666c6000-7f29666cf000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402435                    /usr/lib/x86_64-linux-gnu/libwebpmux.so.3.0.1
7f29666cf000-7f29668ce000 ---p 00009000 103:09 402435                    /usr/lib/x86_64-linux-gnu/libwebpmux.so.3.0.1
7f29668ce000-7f29668cf000 r--p 00008000 103:09 402435                    /usr/lib/x86_64-linux-gnu/libwebpmux.so.3.0.1
7f29668cf000-7f29668d0000 rw-p 00009000 103:09 402435                    /usr/lib/x86_64-linux-gnu/libwebpmux.so.3.0.1
7f29668d0000-7f29669f8000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403423                    /usr/lib/x86_64-linux-gnu/libx264.so.152
7f29669f8000-7f2966bf8000 ---p 00128000 103:09 403423                    /usr/lib/x86_64-linux-gnu/libx264.so.152
7f2966bf8000-7f2966bf9000 r--p 00128000 103:09 403423                    /usr/lib/x86_64-linux-gnu/libx264.so.152
7f2966bf9000-7f2966bfa000 rw-p 00129000 103:09 403423                    /usr/lib/x86_64-linux-gnu/libx264.so.152
7f2966bfa000-7f2966c75000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2966c75000-7f29676e3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403424                    /usr/lib/x86_64-linux-gnu/libx265.so.146
7f29676e3000-7f29678e2000 ---p 00a6e000 103:09 403424                    /usr/lib/x86_64-linux-gnu/libx265.so.146
7f29678e2000-7f29678e5000 r--p 00a6d000 103:09 403424                    /usr/lib/x86_64-linux-gnu/libx265.so.146
7f29678e5000-7f29678e8000 rw-p 00a70000 103:09 403424                    /usr/lib/x86_64-linux-gnu/libx265.so.146
7f29678e8000-7f29678f6000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29678f6000-7f2967994000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403425                    /usr/lib/x86_64-linux-gnu/libxvidcore.so.4.3
7f2967994000-7f2967b93000 ---p 0009e000 103:09 403425                    /usr/lib/x86_64-linux-gnu/libxvidcore.so.4.3
7f2967b93000-7f2967b94000 r--p 0009d000 103:09 403425                    /usr/lib/x86_64-linux-gnu/libxvidcore.so.4.3
7f2967b94000-7f2967b9e000 rw-p 0009e000 103:09 403425                    /usr/lib/x86_64-linux-gnu/libxvidcore.so.4.3
7f2967b9e000-7f2967c07000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2967c07000-7f2967c7e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403428                    /usr/lib/x86_64-linux-gnu/libzvbi.so.0.13.2
7f2967c7e000-7f2967e7d000 ---p 00077000 103:09 403428                    /usr/lib/x86_64-linux-gnu/libzvbi.so.0.13.2
7f2967e7d000-7f2967e86000 r--p 00076000 103:09 403428                    /usr/lib/x86_64-linux-gnu/libzvbi.so.0.13.2
7f2967e86000-7f2967e92000 rw-p 0007f000 103:09 403428                    /usr/lib/x86_64-linux-gnu/libzvbi.so.0.13.2
7f2967e92000-7f2967eb2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403399                    /usr/lib/x86_64-linux-gnu/libva.so.2.100.0
7f2967eb2000-7f29680b1000 ---p 00020000 103:09 403399                    /usr/lib/x86_64-linux-gnu/libva.so.2.100.0
7f29680b1000-7f29680b2000 r--p 0001f000 103:09 403399                    /usr/lib/x86_64-linux-gnu/libva.so.2.100.0
7f29680b2000-7f29680b3000 rw-p 00020000 103:09 403399                    /usr/lib/x86_64-linux-gnu/libva.so.2.100.0
7f29680b3000-7f29680cd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403409                    /usr/lib/x86_64-linux-gnu/libcrystalhd.so.3.6
7f29680cd000-7f29682cc000 ---p 0001a000 103:09 403409                    /usr/lib/x86_64-linux-gnu/libcrystalhd.so.3.6
7f29682cc000-7f29682cd000 r--p 00019000 103:09 403409                    /usr/lib/x86_64-linux-gnu/libcrystalhd.so.3.6
7f29682cd000-7f29682ce000 rw-p 0001a000 103:09 403409                    /usr/lib/x86_64-linux-gnu/libcrystalhd.so.3.6
7f29682ce000-7f2968334000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402431                    /usr/lib/x86_64-linux-gnu/libwebp.so.6.0.2
7f2968334000-7f2968533000 ---p 00066000 103:09 402431                    /usr/lib/x86_64-linux-gnu/libwebp.so.6.0.2
7f2968533000-7f2968534000 r--p 00065000 103:09 402431                    /usr/lib/x86_64-linux-gnu/libwebp.so.6.0.2
7f2968534000-7f2968535000 rw-p 00066000 103:09 402431                    /usr/lib/x86_64-linux-gnu/libwebp.so.6.0.2
7f2968535000-7f2968537000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2968537000-7f2968553000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403421                    /usr/lib/x86_64-linux-gnu/libswresample.so.2.9.100
7f2968553000-7f2968753000 ---p 0001c000 103:09 403421                    /usr/lib/x86_64-linux-gnu/libswresample.so.2.9.100
7f2968753000-7f2968755000 r--p 0001c000 103:09 403421                    /usr/lib/x86_64-linux-gnu/libswresample.so.2.9.100
7f2968755000-7f2968756000 rw-p 0001e000 103:09 403421                    /usr/lib/x86_64-linux-gnu/libswresample.so.2.9.100
7f2968756000-7f2968765000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1843965                   /lib/x86_64-linux-gnu/libbz2.so.1.0.4
7f2968765000-7f2968964000 ---p 0000f000 103:09 1843965                   /lib/x86_64-linux-gnu/libbz2.so.1.0.4
7f2968964000-7f2968965000 r--p 0000e000 103:09 1843965                   /lib/x86_64-linux-gnu/libbz2.so.1.0.4
7f2968965000-7f2968966000 rw-p 0000f000 103:09 1843965                   /lib/x86_64-linux-gnu/libbz2.so.1.0.4
7f2968966000-7f2968978000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403441                    /usr/lib/x86_64-linux-gnu/libchromaprint.so.1.4.3
7f2968978000-7f2968b77000 ---p 00012000 103:09 403441                    /usr/lib/x86_64-linux-gnu/libchromaprint.so.1.4.3
7f2968b77000-7f2968b78000 r--p 00011000 103:09 403441                    /usr/lib/x86_64-linux-gnu/libchromaprint.so.1.4.3
7f2968b78000-7f2968b79000 rw-p 00012000 103:09 403441                    /usr/lib/x86_64-linux-gnu/libchromaprint.so.1.4.3
7f2968b79000-7f2968bc2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403443                    /usr/lib/x86_64-linux-gnu/libgme.so.0.6.2
7f2968bc2000-7f2968dc1000 ---p 00049000 103:09 403443                    /usr/lib/x86_64-linux-gnu/libgme.so.0.6.2
7f2968dc1000-7f2968dc4000 r--p 00048000 103:09 403443                    /usr/lib/x86_64-linux-gnu/libgme.so.0.6.2
7f2968dc4000-7f2968dc5000 rw-p 0004b000 103:09 403443                    /usr/lib/x86_64-linux-gnu/libgme.so.0.6.2
7f2968dc5000-7f2968f7b000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402512                    /usr/lib/x86_64-linux-gnu/libxml2.so.2.9.4
7f2968f7b000-7f296917b000 ---p 001b6000 103:09 402512                    /usr/lib/x86_64-linux-gnu/libxml2.so.2.9.4
7f296917b000-7f2969183000 r--p 001b6000 103:09 402512                    /usr/lib/x86_64-linux-gnu/libxml2.so.2.9.4
7f2969183000-7f2969185000 rw-p 001be000 103:09 402512                    /usr/lib/x86_64-linux-gnu/libxml2.so.2.9.4
7f2969185000-7f2969186000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2969186000-7f29692f7000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403445                    /usr/lib/x86_64-linux-gnu/libopenmpt.so.0.1.1
7f29692f7000-7f29694f7000 ---p 00171000 103:09 403445                    /usr/lib/x86_64-linux-gnu/libopenmpt.so.0.1.1
7f29694f7000-7f29694fb000 r--p 00171000 103:09 403445                    /usr/lib/x86_64-linux-gnu/libopenmpt.so.0.1.1
7f29694fb000-7f29694fc000 rw-p 00175000 103:09 403445                    /usr/lib/x86_64-linux-gnu/libopenmpt.so.0.1.1
7f29694fc000-7f296954e000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f296954e000-7f29695c0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403447                    /usr/lib/x86_64-linux-gnu/libssh-gcrypt.so.4.5.0
7f29695c0000-7f29697bf000 ---p 00072000 103:09 403447                    /usr/lib/x86_64-linux-gnu/libssh-gcrypt.so.4.5.0
7f29697bf000-7f29697c0000 r--p 00071000 103:09 403447                    /usr/lib/x86_64-linux-gnu/libssh-gcrypt.so.4.5.0
7f29697c0000-7f29697c1000 rw-p 00072000 103:09 403447                    /usr/lib/x86_64-linux-gnu/libssh-gcrypt.so.4.5.0
7f29697c1000-7f2969865000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404811                    /usr/lib/x86_64-linux-gnu/libfreeimage-3.17.0.so
7f2969865000-7f2969a64000 ---p 000a4000 103:09 404811                    /usr/lib/x86_64-linux-gnu/libfreeimage-3.17.0.so
7f2969a64000-7f2969a67000 r--p 000a3000 103:09 404811                    /usr/lib/x86_64-linux-gnu/libfreeimage-3.17.0.so
7f2969a67000-7f2969a71000 rw-p 000a6000 103:09 404811                    /usr/lib/x86_64-linux-gnu/libfreeimage-3.17.0.so
7f2969a71000-7f2969acd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404813                    /usr/lib/x86_64-linux-gnu/libgts-0.7.so.5.0.1
7f2969acd000-7f2969ccc000 ---p 0005c000 103:09 404813                    /usr/lib/x86_64-linux-gnu/libgts-0.7.so.5.0.1
7f2969ccc000-7f2969ccd000 r--p 0005b000 103:09 404813                    /usr/lib/x86_64-linux-gnu/libgts-0.7.so.5.0.1
7f2969ccd000-7f2969cce000 rw-p 0005c000 103:09 404813                    /usr/lib/x86_64-linux-gnu/libgts-0.7.so.5.0.1
7f2969cce000-7f2969d35000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403407                    /usr/lib/x86_64-linux-gnu/libavutil.so.55.78.100
7f2969d35000-7f2969f34000 ---p 00067000 103:09 403407                    /usr/lib/x86_64-linux-gnu/libavutil.so.55.78.100
7f2969f34000-7f2969f46000 r--p 00066000 103:09 403407                    /usr/lib/x86_64-linux-gnu/libavutil.so.55.78.100
7f2969f46000-7f2969f47000 rw-p 00078000 103:09 403407                    /usr/lib/x86_64-linux-gnu/libavutil.so.55.78.100
7f2969f47000-7f2969f5a000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2969f5a000-7f296ac00000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403431                    /usr/lib/x86_64-linux-gnu/libavcodec.so.57.107.100
7f296ac00000-7f296ae00000 ---p 00ca6000 103:09 403431                    /usr/lib/x86_64-linux-gnu/libavcodec.so.57.107.100
7f296ae00000-7f296ae3b000 r--p 00ca6000 103:09 403431                    /usr/lib/x86_64-linux-gnu/libavcodec.so.57.107.100
7f296ae3b000-7f296ae68000 rw-p 00ce1000 103:09 403431                    /usr/lib/x86_64-linux-gnu/libavcodec.so.57.107.100
7f296ae68000-7f296b67b000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f296b67b000-7f296b8a2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403451                    /usr/lib/x86_64-linux-gnu/libavformat.so.57.83.100
7f296b8a2000-7f296baa2000 ---p 00227000 103:09 403451                    /usr/lib/x86_64-linux-gnu/libavformat.so.57.83.100
7f296baa2000-7f296babc000 r--p 00227000 103:09 403451                    /usr/lib/x86_64-linux-gnu/libavformat.so.57.83.100
7f296babc000-7f296bad3000 rw-p 00241000 103:09 403451                    /usr/lib/x86_64-linux-gnu/libavformat.so.57.83.100
7f296bad3000-7f296bb58000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403616                    /usr/lib/x86_64-linux-gnu/libswscale.so.4.8.100
7f296bb58000-7f296bd58000 ---p 00085000 103:09 403616                    /usr/lib/x86_64-linux-gnu/libswscale.so.4.8.100
7f296bd58000-7f296bd59000 r--p 00085000 103:09 403616                    /usr/lib/x86_64-linux-gnu/libswscale.so.4.8.100
7f296bd59000-7f296bd5a000 rw-p 00086000 103:09 403616                    /usr/lib/x86_64-linux-gnu/libswscale.so.4.8.100
7f296bd5a000-7f296bd62000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f296bd62000-7f296bdfd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398970                    /usr/lib/x86_64-linux-gnu/libignition-common3-graphics.so.3.3.0
7f296bdfd000-7f296bffd000 ---p 0009b000 103:09 398970                    /usr/lib/x86_64-linux-gnu/libignition-common3-graphics.so.3.3.0
7f296bffd000-7f296bffe000 r--p 0009b000 103:09 398970                    /usr/lib/x86_64-linux-gnu/libignition-common3-graphics.so.3.3.0
7f296bffe000-7f296bfff000 rw-p 0009c000 103:09 398970                    /usr/lib/x86_64-linux-gnu/libignition-common3-graphics.so.3.3.0
7f296bfff000-7f296c000000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f296c000000-7f296c021000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f296c021000-7f2970000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2970000000-7f2970001000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4140                       /i915 (deleted)
7f2970001000-7f2970002000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 4173                       /i915 (deleted)
7f2970002000-7f2970007000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 3918                       /i915 (deleted)
7f2970007000-7f297000b000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 1390                       /i915 (deleted)
7f297000b000-7f2970059000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403439                    /usr/lib/x86_64-linux-gnu/libbluray.so.2.0.2
7f2970059000-7f2970258000 ---p 0004e000 103:09 403439                    /usr/lib/x86_64-linux-gnu/libbluray.so.2.0.2
7f2970258000-7f297025a000 r--p 0004d000 103:09 403439                    /usr/lib/x86_64-linux-gnu/libbluray.so.2.0.2
7f297025a000-7f297025b000 rw-p 0004f000 103:09 403439                    /usr/lib/x86_64-linux-gnu/libbluray.so.2.0.2
7f297025b000-7f2970263000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398627                    /usr/lib/x86_64-linux-gnu/libignition-common3-av.so.3.3.0
7f2970263000-7f2970463000 ---p 00008000 103:09 398627                    /usr/lib/x86_64-linux-gnu/libignition-common3-av.so.3.3.0
7f2970463000-7f2970464000 r--p 00008000 103:09 398627                    /usr/lib/x86_64-linux-gnu/libignition-common3-av.so.3.3.0
7f2970464000-7f2970465000 rw-p 00009000 103:09 398627                    /usr/lib/x86_64-linux-gnu/libignition-common3-av.so.3.3.0
7f2970465000-7f2970467000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2970467000-7f29704b2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398982                    /usr/lib/x86_64-linux-gnu/libignition-rendering2.so.2.1.2
7f29704b2000-7f29706b1000 ---p 0004b000 103:09 398982                    /usr/lib/x86_64-linux-gnu/libignition-rendering2.so.2.1.2
7f29706b1000-7f29706b4000 r--p 0004a000 103:09 398982                    /usr/lib/x86_64-linux-gnu/libignition-rendering2.so.2.1.2
7f29706b4000-7f29706b5000 rw-p 0004d000 103:09 398982                    /usr/lib/x86_64-linux-gnu/libignition-rendering2.so.2.1.2
7f29706b5000-7f2970726000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399055                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-rendering.so.2.11.0
7f2970726000-7f2970925000 ---p 00071000 103:09 399055                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-rendering.so.2.11.0
7f2970925000-7f2970928000 r--p 00070000 103:09 399055                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-rendering.so.2.11.0
7f2970928000-7f2970929000 rw-p 00073000 103:09 399055                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-rendering.so.2.11.0
7f2970929000-7f297096d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 952667                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/libGzScene3D.so
7f297096d000-7f2970b6c000 ---p 00044000 103:09 952667                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/libGzScene3D.so
7f2970b6c000-7f2970b6e000 r--p 00043000 103:09 952667                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/libGzScene3D.so
7f2970b6e000-7f2970b6f000 rw-p 00045000 103:09 952667                    /usr/lib/x86_64-linux-gnu/ign-gazebo-2/plugins/gui/libGzScene3D.so
7f2970b6f000-7f2970c28000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1312047                   /usr/share/fonts/truetype/dejavu/DejaVuSans.ttf
7f2970c28000-7f2970c7a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400551                    /usr/lib/x86_64-linux-gnu/libQt5Svg.so.5.9.5
7f2970c7a000-7f2970e7a000 ---p 00052000 103:09 400551                    /usr/lib/x86_64-linux-gnu/libQt5Svg.so.5.9.5
7f2970e7a000-7f2970e7c000 r--p 00052000 103:09 400551                    /usr/lib/x86_64-linux-gnu/libQt5Svg.so.5.9.5
7f2970e7c000-7f2970e7d000 rw-p 00054000 103:09 400551                    /usr/lib/x86_64-linux-gnu/libQt5Svg.so.5.9.5
7f2970e7d000-7f2970e81000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525565                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqsvg.so
7f2970e81000-7f2971081000 ---p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 525565                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqsvg.so
7f2971081000-7f2971082000 r--p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 525565                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqsvg.so
7f2971082000-7f2971083000 rw-p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 525565                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqsvg.so
7f2971083000-7f29710ea000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401960                    /usr/lib/x86_64-linux-gnu/libjpeg.so.8.1.2
7f29710ea000-7f29712e9000 ---p 00067000 103:09 401960                    /usr/lib/x86_64-linux-gnu/libjpeg.so.8.1.2
7f29712e9000-7f29712ea000 r--p 00066000 103:09 401960                    /usr/lib/x86_64-linux-gnu/libjpeg.so.8.1.2
7f29712ea000-7f29712eb000 rw-p 00067000 103:09 401960                    /usr/lib/x86_64-linux-gnu/libjpeg.so.8.1.2
7f29712eb000-7f29712ec000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:05 1947471                    /memfd:xshmfence (deleted)
7f29712ec000-7f29712ed000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:05 1955871                    /memfd:xshmfence (deleted)
7f29712ed000-7f29712f3000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29712f3000-7f29712f5000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9738929                   /home/jaeyoung/.cache/qmlcache/d7710ab4e5f47903fd5c7391ca229c4f4f7665d3.qmlc
7f29712f5000-7f29712f7000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:0a 9738929                   /home/jaeyoung/.cache/qmlcache/d7710ab4e5f47903fd5c7391ca229c4f4f7665d3.qmlc
7f29712f7000-7f29712ff000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29712ff000-7f2971300000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553686                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ToolTip.qmlc
7f2971300000-7f2971303000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 553686                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ToolTip.qmlc
7f2971303000-7f2971308000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714808                   /home/jaeyoung/.cache/qmlcache/a53a39f93417887b65f8457aef21f7c6ec8a194a.qmlc
7f2971308000-7f297130e000 r-xs 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:0a 9714808                   /home/jaeyoung/.cache/qmlcache/a53a39f93417887b65f8457aef21f7c6ec8a194a.qmlc
7f297130e000-7f2971316000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2971316000-7f2971317000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537745                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/RoundButton.qmlc
7f2971317000-7f297131b000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537745                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/RoundButton.qmlc
7f297131b000-7f297131c000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537731                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Popup.qmlc
7f297131c000-7f297131f000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537731                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Popup.qmlc
7f297131f000-7f2971321000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714806                   /home/jaeyoung/.cache/qmlcache/9bb9e5306fcdb065f711cabd15d59083d227888e.qmlc
7f2971321000-7f2971325000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:0a 9714806                   /home/jaeyoung/.cache/qmlcache/9bb9e5306fcdb065f711cabd15d59083d227888e.qmlc
7f2971325000-7f297132a000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297132a000-7f297132b000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553670                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/SwitchIndicator.qmlc
7f297132b000-7f297132d000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 553670                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/SwitchIndicator.qmlc
7f297132d000-7f2971330000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525836                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/SpinBoxStyle.qmlc
7f2971330000-7f2971335000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:09 525836                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/SpinBoxStyle.qmlc
7f2971335000-7f297133e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 529845                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqjpeg.so
7f297133e000-7f297153e000 ---p 00009000 103:09 529845                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqjpeg.so
7f297153e000-7f297153f000 r--p 00009000 103:09 529845                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqjpeg.so
7f297153f000-7f2971540000 rw-p 0000a000 103:09 529845                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqjpeg.so
7f2971540000-7f2971546000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 529844                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqico.so
7f2971546000-7f2971746000 ---p 00006000 103:09 529844                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqico.so
7f2971746000-7f2971747000 r--p 00006000 103:09 529844                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqico.so
7f2971747000-7f2971748000 rw-p 00007000 103:09 529844                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqico.so
7f2971748000-7f297174e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 529842                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqgif.so
7f297174e000-7f297194e000 ---p 00006000 103:09 529842                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqgif.so
7f297194e000-7f297194f000 r--p 00006000 103:09 529842                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqgif.so
7f297194f000-7f2971950000 rw-p 00007000 103:09 529842                    /usr/lib/x86_64-linux-gnu/qt5/plugins/imageformats/libqgif.so
7f2971950000-7f2971951000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2971951000-7f2971952000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553666                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Switch.qmlc
7f2971952000-7f2971956000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 553666                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Switch.qmlc
7f2971956000-7f297195b000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525771                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/SpinBox.qmlc
7f297195b000-7f2971963000 r-xs 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 525771                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/SpinBox.qmlc
7f2971963000-7f2971964000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714800                   /home/jaeyoung/.cache/qmlcache/137f4566d87be6403a6f5b0a5c76b218be3dad45.qmlc
7f2971964000-7f2971967000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714804                   /home/jaeyoung/.cache/qmlcache/de8ac8f4aa01277c3c74f7a7fe1beab9c419d870.qmlc
7f2971967000-7f297196b000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:0a 9714804                   /home/jaeyoung/.cache/qmlcache/de8ac8f4aa01277c3c74f7a7fe1beab9c419d870.qmlc
7f297196b000-7f297196e000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537729                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Pane.qmlc
7f297196e000-7f2971970000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714803                   /home/jaeyoung/.cache/qmlcache/cf8d623f527b0eab66190dd2231fb4671b7c0d90.qmlc
7f2971970000-7f2971976000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:0a 9714803                   /home/jaeyoung/.cache/qmlcache/cf8d623f527b0eab66190dd2231fb4671b7c0d90.qmlc
7f2971976000-7f297197b000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714805                   /home/jaeyoung/.cache/qmlcache/a3220b3a91a4ae408063eb6408bd1d687fb9a6c2.qmlc
7f297197b000-7f2971984000 r-xs 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:0a 9714805                   /home/jaeyoung/.cache/qmlcache/a3220b3a91a4ae408063eb6408bd1d687fb9a6c2.qmlc
7f2971984000-7f2971985000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525616                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/GammaAdjust.qmlc
7f2971985000-7f2971986000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525616                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtGraphicalEffects/GammaAdjust.qmlc
7f2971986000-7f29719a9000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 786499                    /usr/share/mime/mime.cache
7f29719a9000-7f29719fd000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1312231                   /usr/share/fonts/truetype/ubuntu/Ubuntu-M.ttf
7f29719fd000-7f29719fe000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29719fe000-7f29721fe000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29721fe000-7f297233f000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9699342                   /home/jaeyoung/.cache/mesa_shader_cache/index
7f297233f000-7f2972347000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402135                    /usr/lib/x86_64-linux-gnu/libpciaccess.so.0.11.1
7f2972347000-7f2972546000 ---p 00008000 103:09 402135                    /usr/lib/x86_64-linux-gnu/libpciaccess.so.0.11.1
7f2972546000-7f2972547000 r--p 00007000 103:09 402135                    /usr/lib/x86_64-linux-gnu/libpciaccess.so.0.11.1
7f2972547000-7f2972548000 rw-p 00008000 103:09 402135                    /usr/lib/x86_64-linux-gnu/libpciaccess.so.0.11.1
7f2972548000-7f2972553000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400713                    /usr/lib/x86_64-linux-gnu/libdrm_radeon.so.1.0.1
7f2972553000-7f2972752000 ---p 0000b000 103:09 400713                    /usr/lib/x86_64-linux-gnu/libdrm_radeon.so.1.0.1
7f2972752000-7f2972753000 r--p 0000a000 103:09 400713                    /usr/lib/x86_64-linux-gnu/libdrm_radeon.so.1.0.1
7f2972753000-7f2972754000 rw-p 0000b000 103:09 400713                    /usr/lib/x86_64-linux-gnu/libdrm_radeon.so.1.0.1
7f2972754000-7f297275b000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400722                    /usr/lib/x86_64-linux-gnu/libdrm_nouveau.so.2.0.0
7f297275b000-7f297295a000 ---p 00007000 103:09 400722                    /usr/lib/x86_64-linux-gnu/libdrm_nouveau.so.2.0.0
7f297295a000-7f297295b000 r--p 00006000 103:09 400722                    /usr/lib/x86_64-linux-gnu/libdrm_nouveau.so.2.0.0
7f297295b000-7f297295c000 rw-p 00007000 103:09 400722                    /usr/lib/x86_64-linux-gnu/libdrm_nouveau.so.2.0.0
7f297295c000-7f297297e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400707                    /usr/lib/x86_64-linux-gnu/libdrm_intel.so.1.0.0
7f297297e000-7f2972b7d000 ---p 00022000 103:09 400707                    /usr/lib/x86_64-linux-gnu/libdrm_intel.so.1.0.0
7f2972b7d000-7f2972b7e000 r--p 00021000 103:09 400707                    /usr/lib/x86_64-linux-gnu/libdrm_intel.so.1.0.0
7f2972b7e000-7f2972b7f000 rw-p 00022000 103:09 400707                    /usr/lib/x86_64-linux-gnu/libdrm_intel.so.1.0.0
7f2972b7f000-7f2973498000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 656527                    /usr/lib/x86_64-linux-gnu/dri/i965_dri.so
7f2973498000-7f2973698000 ---p 00919000 103:09 656527                    /usr/lib/x86_64-linux-gnu/dri/i965_dri.so
7f2973698000-7f29736f5000 r--p 00919000 103:09 656527                    /usr/lib/x86_64-linux-gnu/dri/i965_dri.so
7f29736f5000-7f2973701000 rw-p 00976000 103:09 656527                    /usr/lib/x86_64-linux-gnu/dri/i965_dri.so
7f2973701000-7f29737b3000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29737b3000-7f29737c3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400703                    /usr/lib/x86_64-linux-gnu/libdrm.so.2.4.0
7f29737c3000-7f29739c2000 ---p 00010000 103:09 400703                    /usr/lib/x86_64-linux-gnu/libdrm.so.2.4.0
7f29739c2000-7f29739c3000 r--p 0000f000 103:09 400703                    /usr/lib/x86_64-linux-gnu/libdrm.so.2.4.0
7f29739c3000-7f29739c4000 rw-p 00010000 103:09 400703                    /usr/lib/x86_64-linux-gnu/libdrm.so.2.4.0
7f29739c4000-7f29739c9000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401338                    /usr/lib/x86_64-linux-gnu/libXxf86vm.so.1.0.0
7f29739c9000-7f2973bc8000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401338                    /usr/lib/x86_64-linux-gnu/libXxf86vm.so.1.0.0
7f2973bc8000-7f2973bc9000 r--p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 401338                    /usr/lib/x86_64-linux-gnu/libXxf86vm.so.1.0.0
7f2973bc9000-7f2973bca000 rw-p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401338                    /usr/lib/x86_64-linux-gnu/libXxf86vm.so.1.0.0
7f2973bca000-7f2973bce000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400845                    /usr/lib/x86_64-linux-gnu/libxcb-dri2.so.0.0.0
7f2973bce000-7f2973dcd000 ---p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 400845                    /usr/lib/x86_64-linux-gnu/libxcb-dri2.so.0.0.0
7f2973dcd000-7f2973dce000 r--p d72edde1b5da441a550262cce0ea172460bf453d 103:09 400845                    /usr/lib/x86_64-linux-gnu/libxcb-dri2.so.0.0.0
7f2973dce000-7f2973dcf000 rw-p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 400845                    /usr/lib/x86_64-linux-gnu/libxcb-dri2.so.0.0.0
7f2973dcf000-7f2973dfb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401729                    /usr/lib/x86_64-linux-gnu/libglapi.so.0.0.0
7f2973dfb000-7f2973ffa000 ---p 0002c000 103:09 401729                    /usr/lib/x86_64-linux-gnu/libglapi.so.0.0.0
7f2973ffa000-7f2973ffe000 r--p 0002b000 103:09 401729                    /usr/lib/x86_64-linux-gnu/libglapi.so.0.0.0
7f2973ffe000-7f2973fff000 rw-p 0002f000 103:09 401729                    /usr/lib/x86_64-linux-gnu/libglapi.so.0.0.0
7f2973fff000-7f2974000000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2974000000-7f29743eb000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29743eb000-7f2978000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2978000000-7f2978003000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9738927                   /home/jaeyoung/.cache/qmlcache/ef22720b2a2917e83574c509c059bd9eb7b57162.qmlc
7f2978003000-7f2978004000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714801                   /home/jaeyoung/.cache/qmlcache/96d4f30dfcadbda886f9274fe316bd75ae1e19f0.qmlc
7f2978004000-7f2978006000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:0a 9714801                   /home/jaeyoung/.cache/qmlcache/96d4f30dfcadbda886f9274fe316bd75ae1e19f0.qmlc
7f2978006000-7f2978019000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2978019000-7f297801a000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9738937                   /home/jaeyoung/.cache/qmlcache/60c9053864f56027de3e793e7dafd8f337e1f0dc.qmlc
7f297801a000-7f297801d000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:0a 9738937                   /home/jaeyoung/.cache/qmlcache/60c9053864f56027de3e793e7dafd8f337e1f0dc.qmlc
7f297801d000-7f297801e000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9965301                   /home/jaeyoung/.local/share/mime/mime.cache
7f297801e000-7f2978022000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2978022000-7f2978025000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525714                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/EditMenu_base.qmlc
7f2978025000-7f2978029000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:09 525714                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/EditMenu_base.qmlc
7f2978029000-7f297802b000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525787                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/BasicTableViewStyle.qmlc
7f297802b000-7f297802f000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525787                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/BasicTableViewStyle.qmlc
7f297802f000-7f2978036000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525832                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/ScrollViewStyle.qmlc
7f2978036000-7f2978045000 r-xs 00007000 103:09 525832                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/ScrollViewStyle.qmlc
7f2978045000-7f297809c000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1312233                   /usr/share/fonts/truetype/ubuntu/Ubuntu-R.ttf
7f297809c000-7f297809d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402518                    /usr/lib/x86_64-linux-gnu/libxshmfence.so.1.0.0
7f297809d000-7f297829c000 ---p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 402518                    /usr/lib/x86_64-linux-gnu/libxshmfence.so.1.0.0
7f297829c000-7f297829d000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402518                    /usr/lib/x86_64-linux-gnu/libxshmfence.so.1.0.0
7f297829d000-7f297829e000 rw-p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 402518                    /usr/lib/x86_64-linux-gnu/libxshmfence.so.1.0.0
7f297829e000-7f29782a0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400816                    /usr/lib/x86_64-linux-gnu/libxcb-present.so.0.0.0
7f29782a0000-7f297849f000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 400816                    /usr/lib/x86_64-linux-gnu/libxcb-present.so.0.0.0
7f297849f000-7f29784a0000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 400816                    /usr/lib/x86_64-linux-gnu/libxcb-present.so.0.0.0
7f29784a0000-7f29784a1000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 400816                    /usr/lib/x86_64-linux-gnu/libxcb-present.so.0.0.0
7f29784a1000-7f29784a4000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400806                    /usr/lib/x86_64-linux-gnu/libxcb-dri3.so.0.0.0
7f29784a4000-7f29786a3000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 400806                    /usr/lib/x86_64-linux-gnu/libxcb-dri3.so.0.0.0
7f29786a3000-7f29786a4000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 400806                    /usr/lib/x86_64-linux-gnu/libxcb-dri3.so.0.0.0
7f29786a4000-7f29786a5000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 400806                    /usr/lib/x86_64-linux-gnu/libxcb-dri3.so.0.0.0
7f29786a5000-7f2978717000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401247                    /usr/lib/x86_64-linux-gnu/libGLX_mesa.so.0.0.0
7f2978717000-7f2978916000 ---p 00072000 103:09 401247                    /usr/lib/x86_64-linux-gnu/libGLX_mesa.so.0.0.0
7f2978916000-7f2978919000 r--p 00071000 103:09 401247                    /usr/lib/x86_64-linux-gnu/libGLX_mesa.so.0.0.0
7f2978919000-7f297891a000 rw-p 00074000 103:09 401247                    /usr/lib/x86_64-linux-gnu/libGLX_mesa.so.0.0.0
7f297891a000-7f297891b000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297891b000-7f2978971000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537462                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Templates.2/libqtquicktemplates2plugin.so
7f2978971000-7f2978b71000 ---p 00056000 103:09 537462                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Templates.2/libqtquicktemplates2plugin.so
7f2978b71000-7f2978b79000 r--p 00056000 103:09 537462                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Templates.2/libqtquicktemplates2plugin.so
7f2978b79000-7f2978b7a000 rw-p 0005e000 103:09 537462                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Templates.2/libqtquicktemplates2plugin.so
7f2978b7a000-7f2978b80000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554112                    /usr/lib/x86_64-linux-gnu/qt5/qml/Qt/labs/settings/libqmlsettingsplugin.so
7f2978b80000-7f2978d7f000 ---p 00006000 103:09 554112                    /usr/lib/x86_64-linux-gnu/qt5/qml/Qt/labs/settings/libqmlsettingsplugin.so
7f2978d7f000-7f2978d80000 r--p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 554112                    /usr/lib/x86_64-linux-gnu/qt5/qml/Qt/labs/settings/libqmlsettingsplugin.so
7f2978d80000-7f2978d81000 rw-p 00006000 103:09 554112                    /usr/lib/x86_64-linux-gnu/qt5/qml/Qt/labs/settings/libqmlsettingsplugin.so
7f2978d81000-7f2978d90000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554109                    /usr/lib/x86_64-linux-gnu/qt5/qml/Qt/labs/folderlistmodel/libqmlfolderlistmodelplugin.so
7f2978d90000-7f2978f90000 ---p 0000f000 103:09 554109                    /usr/lib/x86_64-linux-gnu/qt5/qml/Qt/labs/folderlistmodel/libqmlfolderlistmodelplugin.so
7f2978f90000-7f2978f91000 r--p 0000f000 103:09 554109                    /usr/lib/x86_64-linux-gnu/qt5/qml/Qt/labs/folderlistmodel/libqmlfolderlistmodelplugin.so
7f2978f91000-7f2978f92000 rw-p 00010000 103:09 554109                    /usr/lib/x86_64-linux-gnu/qt5/qml/Qt/labs/folderlistmodel/libqmlfolderlistmodelplugin.so
7f2978f92000-7f2978f94000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525587                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Window.2/libwindowplugin.so
7f2978f94000-7f2979193000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525587                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Window.2/libwindowplugin.so
7f2979193000-7f2979194000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525587                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Window.2/libwindowplugin.so
7f2979194000-7f2979195000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525587                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Window.2/libwindowplugin.so
7f2979195000-7f29791a0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554074                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/Private/libdialogsprivateplugin.so
7f29791a0000-7f29793a0000 ---p 0000b000 103:09 554074                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/Private/libdialogsprivateplugin.so
7f29793a0000-7f29793a1000 r--p 0000b000 103:09 554074                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/Private/libdialogsprivateplugin.so
7f29793a1000-7f29793a2000 rw-p 0000c000 103:09 554074                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/Private/libdialogsprivateplugin.so
7f29793a2000-7f29799b8000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398892                    /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5.9.5
7f29799b8000-7f2979bb7000 ---p 00616000 103:09 398892                    /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5.9.5
7f2979bb7000-7f2979be4000 r--p 00615000 103:09 398892                    /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5.9.5
7f2979be4000-7f2979be9000 rw-p 00642000 103:09 398892                    /usr/lib/x86_64-linux-gnu/libQt5Widgets.so.5.9.5
7f2979be9000-7f2979c51000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 530325                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/libqtquickcontrolsplugin.so
7f2979c51000-7f2979e51000 ---p 00068000 103:09 530325                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/libqtquickcontrolsplugin.so
7f2979e51000-7f2979e55000 r--p 00068000 103:09 530325                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/libqtquickcontrolsplugin.so
7f2979e55000-7f2979e56000 rw-p 0006c000 103:09 530325                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/libqtquickcontrolsplugin.so
7f2979e56000-7f2979e57000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2979e57000-7f2979e73000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525670                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Layouts/libqquicklayoutsplugin.so
7f2979e73000-7f297a073000 ---p 0001c000 103:09 525670                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Layouts/libqquicklayoutsplugin.so
7f297a073000-7f297a076000 r--p 0001c000 103:09 525670                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Layouts/libqquicklayoutsplugin.so
7f297a076000-7f297a077000 rw-p 0001f000 103:09 525670                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Layouts/libqquicklayoutsplugin.so
7f297a077000-7f297a09e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554096                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/libdialogplugin.so
7f297a09e000-7f297a29d000 ---p 00027000 103:09 554096                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/libdialogplugin.so
7f297a29d000-7f297a29f000 r--p 00026000 103:09 554096                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/libdialogplugin.so
7f297a29f000-7f297a2a0000 rw-p 00028000 103:09 554096                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/libdialogplugin.so
7f297a2a0000-7f297a2bd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553689                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/libqtquickcontrols2materialstyleplugin.so
7f297a2bd000-7f297a4bd000 ---p 0001d000 103:09 553689                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/libqtquickcontrols2materialstyleplugin.so
7f297a4bd000-7f297a4bf000 r--p 0001d000 103:09 553689                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/libqtquickcontrols2materialstyleplugin.so
7f297a4bf000-7f297a4c0000 rw-p 0001f000 103:09 553689                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/libqtquickcontrols2materialstyleplugin.so
7f297a4c0000-7f297a5b0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398660                    /usr/lib/x86_64-linux-gnu/libQt5QuickTemplates2.so.5.9.5
7f297a5b0000-7f297a7af000 ---p 000f0000 103:09 398660                    /usr/lib/x86_64-linux-gnu/libQt5QuickTemplates2.so.5.9.5
7f297a7af000-7f297a7bd000 r--p 000ef000 103:09 398660                    /usr/lib/x86_64-linux-gnu/libQt5QuickTemplates2.so.5.9.5
7f297a7bd000-7f297a7bf000 rw-p 000fd000 103:09 398660                    /usr/lib/x86_64-linux-gnu/libQt5QuickTemplates2.so.5.9.5
7f297a7bf000-7f297a7de000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398663                    /usr/lib/x86_64-linux-gnu/libQt5QuickControls2.so.5.9.5
7f297a7de000-7f297a9dd000 ---p 0001f000 103:09 398663                    /usr/lib/x86_64-linux-gnu/libQt5QuickControls2.so.5.9.5
7f297a9dd000-7f297a9df000 r--p 0001e000 103:09 398663                    /usr/lib/x86_64-linux-gnu/libQt5QuickControls2.so.5.9.5
7f297a9df000-7f297a9e0000 rw-p 00020000 103:09 398663                    /usr/lib/x86_64-linux-gnu/libQt5QuickControls2.so.5.9.5
7f297a9e0000-7f297a9fc000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554058                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/libqtquickcontrols2plugin.so
7f297a9fc000-7f297abfc000 ---p 0001c000 103:09 554058                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/libqtquickcontrols2plugin.so
7f297abfc000-7f297abfe000 r--p 0001c000 103:09 554058                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/libqtquickcontrols2plugin.so
7f297abfe000-7f297abff000 rw-p 0001e000 103:09 554058                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/libqtquickcontrols2plugin.so
7f297abff000-7f297ac00000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297ac00000-7f297b3fe000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297b3fe000-7f297b3ff000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297b3ff000-7f297b400000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297b400000-7f297b7f0000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297b7f0000-7f297b7ff000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297b7ff000-7f297b800000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297b800000-7f297c000000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297c000000-7f297c021000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f297c021000-7f2980000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2980000000-7f2980021000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2980021000-7f2984000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2984000000-7f2984021000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2984021000-7f2988000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2988000000-7f2988003000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2988003000-7f2988004000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525812                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/FocusFrameStyle.qmlc
7f2988004000-7f2988005000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525846                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/TableViewStyle.qmlc
7f2988005000-7f2988007000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525855                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/ToolBarStyle.qmlc
7f2988007000-7f2988009000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525850                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/TextFieldStyle.qmlc
7f2988009000-7f298800c000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525850                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/TextFieldStyle.qmlc
7f298800c000-7f298800d000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525726                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/MenuItemSubControls.qmlc
7f298800d000-7f2988013000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525824                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/MenuStyle.qmlc
7f2988013000-7f298801a000 r-xs 00006000 103:09 525824                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/MenuStyle.qmlc
7f298801a000-7f298801f000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525804                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/ComboBoxStyle.qmlc
7f298801f000-7f2988027000 r-xs 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 525804                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/ComboBoxStyle.qmlc
7f2988027000-7f298802e000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298802e000-7f298806e000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9706870                   /home/jaeyoung/#9706870 (deleted)
7f298806e000-7f29880ae000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9706870                   /home/jaeyoung/#9706870 (deleted)
7f29880ae000-7f29880b3000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 1535                       /i915 (deleted)
7f29880b3000-7f29880b4000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29880b4000-7f29880b5000 rwxp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29880b5000-7f29880b9000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 1495                       /i915 (deleted)
7f29880b9000-7f29880bd000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 1443                       /i915 (deleted)
7f29880bd000-7f29880c2000 rw-s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:19 1408                       /i915 (deleted)
7f29880c2000-7f29880c3000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537630                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/CheckIndicator.qmlc
7f29880c3000-7f29880c6000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537630                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/CheckIndicator.qmlc
7f29880c6000-7f29880ca000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537632                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ComboBox.qmlc
7f29880ca000-7f29880d3000 r-xs ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 537632                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ComboBox.qmlc
7f29880d3000-7f29880d4000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29880d4000-7f2988181000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1312046                   /usr/share/fonts/truetype/dejavu/DejaVuSans-Bold.ttf
7f2988181000-7f2988187000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2988187000-7f298818c000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554106                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/qml/icons.ttf
7f298818c000-7f298818e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525591                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick.2/libqtquick2plugin.so
7f298818e000-7f298838d000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525591                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick.2/libqtquick2plugin.so
7f298838d000-7f298838e000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525591                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick.2/libqtquick2plugin.so
7f298838e000-7f298838f000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525591                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick.2/libqtquick2plugin.so
7f298838f000-7f2988390000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2988390000-7f2988b90000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2988b90000-7f2988baa000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 529847                    /usr/lib/x86_64-linux-gnu/qt5/plugins/platforminputcontexts/libibusplatforminputcontextplugin.so
7f2988baa000-7f2988daa000 ---p 0001a000 103:09 529847                    /usr/lib/x86_64-linux-gnu/qt5/plugins/platforminputcontexts/libibusplatforminputcontextplugin.so
7f2988daa000-7f2988dab000 r--p 0001a000 103:09 529847                    /usr/lib/x86_64-linux-gnu/qt5/plugins/platforminputcontexts/libibusplatforminputcontextplugin.so
7f2988dab000-7f2988dac000 rw-p 0001b000 103:09 529847                    /usr/lib/x86_64-linux-gnu/qt5/plugins/platforminputcontexts/libibusplatforminputcontextplugin.so
7f2988dac000-7f2988db3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402096                    /usr/lib/x86_64-linux-gnu/libogg.so.0.8.2
7f2988db3000-7f2988fb3000 ---p 00007000 103:09 402096                    /usr/lib/x86_64-linux-gnu/libogg.so.0.8.2
7f2988fb3000-7f2988fb4000 r--p 00007000 103:09 402096                    /usr/lib/x86_64-linux-gnu/libogg.so.0.8.2
7f2988fb4000-7f2988fb5000 rw-p 00008000 103:09 402096                    /usr/lib/x86_64-linux-gnu/libogg.so.0.8.2
7f2988fb5000-7f2988fdf000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402404                    /usr/lib/x86_64-linux-gnu/libvorbis.so.0.4.8
7f2988fdf000-7f29891de000 ---p 0002a000 103:09 402404                    /usr/lib/x86_64-linux-gnu/libvorbis.so.0.4.8
7f29891de000-7f29891df000 r--p 00029000 103:09 402404                    /usr/lib/x86_64-linux-gnu/libvorbis.so.0.4.8
7f29891df000-7f29891e0000 rw-p 0002a000 103:09 402404                    /usr/lib/x86_64-linux-gnu/libvorbis.so.0.4.8
7f29891e0000-7f29891e9000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401995                    /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1
7f29891e9000-7f29893e8000 ---p 00009000 103:09 401995                    /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1
7f29893e8000-7f29893e9000 r--p 00008000 103:09 401995                    /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1
7f29893e9000-7f29893ea000 rw-p 00009000 103:09 401995                    /usr/lib/x86_64-linux-gnu/libltdl.so.7.3.1
7f29893ea000-7f29893ff000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402329                    /usr/lib/x86_64-linux-gnu/libtdb.so.1.3.15
7f29893ff000-7f29895fe000 ---p 00015000 103:09 402329                    /usr/lib/x86_64-linux-gnu/libtdb.so.1.3.15
7f29895fe000-7f29895ff000 r--p 00014000 103:09 402329                    /usr/lib/x86_64-linux-gnu/libtdb.so.1.3.15
7f29895ff000-7f2989600000 rw-p 00015000 103:09 402329                    /usr/lib/x86_64-linux-gnu/libtdb.so.1.3.15
7f2989600000-7f2989607000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402408                    /usr/lib/x86_64-linux-gnu/libvorbisfile.so.3.3.7
7f2989607000-7f2989806000 ---p 00007000 103:09 402408                    /usr/lib/x86_64-linux-gnu/libvorbisfile.so.3.3.7
7f2989806000-7f2989807000 r--p 00006000 103:09 402408                    /usr/lib/x86_64-linux-gnu/libvorbisfile.so.3.3.7
7f2989807000-7f2989808000 rw-p 00007000 103:09 402408                    /usr/lib/x86_64-linux-gnu/libvorbisfile.so.3.3.7
7f2989808000-7f2989818000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401452                    /usr/lib/x86_64-linux-gnu/libcanberra.so.0.2.5
7f2989818000-7f2989a18000 ---p 00010000 103:09 401452                    /usr/lib/x86_64-linux-gnu/libcanberra.so.0.2.5
7f2989a18000-7f2989a19000 r--p 00010000 103:09 401452                    /usr/lib/x86_64-linux-gnu/libcanberra.so.0.2.5
7f2989a19000-7f2989a1a000 rw-p 00011000 103:09 401452                    /usr/lib/x86_64-linux-gnu/libcanberra.so.0.2.5
7f2989a1a000-7f2989a1e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401450                    /usr/lib/x86_64-linux-gnu/libcanberra-gtk3.so.0.1.9
7f2989a1e000-7f2989c1d000 ---p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 401450                    /usr/lib/x86_64-linux-gnu/libcanberra-gtk3.so.0.1.9
7f2989c1d000-7f2989c1e000 r--p d72edde1b5da441a550262cce0ea172460bf453d 103:09 401450                    /usr/lib/x86_64-linux-gnu/libcanberra-gtk3.so.0.1.9
7f2989c1e000-7f2989c1f000 rw-p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 401450                    /usr/lib/x86_64-linux-gnu/libcanberra-gtk3.so.0.1.9
7f2989c1f000-7f2989c24000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 657671                    /usr/lib/x86_64-linux-gnu/gtk-3.0/modules/libcanberra-gtk3-module.so
7f2989c24000-7f2989e24000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 657671                    /usr/lib/x86_64-linux-gnu/gtk-3.0/modules/libcanberra-gtk3-module.so
7f2989e24000-7f2989e25000 r--p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 657671                    /usr/lib/x86_64-linux-gnu/gtk-3.0/modules/libcanberra-gtk3-module.so
7f2989e25000-7f2989e26000 rw-p 00006000 103:09 657671                    /usr/lib/x86_64-linux-gnu/gtk-3.0/modules/libcanberra-gtk3-module.so
7f2989e26000-7f2989e27000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2989e27000-7f298a627000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298a627000-7f298a628000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298a628000-7f298ae28000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298ae28000-7f298ae5e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 655981                    /usr/lib/x86_64-linux-gnu/gvfs/libgvfscommon.so
7f298ae5e000-7f298b05e000 ---p 00036000 103:09 655981                    /usr/lib/x86_64-linux-gnu/gvfs/libgvfscommon.so
7f298b05e000-7f298b064000 r--p 00036000 103:09 655981                    /usr/lib/x86_64-linux-gnu/gvfs/libgvfscommon.so
7f298b064000-7f298b065000 rw-p 0003c000 103:09 655981                    /usr/lib/x86_64-linux-gnu/gvfs/libgvfscommon.so
7f298b065000-7f298b096000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 666218                    /usr/lib/x86_64-linux-gnu/gio/modules/libgvfsdbus.so
7f298b096000-7f298b296000 ---p 00031000 103:09 666218                    /usr/lib/x86_64-linux-gnu/gio/modules/libgvfsdbus.so
7f298b296000-7f298b298000 r--p 00031000 103:09 666218                    /usr/lib/x86_64-linux-gnu/gio/modules/libgvfsdbus.so
7f298b298000-7f298b299000 rw-p 00033000 103:09 666218                    /usr/lib/x86_64-linux-gnu/gio/modules/libgvfsdbus.so
7f298b299000-7f298b2e0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840026                   /lib/x86_64-linux-gnu/libblkid.so.1.1.0
7f298b2e0000-7f298b4e0000 ---p 00047000 103:09 1840026                   /lib/x86_64-linux-gnu/libblkid.so.1.1.0
7f298b4e0000-7f298b4e4000 r--p 00047000 103:09 1840026                   /lib/x86_64-linux-gnu/libblkid.so.1.1.0
7f298b4e4000-7f298b4e5000 rw-p 0004b000 103:09 1840026                   /lib/x86_64-linux-gnu/libblkid.so.1.1.0
7f298b4e5000-7f298b4e6000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298b4e6000-7f298b4ec000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401523                    /usr/lib/x86_64-linux-gnu/libdatrie.so.1.3.3
7f298b4ec000-7f298b6eb000 ---p 00006000 103:09 401523                    /usr/lib/x86_64-linux-gnu/libdatrie.so.1.3.3
7f298b6eb000-7f298b6ec000 r--p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401523                    /usr/lib/x86_64-linux-gnu/libdatrie.so.1.3.3
7f298b6ec000-7f298b6ed000 rw-p 00006000 103:09 401523                    /usr/lib/x86_64-linux-gnu/libdatrie.so.1.3.3
7f298b6ed000-7f298b73e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840103                   /lib/x86_64-linux-gnu/libmount.so.1.1.0
7f298b73e000-7f298b93d000 ---p 00051000 103:09 1840103                   /lib/x86_64-linux-gnu/libmount.so.1.1.0
7f298b93d000-7f298b93f000 r--p 00050000 103:09 1840103                   /lib/x86_64-linux-gnu/libmount.so.1.1.0
7f298b93f000-7f298b940000 rw-p 00052000 103:09 1840103                   /lib/x86_64-linux-gnu/libmount.so.1.1.0
7f298b940000-7f298b941000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298b941000-7f298b966000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840179                   /lib/x86_64-linux-gnu/libselinux.so.1
7f298b966000-7f298bb65000 ---p 00025000 103:09 1840179                   /lib/x86_64-linux-gnu/libselinux.so.1
7f298bb65000-7f298bb66000 r--p 00024000 103:09 1840179                   /lib/x86_64-linux-gnu/libselinux.so.1
7f298bb66000-7f298bb67000 rw-p 00025000 103:09 1840179                   /lib/x86_64-linux-gnu/libselinux.so.1
7f298bb67000-7f298bb69000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298bb69000-7f298bb95000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401379                    /usr/lib/x86_64-linux-gnu/libatspi.so.0.0.1
7f298bb95000-7f298bd95000 ---p 0002c000 103:09 401379                    /usr/lib/x86_64-linux-gnu/libatspi.so.0.0.1
7f298bd95000-7f298bd98000 r--p 0002c000 103:09 401379                    /usr/lib/x86_64-linux-gnu/libatspi.so.0.0.1
7f298bd98000-7f298bd99000 rw-p 0002f000 103:09 401379                    /usr/lib/x86_64-linux-gnu/libatspi.so.0.0.1
7f298bd99000-7f298be36000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402153                    /usr/lib/x86_64-linux-gnu/libpixman-1.so.0.34.0
7f298be36000-7f298c035000 ---p 0009d000 103:09 402153                    /usr/lib/x86_64-linux-gnu/libpixman-1.so.0.34.0
7f298c035000-7f298c03d000 r--p 0009c000 103:09 402153                    /usr/lib/x86_64-linux-gnu/libpixman-1.so.0.34.0
7f298c03d000-7f298c03e000 rw-p 000a4000 103:09 402153                    /usr/lib/x86_64-linux-gnu/libpixman-1.so.0.34.0
7f298c03e000-7f298c046000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402337                    /usr/lib/x86_64-linux-gnu/libthai.so.0.3.0
7f298c046000-7f298c245000 ---p 00008000 103:09 402337                    /usr/lib/x86_64-linux-gnu/libthai.so.0.3.0
7f298c245000-7f298c246000 r--p 00007000 103:09 402337                    /usr/lib/x86_64-linux-gnu/libthai.so.0.3.0
7f298c246000-7f298c247000 rw-p 00008000 103:09 402337                    /usr/lib/x86_64-linux-gnu/libthai.so.0.3.0
7f298c247000-7f298c254000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402419                    /usr/lib/x86_64-linux-gnu/libwayland-client.so.0.3.0
7f298c254000-7f298c453000 ---p 0000d000 103:09 402419                    /usr/lib/x86_64-linux-gnu/libwayland-client.so.0.3.0
7f298c453000-7f298c455000 r--p 0000c000 103:09 402419                    /usr/lib/x86_64-linux-gnu/libwayland-client.so.0.3.0
7f298c455000-7f298c456000 rw-p 0000e000 103:09 402419                    /usr/lib/x86_64-linux-gnu/libwayland-client.so.0.3.0
7f298c456000-7f298c457000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402423                    /usr/lib/x86_64-linux-gnu/libwayland-egl.so.1.0.0
7f298c457000-7f298c656000 ---p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 402423                    /usr/lib/x86_64-linux-gnu/libwayland-egl.so.1.0.0
7f298c656000-7f298c657000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402423                    /usr/lib/x86_64-linux-gnu/libwayland-egl.so.1.0.0
7f298c657000-7f298c658000 rw-p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 402423                    /usr/lib/x86_64-linux-gnu/libwayland-egl.so.1.0.0
7f298c658000-7f298c65c000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402421                    /usr/lib/x86_64-linux-gnu/libwayland-cursor.so.0.0.0
7f298c65c000-7f298c85b000 ---p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 402421                    /usr/lib/x86_64-linux-gnu/libwayland-cursor.so.0.0.0
7f298c85b000-7f298c85c000 r--p d72edde1b5da441a550262cce0ea172460bf453d 103:09 402421                    /usr/lib/x86_64-linux-gnu/libwayland-cursor.so.0.0.0
7f298c85c000-7f298c860000 rw-p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 402421                    /usr/lib/x86_64-linux-gnu/libwayland-cursor.so.0.0.0
7f298c860000-7f298c862000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401298                    /usr/lib/x86_64-linux-gnu/libXdamage.so.1.1.0
7f298c862000-7f298ca61000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 401298                    /usr/lib/x86_64-linux-gnu/libXdamage.so.1.1.0
7f298ca61000-7f298ca62000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 401298                    /usr/lib/x86_64-linux-gnu/libXdamage.so.1.1.0
7f298ca62000-7f298ca63000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 401298                    /usr/lib/x86_64-linux-gnu/libXdamage.so.1.1.0
7f298ca63000-7f298ca65000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401294                    /usr/lib/x86_64-linux-gnu/libXcomposite.so.1.0.0
7f298ca65000-7f298cc64000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 401294                    /usr/lib/x86_64-linux-gnu/libXcomposite.so.1.0.0
7f298cc64000-7f298cc65000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 401294                    /usr/lib/x86_64-linux-gnu/libXcomposite.so.1.0.0
7f298cc65000-7f298cc66000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 401294                    /usr/lib/x86_64-linux-gnu/libXcomposite.so.1.0.0
7f298cc66000-7f298cc70000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401320                    /usr/lib/x86_64-linux-gnu/libXrandr.so.2.2.0
7f298cc70000-7f298ce6f000 ---p 0000a000 103:09 401320                    /usr/lib/x86_64-linux-gnu/libXrandr.so.2.2.0
7f298ce6f000-7f298ce70000 r--p 00009000 103:09 401320                    /usr/lib/x86_64-linux-gnu/libXrandr.so.2.2.0
7f298ce70000-7f298ce71000 rw-p 0000a000 103:09 401320                    /usr/lib/x86_64-linux-gnu/libXrandr.so.2.2.0
7f298ce71000-7f298ce73000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401312                    /usr/lib/x86_64-linux-gnu/libXinerama.so.1.0.0
7f298ce73000-7f298d072000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 401312                    /usr/lib/x86_64-linux-gnu/libXinerama.so.1.0.0
7f298d072000-7f298d073000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 401312                    /usr/lib/x86_64-linux-gnu/libXinerama.so.1.0.0
7f298d073000-7f298d074000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 401312                    /usr/lib/x86_64-linux-gnu/libXinerama.so.1.0.0
7f298d074000-7f298d209000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397214                    /usr/lib/x86_64-linux-gnu/libgio-2.0.so.0.5600.4
7f298d209000-7f298d409000 ---p 00195000 103:09 397214                    /usr/lib/x86_64-linux-gnu/libgio-2.0.so.0.5600.4
7f298d409000-7f298d410000 r--p 00195000 103:09 397214                    /usr/lib/x86_64-linux-gnu/libgio-2.0.so.0.5600.4
7f298d410000-7f298d411000 rw-p 0019c000 103:09 397214                    /usr/lib/x86_64-linux-gnu/libgio-2.0.so.0.5600.4
7f298d411000-7f298d413000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298d413000-7f298d427000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402125                    /usr/lib/x86_64-linux-gnu/libpangoft2-1.0.so.0.4000.14
7f298d427000-7f298d627000 ---p 00014000 103:09 402125                    /usr/lib/x86_64-linux-gnu/libpangoft2-1.0.so.0.4000.14
7f298d627000-7f298d628000 r--p 00014000 103:09 402125                    /usr/lib/x86_64-linux-gnu/libpangoft2-1.0.so.0.4000.14
7f298d628000-7f298d629000 rw-p 00015000 103:09 402125                    /usr/lib/x86_64-linux-gnu/libpangoft2-1.0.so.0.4000.14
7f298d629000-7f298d71c000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401605                    /usr/lib/x86_64-linux-gnu/libepoxy.so.0.0.0
7f298d71c000-7f298d91c000 ---p 000f3000 103:09 401605                    /usr/lib/x86_64-linux-gnu/libepoxy.so.0.0.0
7f298d91c000-7f298d923000 r--p 000f3000 103:09 401605                    /usr/lib/x86_64-linux-gnu/libepoxy.so.0.0.0
7f298d923000-7f298d92a000 rw-p 000fa000 103:09 401605                    /usr/lib/x86_64-linux-gnu/libepoxy.so.0.0.0
7f298d92a000-7f298d958000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401377                    /usr/lib/x86_64-linux-gnu/libatk-bridge-2.0.so.0.0.0
7f298d958000-7f298db58000 ---p 0002e000 103:09 401377                    /usr/lib/x86_64-linux-gnu/libatk-bridge-2.0.so.0.0.0
7f298db58000-7f298db59000 r--p 0002e000 103:09 401377                    /usr/lib/x86_64-linux-gnu/libatk-bridge-2.0.so.0.0.0
7f298db59000-7f298db5a000 rw-p 0002f000 103:09 401377                    /usr/lib/x86_64-linux-gnu/libatk-bridge-2.0.so.0.0.0
7f298db5a000-7f298db5b000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298db5b000-7f298db7d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401375                    /usr/lib/x86_64-linux-gnu/libatk-1.0.so.0.22810.1
7f298db7d000-7f298dd7d000 ---p 00022000 103:09 401375                    /usr/lib/x86_64-linux-gnu/libatk-1.0.so.0.22810.1
7f298dd7d000-7f298dd80000 r--p 00022000 103:09 401375                    /usr/lib/x86_64-linux-gnu/libatk-1.0.so.0.22810.1
7f298dd80000-7f298dd81000 rw-p 00025000 103:09 401375                    /usr/lib/x86_64-linux-gnu/libatk-1.0.so.0.22810.1
7f298dd81000-7f298dda3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401707                    /usr/lib/x86_64-linux-gnu/libgdk_pixbuf-2.0.so.0.3611.0
7f298dda3000-7f298dfa3000 ---p 00022000 103:09 401707                    /usr/lib/x86_64-linux-gnu/libgdk_pixbuf-2.0.so.0.3611.0
7f298dfa3000-7f298dfa4000 r--p 00022000 103:09 401707                    /usr/lib/x86_64-linux-gnu/libgdk_pixbuf-2.0.so.0.3611.0
7f298dfa4000-7f298dfa5000 rw-p 00023000 103:09 401707                    /usr/lib/x86_64-linux-gnu/libgdk_pixbuf-2.0.so.0.3611.0
7f298dfa5000-7f298e0bd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401446                    /usr/lib/x86_64-linux-gnu/libcairo.so.2.11510.0
7f298e0bd000-7f298e2bc000 ---p 00118000 103:09 401446                    /usr/lib/x86_64-linux-gnu/libcairo.so.2.11510.0
7f298e2bc000-7f298e2bf000 r--p 00117000 103:09 401446                    /usr/lib/x86_64-linux-gnu/libcairo.so.2.11510.0
7f298e2bf000-7f298e2c1000 rw-p 0011a000 103:09 401446                    /usr/lib/x86_64-linux-gnu/libcairo.so.2.11510.0
7f298e2c1000-7f298e2c2000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298e2c2000-7f298e2c8000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401444                    /usr/lib/x86_64-linux-gnu/libcairo-gobject.so.2.11510.0
7f298e2c8000-7f298e4c8000 ---p 00006000 103:09 401444                    /usr/lib/x86_64-linux-gnu/libcairo-gobject.so.2.11510.0
7f298e4c8000-7f298e4ca000 r--p 00006000 103:09 401444                    /usr/lib/x86_64-linux-gnu/libcairo-gobject.so.2.11510.0
7f298e4ca000-7f298e4cb000 rw-p 00008000 103:09 401444                    /usr/lib/x86_64-linux-gnu/libcairo-gobject.so.2.11510.0
7f298e4cb000-7f298e4d7000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402123                    /usr/lib/x86_64-linux-gnu/libpangocairo-1.0.so.0.4000.14
7f298e4d7000-7f298e6d6000 ---p 0000c000 103:09 402123                    /usr/lib/x86_64-linux-gnu/libpangocairo-1.0.so.0.4000.14
7f298e6d6000-7f298e6d7000 r--p 0000b000 103:09 402123                    /usr/lib/x86_64-linux-gnu/libpangocairo-1.0.so.0.4000.14
7f298e6d7000-7f298e6d8000 rw-p 0000c000 103:09 402123                    /usr/lib/x86_64-linux-gnu/libpangocairo-1.0.so.0.4000.14
7f298e6d8000-7f298e6db000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397217                    /usr/lib/x86_64-linux-gnu/libgmodule-2.0.so.0.5600.4
7f298e6db000-7f298e8da000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 397217                    /usr/lib/x86_64-linux-gnu/libgmodule-2.0.so.0.5600.4
7f298e8da000-7f298e8db000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 397217                    /usr/lib/x86_64-linux-gnu/libgmodule-2.0.so.0.5600.4
7f298e8db000-7f298e8dc000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 397217                    /usr/lib/x86_64-linux-gnu/libgmodule-2.0.so.0.5600.4
7f298e8dc000-7f298e92e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397218                    /usr/lib/x86_64-linux-gnu/libgobject-2.0.so.0.5600.4
7f298e92e000-7f298eb2e000 ---p 00052000 103:09 397218                    /usr/lib/x86_64-linux-gnu/libgobject-2.0.so.0.5600.4
7f298eb2e000-7f298eb2f000 r--p 00052000 103:09 397218                    /usr/lib/x86_64-linux-gnu/libgobject-2.0.so.0.5600.4
7f298eb2f000-7f298eb30000 rw-p 00053000 103:09 397218                    /usr/lib/x86_64-linux-gnu/libgobject-2.0.so.0.5600.4
7f298eb30000-7f298eb7a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402121                    /usr/lib/x86_64-linux-gnu/libpango-1.0.so.0.4000.14
7f298eb7a000-7f298ed79000 ---p 0004a000 103:09 402121                    /usr/lib/x86_64-linux-gnu/libpango-1.0.so.0.4000.14
7f298ed79000-7f298ed7c000 r--p 00049000 103:09 402121                    /usr/lib/x86_64-linux-gnu/libpango-1.0.so.0.4000.14
7f298ed7c000-7f298ed7d000 rw-p 0004c000 103:09 402121                    /usr/lib/x86_64-linux-gnu/libpango-1.0.so.0.4000.14
7f298ed7d000-7f298ee68000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401703                    /usr/lib/x86_64-linux-gnu/libgdk-3.so.0.2200.30
7f298ee68000-7f298f068000 ---p 000eb000 103:09 401703                    /usr/lib/x86_64-linux-gnu/libgdk-3.so.0.2200.30
7f298f068000-7f298f06f000 r--p 000eb000 103:09 401703                    /usr/lib/x86_64-linux-gnu/libgdk-3.so.0.2200.30
7f298f06f000-7f298f072000 rw-p 000f2000 103:09 401703                    /usr/lib/x86_64-linux-gnu/libgdk-3.so.0.2200.30
7f298f072000-7f298f073000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298f073000-7f298f764000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401836                    /usr/lib/x86_64-linux-gnu/libgtk-3.so.0.2200.30
7f298f764000-7f298f963000 ---p 006f1000 103:09 401836                    /usr/lib/x86_64-linux-gnu/libgtk-3.so.0.2200.30
7f298f963000-7f298f96e000 r--p 006f0000 103:09 401836                    /usr/lib/x86_64-linux-gnu/libgtk-3.so.0.2200.30
7f298f96e000-7f298f975000 rw-p 006fb000 103:09 401836                    /usr/lib/x86_64-linux-gnu/libgtk-3.so.0.2200.30
7f298f975000-7f298f97a000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f298f97a000-7f298f9d1000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1049925                   /usr/lib/x86_64-linux-gnu/qt5/plugins/platformthemes/libqgtk3.so
7f298f9d1000-7f298fbd1000 ---p 00057000 103:09 1049925                   /usr/lib/x86_64-linux-gnu/qt5/plugins/platformthemes/libqgtk3.so
7f298fbd1000-7f298fbd3000 r--p 00057000 103:09 1049925                   /usr/lib/x86_64-linux-gnu/qt5/plugins/platformthemes/libqgtk3.so
7f298fbd3000-7f298fbd5000 rw-p 00059000 103:09 1049925                   /usr/lib/x86_64-linux-gnu/qt5/plugins/platformthemes/libqgtk3.so
7f298fbd5000-7f298fbed000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400849                    /usr/lib/x86_64-linux-gnu/libxcb-glx.so.0.0.0
7f298fbed000-7f298fded000 ---p 00018000 103:09 400849                    /usr/lib/x86_64-linux-gnu/libxcb-glx.so.0.0.0
7f298fded000-7f298fdef000 r--p 00018000 103:09 400849                    /usr/lib/x86_64-linux-gnu/libxcb-glx.so.0.0.0
7f298fdef000-7f298fdf0000 rw-p 0001a000 103:09 400849                    /usr/lib/x86_64-linux-gnu/libxcb-glx.so.0.0.0
7f298fdf0000-7f298fdfe000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554116                    /usr/lib/x86_64-linux-gnu/qt5/plugins/xcbglintegrations/libqxcb-glx-integration.so
7f298fdfe000-7f298fffe000 ---p 0000e000 103:09 554116                    /usr/lib/x86_64-linux-gnu/qt5/plugins/xcbglintegrations/libqxcb-glx-integration.so
7f298fffe000-7f298ffff000 r--p 0000e000 103:09 554116                    /usr/lib/x86_64-linux-gnu/qt5/plugins/xcbglintegrations/libqxcb-glx-integration.so
7f298ffff000-7f2990000000 rw-p 0000f000 103:09 554116                    /usr/lib/x86_64-linux-gnu/qt5/plugins/xcbglintegrations/libqxcb-glx-integration.so
7f2990000000-7f2990021000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2990021000-7f2994000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2994000000-7f2994001000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554101                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/qml/DefaultWindowDecoration.qmlc
7f2994001000-7f2994003000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 554101                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/qml/DefaultWindowDecoration.qmlc
7f2994003000-7f2994004000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537721                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/MenuItem.qmlc
7f2994004000-7f2994008000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537721                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/MenuItem.qmlc
7f2994008000-7f299400a000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537697                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/CursorDelegate.qmlc
7f299400a000-7f299400d000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714764                   /home/jaeyoung/.cache/qmlcache/fb5eeb1a6b248cc33ca9b0734e796faec7ce0712.qmlc
7f299400d000-7f2994014000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:0a 9714764                   /home/jaeyoung/.cache/qmlcache/fb5eeb1a6b248cc33ca9b0734e796faec7ce0712.qmlc
7f2994014000-7f2994015000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537719                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Menu.qmlc
7f2994015000-7f2994018000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537719                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Menu.qmlc
7f2994018000-7f299401a000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714794                   /home/jaeyoung/.cache/qmlcache/ce436a7ecd4a737efb448683be5179cabe4c8b8e.qmlc
7f299401a000-7f299401d000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553680                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ToolBar.qmlc
7f299401d000-7f299401e000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537618                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ApplicationWindow.qmlc
7f299401e000-7f2994020000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537624                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Button.qmlc
7f2994020000-7f2994024000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 537624                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Button.qmlc
7f2994024000-7f2994025000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537705                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/DialogButtonBox.qmlc
7f2994025000-7f2994027000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537705                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/DialogButtonBox.qmlc
7f2994027000-7f2994029000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537703                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Dialog.qmlc
7f2994029000-7f299402c000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 537703                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Dialog.qmlc
7f299402c000-7f299402d000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537743                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/RectangularGlow.qmlc
7f299402d000-7f2994030000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537743                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/RectangularGlow.qmlc
7f2994030000-7f2994032000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537620                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/BoxShadow.qmlc
7f2994032000-7f2994034000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537709                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ElevationEffect.qmlc
7f2994034000-7f299403b000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 537709                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ElevationEffect.qmlc
7f299403b000-7f299403c000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537707                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Drawer.qmlc
7f299403c000-7f2994040000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537707                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Drawer.qmlc
7f2994040000-7f2994041000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537715                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ItemDelegate.qmlc
7f2994041000-7f2994044000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537715                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ItemDelegate.qmlc
7f2994044000-7f2994045000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537749                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ScrollIndicator.qmlc
7f2994045000-7f2994046000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537749                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ScrollIndicator.qmlc
7f2994046000-7f2994047000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714797                   /home/jaeyoung/.cache/qmlcache/542526a9ba2d8a2b303e3bf4320991b3cfbc4596.qmlc
7f2994047000-7f2994049000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:0a 9714797                   /home/jaeyoung/.cache/qmlcache/542526a9ba2d8a2b303e3bf4320991b3cfbc4596.qmlc
7f2994049000-7f299404a000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537747                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ScrollBar.qmlc
7f299404a000-7f299404d000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537747                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ScrollBar.qmlc
7f299404d000-7f299404e000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553723                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/ScrollView.qmlc
7f299404e000-7f2994050000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 553723                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/ScrollView.qmlc
7f2994050000-7f2994051000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537717                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/Label.qmlc
7f2994051000-7f2994053000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714781                   /home/jaeyoung/.cache/qmlcache/42eddf477446a29654878b4c6db9bc40a417ab5a.qmlc
7f2994053000-7f2994058000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:0a 9714781                   /home/jaeyoung/.cache/qmlcache/42eddf477446a29654878b4c6db9bc40a417ab5a.qmlc
7f2994058000-7f2994059000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553682                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ToolButton.qmlc
7f2994059000-7f299405c000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 553682                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls.2/Material/ToolButton.qmlc
7f299405c000-7f299405d000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525756                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/ToolMenuButton.qmlc
7f299405d000-7f2994061000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525756                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/ToolMenuButton.qmlc
7f2994061000-7f2994063000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 530320                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/ToolBar.qmlc
7f2994063000-7f2994067000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 530320                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/ToolBar.qmlc
7f2994067000-7f299406c000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525685                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/ComboBox.qmlc
7f299406c000-7f2994077000 r-xs 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 525685                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/ComboBox.qmlc
7f2994077000-7f299407a000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525791                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/ButtonStyle.qmlc
7f299407a000-7f2994080000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:09 525791                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Styles/Base/ButtonStyle.qmlc
7f2994080000-7f2994082000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554103                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/qml/IconButtonStyle.qmlc
7f2994082000-7f299408b000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525700                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/BasicTableView.qmlc
7f299408b000-7f299409b000 r-xs 00009000 103:09 525700                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/BasicTableView.qmlc
7f299409b000-7f299409c000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525746                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/TableViewItemDelegateLoader.qmlc
7f299409c000-7f299409f000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525746                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/TableViewItemDelegateLoader.qmlc
7f299409f000-7f29940a4000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525748                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/TableViewSelection.qmlc
7f29940a4000-7f29940a7000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 530312                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/TableView.qmlc
7f29940a7000-7f29940ae000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:09 530312                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/TableView.qmlc
7f29940ae000-7f29940b3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401304                    /usr/lib/x86_64-linux-gnu/libXfixes.so.3.1.0
7f29940b3000-7f29942b2000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401304                    /usr/lib/x86_64-linux-gnu/libXfixes.so.3.1.0
7f29942b2000-7f29942b3000 r--p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 401304                    /usr/lib/x86_64-linux-gnu/libXfixes.so.3.1.0
7f29942b3000-7f29942b4000 rw-p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401304                    /usr/lib/x86_64-linux-gnu/libXfixes.so.3.1.0
7f29942b4000-7f29942bd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401322                    /usr/lib/x86_64-linux-gnu/libXrender.so.1.3.0
7f29942bd000-7f29944bc000 ---p 00009000 103:09 401322                    /usr/lib/x86_64-linux-gnu/libXrender.so.1.3.0
7f29944bc000-7f29944bd000 r--p 00008000 103:09 401322                    /usr/lib/x86_64-linux-gnu/libXrender.so.1.3.0
7f29944bd000-7f29944be000 rw-p 00009000 103:09 401322                    /usr/lib/x86_64-linux-gnu/libXrender.so.1.3.0
7f29944be000-7f29944c7000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401296                    /usr/lib/x86_64-linux-gnu/libXcursor.so.1.0.2
7f29944c7000-7f29946c6000 ---p 00009000 103:09 401296                    /usr/lib/x86_64-linux-gnu/libXcursor.so.1.0.2
7f29946c6000-7f29946c7000 r--p 00008000 103:09 401296                    /usr/lib/x86_64-linux-gnu/libXcursor.so.1.0.2
7f29946c7000-7f29946c8000 rw-p 00009000 103:09 401296                    /usr/lib/x86_64-linux-gnu/libXcursor.so.1.0.2
7f29946c8000-7f29946c9000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29946c9000-7f2994ec9000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2994ec9000-7f2994edd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840075                   /lib/x86_64-linux-gnu/libgpg-error.so.0.22.0
7f2994edd000-7f29950dc000 ---p 00014000 103:09 1840075                   /lib/x86_64-linux-gnu/libgpg-error.so.0.22.0
7f29950dc000-7f29950dd000 r--p 00013000 103:09 1840075                   /lib/x86_64-linux-gnu/libgpg-error.so.0.22.0
7f29950dd000-7f29950de000 rw-p 00014000 103:09 1840075                   /lib/x86_64-linux-gnu/libgpg-error.so.0.22.0
7f29950de000-7f29951f2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840073                   /lib/x86_64-linux-gnu/libgcrypt.so.20.2.1
7f29951f2000-7f29953f1000 ---p 00114000 103:09 1840073                   /lib/x86_64-linux-gnu/libgcrypt.so.20.2.1
7f29953f1000-7f29953f3000 r--p 00113000 103:09 1840073                   /lib/x86_64-linux-gnu/libgcrypt.so.20.2.1
7f29953f3000-7f29953f8000 rw-p 00115000 103:09 1840073                   /lib/x86_64-linux-gnu/libgcrypt.so.20.2.1
7f29953f8000-7f29953f9000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29953f9000-7f2995414000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402003                    /usr/lib/x86_64-linux-gnu/liblz4.so.1.7.1
7f2995414000-7f2995613000 ---p 0001b000 103:09 402003                    /usr/lib/x86_64-linux-gnu/liblz4.so.1.7.1
7f2995613000-7f2995614000 r--p 0001a000 103:09 402003                    /usr/lib/x86_64-linux-gnu/liblz4.so.1.7.1
7f2995614000-7f2995615000 rw-p 0001b000 103:09 402003                    /usr/lib/x86_64-linux-gnu/liblz4.so.1.7.1
7f2995615000-7f2995639000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840094                   /lib/x86_64-linux-gnu/liblzma.so.5.2.2
7f2995639000-7f2995839000 ---p 00024000 103:09 1840094                   /lib/x86_64-linux-gnu/liblzma.so.5.2.2
7f2995839000-7f299583a000 r--p 00024000 103:09 1840094                   /lib/x86_64-linux-gnu/liblzma.so.5.2.2
7f299583a000-7f299583b000 rw-p 00025000 103:09 1840094                   /lib/x86_64-linux-gnu/liblzma.so.5.2.2
7f299583b000-7f29958bb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1835198                   /lib/x86_64-linux-gnu/libsystemd.so.0.21.0
7f29958bb000-7f2995aba000 ---p 00080000 103:09 1835198                   /lib/x86_64-linux-gnu/libsystemd.so.0.21.0
7f2995aba000-7f2995abd000 r--p 0007f000 103:09 1835198                   /lib/x86_64-linux-gnu/libsystemd.so.0.21.0
7f2995abd000-7f2995abe000 rw-p 00082000 103:09 1835198                   /lib/x86_64-linux-gnu/libsystemd.so.0.21.0
7f2995abe000-7f2995abf000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2995abf000-7f2995ac4000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402494                    /usr/lib/x86_64-linux-gnu/libxcb-util.so.1.0.0
7f2995ac4000-7f2995cc3000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 402494                    /usr/lib/x86_64-linux-gnu/libxcb-util.so.1.0.0
7f2995cc3000-7f2995cc4000 r--p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 402494                    /usr/lib/x86_64-linux-gnu/libxcb-util.so.1.0.0
7f2995cc4000-7f2995cc5000 rw-p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 402494                    /usr/lib/x86_64-linux-gnu/libxcb-util.so.1.0.0
7f2995cc5000-7f2995cd6000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401302                    /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0
7f2995cd6000-7f2995ed5000 ---p 00011000 103:09 401302                    /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0
7f2995ed5000-7f2995ed6000 r--p 00010000 103:09 401302                    /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0
7f2995ed6000-7f2995ed7000 rw-p 00011000 103:09 401302                    /usr/lib/x86_64-linux-gnu/libXext.so.6.4.0
7f2995ed7000-7f2995f22000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1835229                   /lib/x86_64-linux-gnu/libdbus-1.so.3.19.4
7f2995f22000-7f2996122000 ---p 0004b000 103:09 1835229                   /lib/x86_64-linux-gnu/libdbus-1.so.3.19.4
7f2996122000-7f2996123000 r--p 0004b000 103:09 1835229                   /lib/x86_64-linux-gnu/libdbus-1.so.3.19.4
7f2996123000-7f2996124000 rw-p 0004c000 103:09 1835229                   /lib/x86_64-linux-gnu/libdbus-1.so.3.19.4
7f2996124000-7f2996153000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1843303                   /lib/x86_64-linux-gnu/libexpat.so.1.6.7
7f2996153000-7f2996353000 ---p 0002f000 103:09 1843303                   /lib/x86_64-linux-gnu/libexpat.so.1.6.7
7f2996353000-7f2996355000 r--p 0002f000 103:09 1843303                   /lib/x86_64-linux-gnu/libexpat.so.1.6.7
7f2996355000-7f2996356000 rw-p 00031000 103:09 1843303                   /lib/x86_64-linux-gnu/libexpat.so.1.6.7
7f2996356000-7f2996393000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402506                    /usr/lib/x86_64-linux-gnu/libxkbcommon.so.0.0.0
7f2996393000-7f2996592000 ---p 0003d000 103:09 402506                    /usr/lib/x86_64-linux-gnu/libxkbcommon.so.0.0.0
7f2996592000-7f2996594000 r--p 0003c000 103:09 402506                    /usr/lib/x86_64-linux-gnu/libxkbcommon.so.0.0.0
7f2996594000-7f2996595000 rw-p 0003e000 103:09 402506                    /usr/lib/x86_64-linux-gnu/libxkbcommon.so.0.0.0
7f2996595000-7f299659c000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402504                    /usr/lib/x86_64-linux-gnu/libxkbcommon-x11.so.0.0.0
7f299659c000-7f299679b000 ---p 00007000 103:09 402504                    /usr/lib/x86_64-linux-gnu/libxkbcommon-x11.so.0.0.0
7f299679b000-7f299679c000 r--p 00006000 103:09 402504                    /usr/lib/x86_64-linux-gnu/libxkbcommon-x11.so.0.0.0
7f299679c000-7f299679d000 rw-p 00007000 103:09 402504                    /usr/lib/x86_64-linux-gnu/libxkbcommon-x11.so.0.0.0
7f299679d000-7f29967a0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400830                    /usr/lib/x86_64-linux-gnu/libxcb-shape.so.0.0.0
7f29967a0000-7f299699f000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 400830                    /usr/lib/x86_64-linux-gnu/libxcb-shape.so.0.0.0
7f299699f000-7f29969a0000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 400830                    /usr/lib/x86_64-linux-gnu/libxcb-shape.so.0.0.0
7f29969a0000-7f29969a1000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 400830                    /usr/lib/x86_64-linux-gnu/libxcb-shape.so.0.0.0
7f29969a1000-7f29969a5000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402472                    /usr/lib/x86_64-linux-gnu/libxcb-icccm.so.4.0.0
7f29969a5000-7f2996ba4000 ---p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 402472                    /usr/lib/x86_64-linux-gnu/libxcb-icccm.so.4.0.0
7f2996ba4000-7f2996ba5000 r--p d72edde1b5da441a550262cce0ea172460bf453d 103:09 402472                    /usr/lib/x86_64-linux-gnu/libxcb-icccm.so.4.0.0
7f2996ba5000-7f2996ba6000 rw-p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 402472                    /usr/lib/x86_64-linux-gnu/libxcb-icccm.so.4.0.0
7f2996ba6000-7f2996ba8000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402476                    /usr/lib/x86_64-linux-gnu/libxcb-keysyms.so.1.0.0
7f2996ba8000-7f2996da7000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 402476                    /usr/lib/x86_64-linux-gnu/libxcb-keysyms.so.1.0.0
7f2996da7000-7f2996da8000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 402476                    /usr/lib/x86_64-linux-gnu/libxcb-keysyms.so.1.0.0
7f2996da8000-7f2996da9000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 402476                    /usr/lib/x86_64-linux-gnu/libxcb-keysyms.so.1.0.0
7f2996da9000-7f2996dab000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404791                    /usr/lib/x86_64-linux-gnu/libxcb-shm.so.0.0.0
7f2996dab000-7f2996faa000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 404791                    /usr/lib/x86_64-linux-gnu/libxcb-shm.so.0.0.0
7f2996faa000-7f2996fab000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 404791                    /usr/lib/x86_64-linux-gnu/libxcb-shm.so.0.0.0
7f2996fab000-7f2996fac000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 404791                    /usr/lib/x86_64-linux-gnu/libxcb-shm.so.0.0.0
7f2996fac000-7f2996fb0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402474                    /usr/lib/x86_64-linux-gnu/libxcb-image.so.0.0.0
7f2996fb0000-7f29971af000 ---p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 402474                    /usr/lib/x86_64-linux-gnu/libxcb-image.so.0.0.0
7f29971af000-7f29971b0000 r--p d72edde1b5da441a550262cce0ea172460bf453d 103:09 402474                    /usr/lib/x86_64-linux-gnu/libxcb-image.so.0.0.0
7f29971b0000-7f29971b1000 rw-p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 402474                    /usr/lib/x86_64-linux-gnu/libxcb-image.so.0.0.0
7f29971b1000-7f29971bf000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400819                    /usr/lib/x86_64-linux-gnu/libxcb-randr.so.0.1.0
7f29971bf000-7f29973bf000 ---p 0000e000 103:09 400819                    /usr/lib/x86_64-linux-gnu/libxcb-randr.so.0.1.0
7f29973bf000-7f29973c0000 r--p 0000e000 103:09 400819                    /usr/lib/x86_64-linux-gnu/libxcb-randr.so.0.1.0
7f29973c0000-7f29973c1000 rw-p 0000f000 103:09 400819                    /usr/lib/x86_64-linux-gnu/libxcb-randr.so.0.1.0
7f29973c1000-7f29973c3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400534                    /usr/lib/x86_64-linux-gnu/libxcb-xinerama.so.0.0.0
7f29973c3000-7f29975c2000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 400534                    /usr/lib/x86_64-linux-gnu/libxcb-xinerama.so.0.0.0
7f29975c2000-7f29975c3000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 400534                    /usr/lib/x86_64-linux-gnu/libxcb-xinerama.so.0.0.0
7f29975c3000-7f29975c4000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 400534                    /usr/lib/x86_64-linux-gnu/libxcb-xinerama.so.0.0.0
7f29975c4000-7f29975cb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400828                    /usr/lib/x86_64-linux-gnu/libxcb-xfixes.so.0.0.0
7f29975cb000-7f29977ca000 ---p 00007000 103:09 400828                    /usr/lib/x86_64-linux-gnu/libxcb-xfixes.so.0.0.0
7f29977ca000-7f29977cb000 r--p 00006000 103:09 400828                    /usr/lib/x86_64-linux-gnu/libxcb-xfixes.so.0.0.0
7f29977cb000-7f29977cc000 rw-p 00007000 103:09 400828                    /usr/lib/x86_64-linux-gnu/libxcb-xfixes.so.0.0.0
7f29977cc000-7f29977d1000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400836                    /usr/lib/x86_64-linux-gnu/libxcb-sync.so.1.0.0
7f29977d1000-7f29979d1000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 400836                    /usr/lib/x86_64-linux-gnu/libxcb-sync.so.1.0.0
7f29979d1000-7f29979d2000 r--p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 400836                    /usr/lib/x86_64-linux-gnu/libxcb-sync.so.1.0.0
7f29979d2000-7f29979d3000 rw-p 00006000 103:09 400836                    /usr/lib/x86_64-linux-gnu/libxcb-sync.so.1.0.0
7f29979d3000-7f29979df000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400821                    /usr/lib/x86_64-linux-gnu/libxcb-render.so.0.0.0
7f29979df000-7f2997bde000 ---p 0000c000 103:09 400821                    /usr/lib/x86_64-linux-gnu/libxcb-render.so.0.0.0
7f2997bde000-7f2997bdf000 r--p 0000b000 103:09 400821                    /usr/lib/x86_64-linux-gnu/libxcb-render.so.0.0.0
7f2997bdf000-7f2997be0000 rw-p 0000c000 103:09 400821                    /usr/lib/x86_64-linux-gnu/libxcb-render.so.0.0.0
7f2997be0000-7f2997be3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402482                    /usr/lib/x86_64-linux-gnu/libxcb-render-util.so.0.0.0
7f2997be3000-7f2997de2000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 402482                    /usr/lib/x86_64-linux-gnu/libxcb-render-util.so.0.0.0
7f2997de2000-7f2997de3000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 402482                    /usr/lib/x86_64-linux-gnu/libxcb-render-util.so.0.0.0
7f2997de3000-7f2997de4000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 402482                    /usr/lib/x86_64-linux-gnu/libxcb-render-util.so.0.0.0
7f2997de4000-7f2997dfe000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402498                    /usr/lib/x86_64-linux-gnu/libxcb-xkb.so.1.0.0
7f2997dfe000-7f2997ffe000 ---p 0001a000 103:09 402498                    /usr/lib/x86_64-linux-gnu/libxcb-xkb.so.1.0.0
7f2997ffe000-7f2997fff000 r--p 0001a000 103:09 402498                    /usr/lib/x86_64-linux-gnu/libxcb-xkb.so.1.0.0
7f2997fff000-7f2998000000 rw-p 0001b000 103:09 402498                    /usr/lib/x86_64-linux-gnu/libxcb-xkb.so.1.0.0
7f2998000000-7f2998021000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f2998021000-7f299c000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f299c000000-7f299c021000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f299c021000-7f29a0000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a0000000-7f29a002d000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a002d000-7f29a4000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a4000000-7f29a4038000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a4038000-7f29a8000000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a8000000-7f29a8001000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714601                   /home/jaeyoung/.cache/qmlcache/4f45f5de8f55aaf8ec2168cd13b1bd8af024ea7a.qmlc
7f29a8001000-7f29a8003000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 530314                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/TableViewColumn.qmlc
7f29a8003000-7f29a8005000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525712                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/EditMenu.qmlc
7f29a8005000-7f29a8006000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525750                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/TextHandle.qmlc
7f29a8006000-7f29a8009000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525750                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/TextHandle.qmlc
7f29a8009000-7f29a800b000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525752                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/TextInputWithHandles.qmlc
7f29a800b000-7f29a8013000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525752                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/TextInputWithHandles.qmlc
7f29a8013000-7f29a8016000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 530318                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/TextField.qmlc
7f29a8016000-7f29a801b000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:09 530318                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/TextField.qmlc
7f29a801b000-7f29a801c000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554105                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/qml/IconGlyph.qmlc
7f29a801c000-7f29a801e000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525710                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/Control.qmlc
7f29a801e000-7f29a8020000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525698                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/BasicButton.qmlc
7f29a8020000-7f29a8026000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525698                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/BasicButton.qmlc
7f29a8026000-7f29a8028000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525718                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/FocusFrame.qmlc
7f29a8028000-7f29a802a000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525730                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/ScrollBar.qmlc
7f29a802a000-7f29a8031000 r-xs cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 525730                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/ScrollBar.qmlc
7f29a8031000-7f29a8035000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525732                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/ScrollViewHelper.qmlc
7f29a8035000-7f29a803d000 r-xs ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 525732                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/ScrollViewHelper.qmlc
7f29a803d000-7f29a8040000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525767                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/ScrollView.qmlc
7f29a8040000-7f29a8048000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:09 525767                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/ScrollView.qmlc
7f29a8048000-7f29a8049000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525740                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/Style.qmlc
7f29a8049000-7f29a804a000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525724                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/MenuContentScroller.qmlc
7f29a804a000-7f29a804b000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525724                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/MenuContentScroller.qmlc
7f29a804b000-7f29a804e000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525706                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/ColumnMenuContent.qmlc
7f29a804e000-7f29a8056000 r-xs d72edde1b5da441a550262cce0ea172460bf453d 103:09 525706                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/ColumnMenuContent.qmlc
7f29a8056000-7f29a805a000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525722                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/MenuContentItem.qmlc
7f29a805a000-7f29a8064000 r-xs ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 525722                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/MenuContentItem.qmlc
7f29a8064000-7f29a8065000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525691                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Menu.qmlc
7f29a8065000-7f29a8067000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525691                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Menu.qmlc
7f29a8067000-7f29a8068000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525679                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Button.qmlc
7f29a8068000-7f29a806a000 r-xs 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 525679                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Button.qmlc
7f29a806a000-7f29a806b000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 530322                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/ToolButton.qmlc
7f29a806b000-7f29a806f000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525773                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/SplitView.qmlc
7f29a806f000-7f29a807d000 r-xs ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 525773                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/SplitView.qmlc
7f29a807d000-7f29a807e000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525754                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/TextSingleton.qmlc
7f29a807e000-7f29a8087000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 554069                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qmlc
7f29a8087000-7f29a8096000 r-xs 00009000 103:09 554069                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qmlc
7f29a8096000-7f29a80a1000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053731                   /var/cache/fontconfig/945677eb7aeaf62f1d50efc3fb3ec7d8-le64.cache-7
7f29a80a1000-7f29a80b8000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401257                    /usr/lib/x86_64-linux-gnu/libICE.so.6.3.0
7f29a80b8000-7f29a82b7000 ---p 00017000 103:09 401257                    /usr/lib/x86_64-linux-gnu/libICE.so.6.3.0
7f29a82b7000-7f29a82b8000 r--p 00016000 103:09 401257                    /usr/lib/x86_64-linux-gnu/libICE.so.6.3.0
7f29a82b8000-7f29a82b9000 rw-p 00017000 103:09 401257                    /usr/lib/x86_64-linux-gnu/libICE.so.6.3.0
7f29a82b9000-7f29a82bc000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a82bc000-7f29a82c3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401281                    /usr/lib/x86_64-linux-gnu/libSM.so.6.0.1
7f29a82c3000-7f29a84c2000 ---p 00007000 103:09 401281                    /usr/lib/x86_64-linux-gnu/libSM.so.6.0.1
7f29a84c2000-7f29a84c3000 r--p 00006000 103:09 401281                    /usr/lib/x86_64-linux-gnu/libSM.so.6.0.1
7f29a84c3000-7f29a84c4000 rw-p 00007000 103:09 401281                    /usr/lib/x86_64-linux-gnu/libSM.so.6.0.1
7f29a84c4000-7f29a84d3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401310                    /usr/lib/x86_64-linux-gnu/libXi.so.6.1.0
7f29a84d3000-7f29a86d2000 ---p 0000f000 103:09 401310                    /usr/lib/x86_64-linux-gnu/libXi.so.6.1.0
7f29a86d2000-7f29a86d3000 r--p 0000e000 103:09 401310                    /usr/lib/x86_64-linux-gnu/libXi.so.6.1.0
7f29a86d3000-7f29a86d4000 rw-p 0000f000 103:09 401310                    /usr/lib/x86_64-linux-gnu/libXi.so.6.1.0
7f29a86d4000-7f29a86d5000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400794                    /usr/lib/x86_64-linux-gnu/libX11-xcb.so.1.0.0
7f29a86d5000-7f29a88d4000 ---p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 400794                    /usr/lib/x86_64-linux-gnu/libX11-xcb.so.1.0.0
7f29a88d4000-7f29a88d5000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400794                    /usr/lib/x86_64-linux-gnu/libX11-xcb.so.1.0.0
7f29a88d5000-7f29a88d6000 rw-p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 400794                    /usr/lib/x86_64-linux-gnu/libX11-xcb.so.1.0.0
7f29a88d6000-7f29a895d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398870                    /usr/lib/x86_64-linux-gnu/libQt5DBus.so.5.9.5
7f29a895d000-7f29a8b5c000 ---p 00087000 103:09 398870                    /usr/lib/x86_64-linux-gnu/libQt5DBus.so.5.9.5
7f29a8b5c000-7f29a8b5e000 r--p 00086000 103:09 398870                    /usr/lib/x86_64-linux-gnu/libQt5DBus.so.5.9.5
7f29a8b5e000-7f29a8b5f000 rw-p 00088000 103:09 398870                    /usr/lib/x86_64-linux-gnu/libQt5DBus.so.5.9.5
7f29a8b5f000-7f29a8b60000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a8b60000-7f29a8b9e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401651                    /usr/lib/x86_64-linux-gnu/libfontconfig.so.1.10.1
7f29a8b9e000-7f29a8d9e000 ---p 0003e000 103:09 401651                    /usr/lib/x86_64-linux-gnu/libfontconfig.so.1.10.1
7f29a8d9e000-7f29a8da0000 r--p 0003e000 103:09 401651                    /usr/lib/x86_64-linux-gnu/libfontconfig.so.1.10.1
7f29a8da0000-7f29a8da5000 rw-p 00040000 103:09 401651                    /usr/lib/x86_64-linux-gnu/libfontconfig.so.1.10.1
7f29a8da5000-7f29a8ea3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398890                    /usr/lib/x86_64-linux-gnu/libQt5XcbQpa.so.5.9.5
7f29a8ea3000-7f29a90a3000 ---p 000fe000 103:09 398890                    /usr/lib/x86_64-linux-gnu/libQt5XcbQpa.so.5.9.5
7f29a90a3000-7f29a90a7000 r--p 000fe000 103:09 398890                    /usr/lib/x86_64-linux-gnu/libQt5XcbQpa.so.5.9.5
7f29a90a7000-7f29a90aa000 rw-p 00102000 103:09 398890                    /usr/lib/x86_64-linux-gnu/libQt5XcbQpa.so.5.9.5
7f29a90aa000-7f29a90ab000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a90ab000-7f29a90ad000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 537447                    /usr/lib/x86_64-linux-gnu/qt5/plugins/platforms/libqxcb.so
7f29a90ad000-7f29a92ac000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 537447                    /usr/lib/x86_64-linux-gnu/qt5/plugins/platforms/libqxcb.so
7f29a92ac000-7f29a92ad000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 537447                    /usr/lib/x86_64-linux-gnu/qt5/plugins/platforms/libqxcb.so
7f29a92ad000-7f29a92ae000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 537447                    /usr/lib/x86_64-linux-gnu/qt5/plugins/platforms/libqxcb.so
7f29a92ae000-7f29a92af000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a92af000-7f29a9aaf000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a9aaf000-7f29a9ab0000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29a9ab0000-7f29aa2b0000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29aa2b0000-7f29aa2b1000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29aa2b1000-7f29aaab1000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29aaab1000-7f29aaab2000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29aaab2000-7f29ab2b2000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ab2b2000-7f29ab2b3000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ab2b3000-7f29abab3000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29abab3000-7f29abab4000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29abab4000-7f29ac2b4000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ac2b4000-7f29ac2bf000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840124                   /lib/x86_64-linux-gnu/libnss_files-2.27.so
7f29ac2bf000-7f29ac4be000 ---p 0000b000 103:09 1840124                   /lib/x86_64-linux-gnu/libnss_files-2.27.so
7f29ac4be000-7f29ac4bf000 r--p 0000a000 103:09 1840124                   /lib/x86_64-linux-gnu/libnss_files-2.27.so
7f29ac4bf000-7f29ac4c0000 rw-p 0000b000 103:09 1840124                   /lib/x86_64-linux-gnu/libnss_files-2.27.so
7f29ac4c0000-7f29ac4c6000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ac4c6000-7f29ac4dd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840118                   /lib/x86_64-linux-gnu/libnsl-2.27.so
7f29ac4dd000-7f29ac6dc000 ---p 00017000 103:09 1840118                   /lib/x86_64-linux-gnu/libnsl-2.27.so
7f29ac6dc000-7f29ac6dd000 r--p 00016000 103:09 1840118                   /lib/x86_64-linux-gnu/libnsl-2.27.so
7f29ac6dd000-7f29ac6de000 rw-p 00017000 103:09 1840118                   /lib/x86_64-linux-gnu/libnsl-2.27.so
7f29ac6de000-7f29ac6e0000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ac6e0000-7f29ac6eb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840135                   /lib/x86_64-linux-gnu/libnss_nis-2.27.so
7f29ac6eb000-7f29ac8ea000 ---p 0000b000 103:09 1840135                   /lib/x86_64-linux-gnu/libnss_nis-2.27.so
7f29ac8ea000-7f29ac8eb000 r--p 0000a000 103:09 1840135                   /lib/x86_64-linux-gnu/libnss_nis-2.27.so
7f29ac8eb000-7f29ac8ec000 rw-p 0000b000 103:09 1840135                   /lib/x86_64-linux-gnu/libnss_nis-2.27.so
7f29ac8ec000-7f29ac8f4000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840120                   /lib/x86_64-linux-gnu/libnss_compat-2.27.so
7f29ac8f4000-7f29acaf4000 ---p 00008000 103:09 1840120                   /lib/x86_64-linux-gnu/libnss_compat-2.27.so
7f29acaf4000-7f29acaf5000 r--p 00008000 103:09 1840120                   /lib/x86_64-linux-gnu/libnss_compat-2.27.so
7f29acaf5000-7f29acaf6000 rw-p 00009000 103:09 1840120                   /lib/x86_64-linux-gnu/libnss_compat-2.27.so
7f29acaf6000-7f29acb09000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840030                   /lib/x86_64-linux-gnu/libbsd.so.0.8.7
7f29acb09000-7f29acd08000 ---p 00013000 103:09 1840030                   /lib/x86_64-linux-gnu/libbsd.so.0.8.7
7f29acd08000-7f29acd09000 r--p 00012000 103:09 1840030                   /lib/x86_64-linux-gnu/libbsd.so.0.8.7
7f29acd09000-7f29acd0a000 rw-p 00013000 103:09 1840030                   /lib/x86_64-linux-gnu/libbsd.so.0.8.7
7f29acd0a000-7f29acd0b000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29acd0b000-7f29ace0f000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400687                    /usr/lib/x86_64-linux-gnu/libsqlite3.so.0.8.6
7f29ace0f000-7f29ad00e000 ---p 00104000 103:09 400687                    /usr/lib/x86_64-linux-gnu/libsqlite3.so.0.8.6
7f29ad00e000-7f29ad011000 r--p 00103000 103:09 400687                    /usr/lib/x86_64-linux-gnu/libsqlite3.so.0.8.6
7f29ad011000-7f29ad013000 rw-p 00106000 103:09 400687                    /usr/lib/x86_64-linux-gnu/libsqlite3.so.0.8.6
7f29ad013000-7f29ad014000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ad014000-7f29ad05a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401883                    /usr/lib/x86_64-linux-gnu/libhx509.so.5.0.0
7f29ad05a000-7f29ad259000 ---p 00046000 103:09 401883                    /usr/lib/x86_64-linux-gnu/libhx509.so.5.0.0
7f29ad259000-7f29ad25c000 r--p 00045000 103:09 401883                    /usr/lib/x86_64-linux-gnu/libhx509.so.5.0.0
7f29ad25c000-7f29ad25d000 rw-p 00048000 103:09 401883                    /usr/lib/x86_64-linux-gnu/libhx509.so.5.0.0
7f29ad25d000-7f29ad25e000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ad25e000-7f29ad26c000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401867                    /usr/lib/x86_64-linux-gnu/libheimbase.so.1.0.0
7f29ad26c000-7f29ad46b000 ---p 0000e000 103:09 401867                    /usr/lib/x86_64-linux-gnu/libheimbase.so.1.0.0
7f29ad46b000-7f29ad46c000 r--p 0000d000 103:09 401867                    /usr/lib/x86_64-linux-gnu/libheimbase.so.1.0.0
7f29ad46c000-7f29ad46d000 rw-p 0000e000 103:09 401867                    /usr/lib/x86_64-linux-gnu/libheimbase.so.1.0.0
7f29ad46d000-7f29ad495000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402443                    /usr/lib/x86_64-linux-gnu/libwind.so.0.0.0
7f29ad495000-7f29ad694000 ---p 00028000 103:09 402443                    /usr/lib/x86_64-linux-gnu/libwind.so.0.0.0
7f29ad694000-7f29ad695000 r--p 00027000 103:09 402443                    /usr/lib/x86_64-linux-gnu/libwind.so.0.0.0
7f29ad695000-7f29ad696000 rw-p 00028000 103:09 402443                    /usr/lib/x86_64-linux-gnu/libwind.so.0.0.0
7f29ad696000-7f29ad69b000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401300                    /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0
7f29ad69b000-7f29ad89a000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401300                    /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0
7f29ad89a000-7f29ad89b000 r--p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 401300                    /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0
7f29ad89b000-7f29ad89c000 rw-p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 401300                    /usr/lib/x86_64-linux-gnu/libXdmcp.so.6.0.0
7f29ad89c000-7f29ad89e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401289                    /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0
7f29ad89e000-7f29ada9e000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 401289                    /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0
7f29ada9e000-7f29ada9f000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 401289                    /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0
7f29ada9f000-7f29adaa0000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 401289                    /usr/lib/x86_64-linux-gnu/libXau.so.6.0.0
7f29adaa0000-7f29adab5000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402230                    /usr/lib/x86_64-linux-gnu/libroken.so.18.1.0
7f29adab5000-7f29adcb4000 ---p 00015000 103:09 402230                    /usr/lib/x86_64-linux-gnu/libroken.so.18.1.0
7f29adcb4000-7f29adcb5000 r--p 00014000 103:09 402230                    /usr/lib/x86_64-linux-gnu/libroken.so.18.1.0
7f29adcb5000-7f29adcb6000 rw-p 00015000 103:09 402230                    /usr/lib/x86_64-linux-gnu/libroken.so.18.1.0
7f29adcb6000-7f29adce9000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401865                    /usr/lib/x86_64-linux-gnu/libhcrypto.so.4.1.0
7f29adce9000-7f29adee8000 ---p 00033000 103:09 401865                    /usr/lib/x86_64-linux-gnu/libhcrypto.so.4.1.0
7f29adee8000-7f29adeea000 r--p 00032000 103:09 401865                    /usr/lib/x86_64-linux-gnu/libhcrypto.so.4.1.0
7f29adeea000-7f29adeeb000 rw-p 00034000 103:09 401865                    /usr/lib/x86_64-linux-gnu/libhcrypto.so.4.1.0
7f29adeeb000-7f29adeec000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29adeec000-7f29adf8a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401365                    /usr/lib/x86_64-linux-gnu/libasn1.so.8.0.0
7f29adf8a000-7f29ae18a000 ---p 0009e000 103:09 401365                    /usr/lib/x86_64-linux-gnu/libasn1.so.8.0.0
7f29ae18a000-7f29ae18b000 r--p 0009e000 103:09 401365                    /usr/lib/x86_64-linux-gnu/libasn1.so.8.0.0
7f29ae18b000-7f29ae18e000 rw-p 0009f000 103:09 401365                    /usr/lib/x86_64-linux-gnu/libasn1.so.8.0.0
7f29ae18e000-7f29ae215000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401968                    /usr/lib/x86_64-linux-gnu/libkrb5.so.26.0.0
7f29ae215000-7f29ae414000 ---p 00087000 103:09 401968                    /usr/lib/x86_64-linux-gnu/libkrb5.so.26.0.0
7f29ae414000-7f29ae418000 r--p 00086000 103:09 401968                    /usr/lib/x86_64-linux-gnu/libkrb5.so.26.0.0
7f29ae418000-7f29ae41a000 rw-p 0008a000 103:09 401968                    /usr/lib/x86_64-linux-gnu/libkrb5.so.26.0.0
7f29ae41a000-7f29ae41b000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ae41b000-7f29ae423000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401869                    /usr/lib/x86_64-linux-gnu/libheimntlm.so.0.1.0
7f29ae423000-7f29ae622000 ---p 00008000 103:09 401869                    /usr/lib/x86_64-linux-gnu/libheimntlm.so.0.1.0
7f29ae622000-7f29ae623000 r--p 00007000 103:09 401869                    /usr/lib/x86_64-linux-gnu/libheimntlm.so.0.1.0
7f29ae623000-7f29ae624000 rw-p 00008000 103:09 401869                    /usr/lib/x86_64-linux-gnu/libheimntlm.so.0.1.0
7f29ae624000-7f29ae627000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840088                   /lib/x86_64-linux-gnu/libkeyutils.so.1.5
7f29ae627000-7f29ae826000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 1840088                   /lib/x86_64-linux-gnu/libkeyutils.so.1.5
7f29ae826000-7f29ae827000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 1840088                   /lib/x86_64-linux-gnu/libkeyutils.so.1.5
7f29ae827000-7f29ae828000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 1840088                   /lib/x86_64-linux-gnu/libkeyutils.so.1.5
7f29ae828000-7f29ae839000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402327                    /usr/lib/x86_64-linux-gnu/libtasn1.so.6.5.5
7f29ae839000-7f29aea39000 ---p 00011000 103:09 402327                    /usr/lib/x86_64-linux-gnu/libtasn1.so.6.5.5
7f29aea39000-7f29aea3a000 r--p 00011000 103:09 402327                    /usr/lib/x86_64-linux-gnu/libtasn1.so.6.5.5
7f29aea3a000-7f29aea3b000 rw-p 00012000 103:09 402327                    /usr/lib/x86_64-linux-gnu/libtasn1.so.6.5.5
7f29aea3b000-7f29aeb55000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402111                    /usr/lib/x86_64-linux-gnu/libp11-kit.so.0.3.0
7f29aeb55000-7f29aed55000 ---p 0011a000 103:09 402111                    /usr/lib/x86_64-linux-gnu/libp11-kit.so.0.3.0
7f29aed55000-7f29aed5f000 r--p 0011a000 103:09 402111                    /usr/lib/x86_64-linux-gnu/libp11-kit.so.0.3.0
7f29aed5f000-7f29aed69000 rw-p 00124000 103:09 402111                    /usr/lib/x86_64-linux-gnu/libp11-kit.so.0.3.0
7f29aed69000-7f29aed6a000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29aed6a000-7f29aed90000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403245                    /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0
7f29aed90000-7f29aef90000 ---p 00026000 103:09 403245                    /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0
7f29aef90000-7f29aef91000 r--p 00026000 103:09 403245                    /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0
7f29aef91000-7f29aef92000 rw-p 00027000 103:09 403245                    /usr/lib/x86_64-linux-gnu/libxcb.so.1.1.0
7f29aef92000-7f29aefcf000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401792                    /usr/lib/x86_64-linux-gnu/libgssapi.so.3.0.0
7f29aefcf000-7f29af1cf000 ---p 0003d000 103:09 401792                    /usr/lib/x86_64-linux-gnu/libgssapi.so.3.0.0
7f29af1cf000-7f29af1d1000 r--p 0003d000 103:09 401792                    /usr/lib/x86_64-linux-gnu/libgssapi.so.3.0.0
7f29af1d1000-7f29af1d3000 rw-p 0003f000 103:09 401792                    /usr/lib/x86_64-linux-gnu/libgssapi.so.3.0.0
7f29af1d3000-7f29af1ec000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402254                    /usr/lib/x86_64-linux-gnu/libsasl2.so.2.0.25
7f29af1ec000-7f29af3ec000 ---p 00019000 103:09 402254                    /usr/lib/x86_64-linux-gnu/libsasl2.so.2.0.25
7f29af3ec000-7f29af3ed000 r--p 00019000 103:09 402254                    /usr/lib/x86_64-linux-gnu/libsasl2.so.2.0.25
7f29af3ed000-7f29af3ee000 rw-p 0001a000 103:09 402254                    /usr/lib/x86_64-linux-gnu/libsasl2.so.2.0.25
7f29af3ee000-7f29af405000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840173                   /lib/x86_64-linux-gnu/libresolv-2.27.so
7f29af405000-7f29af605000 ---p 00017000 103:09 1840173                   /lib/x86_64-linux-gnu/libresolv-2.27.so
7f29af605000-7f29af606000 r--p 00017000 103:09 1840173                   /lib/x86_64-linux-gnu/libresolv-2.27.so
7f29af606000-7f29af607000 rw-p 00018000 103:09 1840173                   /lib/x86_64-linux-gnu/libresolv-2.27.so
7f29af607000-7f29af609000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29af609000-7f29af613000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401972                    /usr/lib/x86_64-linux-gnu/libkrb5support.so.0.1
7f29af613000-7f29af812000 ---p 0000a000 103:09 401972                    /usr/lib/x86_64-linux-gnu/libkrb5support.so.0.1
7f29af812000-7f29af813000 r--p 00009000 103:09 401972                    /usr/lib/x86_64-linux-gnu/libkrb5support.so.0.1
7f29af813000-7f29af814000 rw-p 0000a000 103:09 401972                    /usr/lib/x86_64-linux-gnu/libkrb5support.so.0.1
7f29af814000-7f29af817000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1889271                   /lib/x86_64-linux-gnu/libcom_err.so.2.1
7f29af817000-7f29afa16000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 1889271                   /lib/x86_64-linux-gnu/libcom_err.so.2.1
7f29afa16000-7f29afa17000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 1889271                   /lib/x86_64-linux-gnu/libcom_err.so.2.1
7f29afa17000-7f29afa18000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 1889271                   /lib/x86_64-linux-gnu/libcom_err.so.2.1
7f29afa18000-7f29afa46000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401964                    /usr/lib/x86_64-linux-gnu/libk5crypto.so.3.1
7f29afa46000-7f29afc46000 ---p 0002e000 103:09 401964                    /usr/lib/x86_64-linux-gnu/libk5crypto.so.3.1
7f29afc46000-7f29afc48000 r--p 0002e000 103:09 401964                    /usr/lib/x86_64-linux-gnu/libk5crypto.so.3.1
7f29afc48000-7f29afc49000 rw-p 00030000 103:09 401964                    /usr/lib/x86_64-linux-gnu/libk5crypto.so.3.1
7f29afc49000-7f29afc4a000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29afc4a000-7f29afd10000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401970                    /usr/lib/x86_64-linux-gnu/libkrb5.so.3.3
7f29afd10000-7f29aff10000 ---p 000c6000 103:09 401970                    /usr/lib/x86_64-linux-gnu/libkrb5.so.3.3
7f29aff10000-7f29aff1e000 r--p 000c6000 103:09 401970                    /usr/lib/x86_64-linux-gnu/libkrb5.so.3.3
7f29aff1e000-7f29aff20000 rw-p 000d4000 103:09 401970                    /usr/lib/x86_64-linux-gnu/libkrb5.so.3.3
7f29aff20000-7f29aff54000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402073                    /usr/lib/x86_64-linux-gnu/libnettle.so.6.4
7f29aff54000-7f29b0153000 ---p 00034000 103:09 402073                    /usr/lib/x86_64-linux-gnu/libnettle.so.6.4
7f29b0153000-7f29b0155000 r--p 00033000 103:09 402073                    /usr/lib/x86_64-linux-gnu/libnettle.so.6.4
7f29b0155000-7f29b0156000 rw-p 00035000 103:09 402073                    /usr/lib/x86_64-linux-gnu/libnettle.so.6.4
7f29b0156000-7f29b0189000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401871                    /usr/lib/x86_64-linux-gnu/libhogweed.so.4.4
7f29b0189000-7f29b0388000 ---p 00033000 103:09 401871                    /usr/lib/x86_64-linux-gnu/libhogweed.so.4.4
7f29b0388000-7f29b0389000 r--p 00032000 103:09 401871                    /usr/lib/x86_64-linux-gnu/libhogweed.so.4.4
7f29b0389000-7f29b038a000 rw-p 00033000 103:09 401871                    /usr/lib/x86_64-linux-gnu/libhogweed.so.4.4
7f29b038a000-7f29b04e2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 393992                    /usr/lib/x86_64-linux-gnu/libgnutls.so.30.14.10
7f29b04e2000-7f29b06e1000 ---p 00158000 103:09 393992                    /usr/lib/x86_64-linux-gnu/libgnutls.so.30.14.10
7f29b06e1000-7f29b06ed000 r--p 00157000 103:09 393992                    /usr/lib/x86_64-linux-gnu/libgnutls.so.30.14.10
7f29b06ed000-7f29b06ee000 rw-p 00163000 103:09 393992                    /usr/lib/x86_64-linux-gnu/libgnutls.so.30.14.10
7f29b06ee000-7f29b06ef000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b06ef000-7f29b0869000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402367                    /usr/lib/x86_64-linux-gnu/libunistring.so.2.1.0
7f29b0869000-7f29b0a69000 ---p 0017a000 103:09 402367                    /usr/lib/x86_64-linux-gnu/libunistring.so.2.1.0
7f29b0a69000-7f29b0a6c000 r--p 0017a000 103:09 402367                    /usr/lib/x86_64-linux-gnu/libunistring.so.2.1.0
7f29b0a6c000-7f29b0a6d000 rw-p 0017d000 103:09 402367                    /usr/lib/x86_64-linux-gnu/libunistring.so.2.1.0
7f29b0a6d000-7f29b0ba0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402501                    /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0
7f29b0ba0000-7f29b0da0000 ---p 00133000 103:09 402501                    /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0
7f29b0da0000-7f29b0da1000 r--p 00133000 103:09 402501                    /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0
7f29b0da1000-7f29b0da5000 rw-p 00134000 103:09 402501                    /usr/lib/x86_64-linux-gnu/libX11.so.6.3.0
7f29b0da5000-7f29b0db2000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401977                    /usr/lib/x86_64-linux-gnu/liblber-2.4.so.2.10.8
7f29b0db2000-7f29b0fb1000 ---p 0000d000 103:09 401977                    /usr/lib/x86_64-linux-gnu/liblber-2.4.so.2.10.8
7f29b0fb1000-7f29b0fb2000 r--p 0000c000 103:09 401977                    /usr/lib/x86_64-linux-gnu/liblber-2.4.so.2.10.8
7f29b0fb2000-7f29b0fb3000 rw-p 0000d000 103:09 401977                    /usr/lib/x86_64-linux-gnu/liblber-2.4.so.2.10.8
7f29b0fb3000-7f29b1001000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401981                    /usr/lib/x86_64-linux-gnu/libldap_r-2.4.so.2.10.8
7f29b1001000-7f29b1200000 ---p 0004e000 103:09 401981                    /usr/lib/x86_64-linux-gnu/libldap_r-2.4.so.2.10.8
7f29b1200000-7f29b1202000 r--p 0004d000 103:09 401981                    /usr/lib/x86_64-linux-gnu/libldap_r-2.4.so.2.10.8
7f29b1202000-7f29b1203000 rw-p 0004f000 103:09 401981                    /usr/lib/x86_64-linux-gnu/libldap_r-2.4.so.2.10.8
7f29b1203000-7f29b1205000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b1205000-7f29b124d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401794                    /usr/lib/x86_64-linux-gnu/libgssapi_krb5.so.2.2
7f29b124d000-7f29b144c000 ---p 00048000 103:09 401794                    /usr/lib/x86_64-linux-gnu/libgssapi_krb5.so.2.2
7f29b144c000-7f29b144e000 r--p 00047000 103:09 401794                    /usr/lib/x86_64-linux-gnu/libgssapi_krb5.so.2.2
7f29b144e000-7f29b1450000 rw-p 00049000 103:09 401794                    /usr/lib/x86_64-linux-gnu/libgssapi_krb5.so.2.2
7f29b1450000-7f29b16eb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397175                    /usr/lib/x86_64-linux-gnu/libcrypto.so.1.1
7f29b16eb000-7f29b18ea000 ---p 0029b000 103:09 397175                    /usr/lib/x86_64-linux-gnu/libcrypto.so.1.1
7f29b18ea000-7f29b1916000 r--p 0029a000 103:09 397175                    /usr/lib/x86_64-linux-gnu/libcrypto.so.1.1
7f29b1916000-7f29b1918000 rw-p 002c6000 103:09 397175                    /usr/lib/x86_64-linux-gnu/libcrypto.so.1.1
7f29b1918000-7f29b191b000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b191b000-7f29b199b000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397227                    /usr/lib/x86_64-linux-gnu/libssl.so.1.1
7f29b199b000-7f29b1b9b000 ---p 00080000 103:09 397227                    /usr/lib/x86_64-linux-gnu/libssl.so.1.1
7f29b1b9b000-7f29b1ba4000 r--p 00080000 103:09 397227                    /usr/lib/x86_64-linux-gnu/libssl.so.1.1
7f29b1ba4000-7f29b1ba8000 rw-p 00089000 103:09 397227                    /usr/lib/x86_64-linux-gnu/libssl.so.1.1
7f29b1ba8000-7f29b1bb5000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402177                    /usr/lib/x86_64-linux-gnu/libpsl.so.5.2.0
7f29b1bb5000-7f29b1db4000 ---p 0000d000 103:09 402177                    /usr/lib/x86_64-linux-gnu/libpsl.so.5.2.0
7f29b1db4000-7f29b1db5000 r--p 0000c000 103:09 402177                    /usr/lib/x86_64-linux-gnu/libpsl.so.5.2.0
7f29b1db5000-7f29b1db6000 rw-p 0000d000 103:09 402177                    /usr/lib/x86_64-linux-gnu/libpsl.so.5.2.0
7f29b1db6000-7f29b1dd1000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402235                    /usr/lib/x86_64-linux-gnu/librtmp.so.1
7f29b1dd1000-7f29b1fd0000 ---p 0001b000 103:09 402235                    /usr/lib/x86_64-linux-gnu/librtmp.so.1
7f29b1fd0000-7f29b1fd1000 r--p 0001a000 103:09 402235                    /usr/lib/x86_64-linux-gnu/librtmp.so.1
7f29b1fd1000-7f29b1fd2000 rw-p 0001b000 103:09 402235                    /usr/lib/x86_64-linux-gnu/librtmp.so.1
7f29b1fd2000-7f29b1fee000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401913                    /usr/lib/x86_64-linux-gnu/libidn2.so.0.3.3
7f29b1fee000-7f29b21ed000 ---p 0001c000 103:09 401913                    /usr/lib/x86_64-linux-gnu/libidn2.so.0.3.3
7f29b21ed000-7f29b21ee000 r--p 0001b000 103:09 401913                    /usr/lib/x86_64-linux-gnu/libidn2.so.0.3.3
7f29b21ee000-7f29b21ef000 rw-p 0001c000 103:09 401913                    /usr/lib/x86_64-linux-gnu/libidn2.so.0.3.3
7f29b21ef000-7f29b2212000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402077                    /usr/lib/x86_64-linux-gnu/libnghttp2.so.14.15.2
7f29b2212000-7f29b2411000 ---p 00023000 103:09 402077                    /usr/lib/x86_64-linux-gnu/libnghttp2.so.14.15.2
7f29b2411000-7f29b2412000 r--p 00022000 103:09 402077                    /usr/lib/x86_64-linux-gnu/libnghttp2.so.14.15.2
7f29b2412000-7f29b2414000 rw-p 00023000 103:09 402077                    /usr/lib/x86_64-linux-gnu/libnghttp2.so.14.15.2
7f29b2414000-7f29b2484000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840156                   /lib/x86_64-linux-gnu/libpcre.so.3.13.3
7f29b2484000-7f29b2684000 ---p 00070000 103:09 1840156                   /lib/x86_64-linux-gnu/libpcre.so.3.13.3
7f29b2684000-7f29b2685000 r--p 00070000 103:09 1840156                   /lib/x86_64-linux-gnu/libpcre.so.3.13.3
7f29b2685000-7f29b2686000 rw-p 00071000 103:09 1840156                   /lib/x86_64-linux-gnu/libpcre.so.3.13.3
7f29b2686000-7f29b402e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401901                    /usr/lib/x86_64-linux-gnu/libicudata.so.60.2
7f29b402e000-7f29b422d000 ---p 019a8000 103:09 401901                    /usr/lib/x86_64-linux-gnu/libicudata.so.60.2
7f29b422d000-7f29b422e000 r--p 019a7000 103:09 401901                    /usr/lib/x86_64-linux-gnu/libicudata.so.60.2
7f29b422e000-7f29b422f000 rw-p 019a8000 103:09 401901                    /usr/lib/x86_64-linux-gnu/libicudata.so.60.2
7f29b422f000-7f29b4236000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840175                   /lib/x86_64-linux-gnu/librt-2.27.so
7f29b4236000-7f29b4435000 ---p 00007000 103:09 1840175                   /lib/x86_64-linux-gnu/librt-2.27.so
7f29b4435000-7f29b4436000 r--p 00006000 103:09 1840175                   /lib/x86_64-linux-gnu/librt-2.27.so
7f29b4436000-7f29b4437000 rw-p 00007000 103:09 1840175                   /lib/x86_64-linux-gnu/librt-2.27.so
7f29b4437000-7f29b44b4000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404778                    /usr/lib/x86_64-linux-gnu/libnorm.so.1.0.0
7f29b44b4000-7f29b46b4000 ---p 0007d000 103:09 404778                    /usr/lib/x86_64-linux-gnu/libnorm.so.1.0.0
7f29b46b4000-7f29b46b6000 r--p 0007d000 103:09 404778                    /usr/lib/x86_64-linux-gnu/libnorm.so.1.0.0
7f29b46b6000-7f29b46b7000 rw-p 0007f000 103:09 404778                    /usr/lib/x86_64-linux-gnu/libnorm.so.1.0.0
7f29b46b7000-7f29b4767000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b4767000-7f29b47ae000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404780                    /usr/lib/x86_64-linux-gnu/libpgm-5.2.so.0.0.122
7f29b47ae000-7f29b49ad000 ---p 00047000 103:09 404780                    /usr/lib/x86_64-linux-gnu/libpgm-5.2.so.0.0.122
7f29b49ad000-7f29b49ae000 r--p 00046000 103:09 404780                    /usr/lib/x86_64-linux-gnu/libpgm-5.2.so.0.0.122
7f29b49ae000-7f29b49af000 rw-p 00047000 103:09 404780                    /usr/lib/x86_64-linux-gnu/libpgm-5.2.so.0.0.122
7f29b49af000-7f29b49b3000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b49b3000-7f29b4a03000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402289                    /usr/lib/x86_64-linux-gnu/libsodium.so.23.1.0
7f29b4a03000-7f29b4c02000 ---p 00050000 103:09 402289                    /usr/lib/x86_64-linux-gnu/libsodium.so.23.1.0
7f29b4c02000-7f29b4c03000 r--p 0004f000 103:09 402289                    /usr/lib/x86_64-linux-gnu/libsodium.so.23.1.0
7f29b4c03000-7f29b4c04000 rw-p 00050000 103:09 402289                    /usr/lib/x86_64-linux-gnu/libsodium.so.23.1.0
7f29b4c04000-7f29b4c2f000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401780                    /usr/lib/x86_64-linux-gnu/libgraphite2.so.3.0.1
7f29b4c2f000-7f29b4e2e000 ---p 0002b000 103:09 401780                    /usr/lib/x86_64-linux-gnu/libgraphite2.so.3.0.1
7f29b4e2e000-7f29b4e30000 r--p 0002a000 103:09 401780                    /usr/lib/x86_64-linux-gnu/libgraphite2.so.3.0.1
7f29b4e30000-7f29b4e31000 rw-p 0002c000 103:09 401780                    /usr/lib/x86_64-linux-gnu/libgraphite2.so.3.0.1
7f29b4e31000-7f29b4ede000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401669                    /usr/lib/x86_64-linux-gnu/libfreetype.so.6.15.0
7f29b4ede000-7f29b50dd000 ---p 000ad000 103:09 401669                    /usr/lib/x86_64-linux-gnu/libfreetype.so.6.15.0
7f29b50dd000-7f29b50e4000 r--p 000ac000 103:09 401669                    /usr/lib/x86_64-linux-gnu/libfreetype.so.6.15.0
7f29b50e4000-7f29b50e5000 rw-p 000b3000 103:09 401669                    /usr/lib/x86_64-linux-gnu/libfreetype.so.6.15.0
7f29b50e5000-7f29b5153000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400759                    /usr/lib/x86_64-linux-gnu/libGLdispatch.so.0.0.0
7f29b5153000-7f29b5352000 ---p 0006e000 103:09 400759                    /usr/lib/x86_64-linux-gnu/libGLdispatch.so.0.0.0
7f29b5352000-7f29b537a000 r--p 0006d000 103:09 400759                    /usr/lib/x86_64-linux-gnu/libGLdispatch.so.0.0.0
7f29b537a000-7f29b537b000 rw-p 00095000 103:09 400759                    /usr/lib/x86_64-linux-gnu/libGLdispatch.so.0.0.0
7f29b537b000-7f29b539b000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b539b000-7f29b53ab000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400752                    /usr/lib/x86_64-linux-gnu/libGLX.so.0.0.0
7f29b53ab000-7f29b55aa000 ---p 00010000 103:09 400752                    /usr/lib/x86_64-linux-gnu/libGLX.so.0.0.0
7f29b55aa000-7f29b55ab000 r--p 0000f000 103:09 400752                    /usr/lib/x86_64-linux-gnu/libGLX.so.0.0.0
7f29b55ab000-7f29b55ac000 rw-p 00010000 103:09 400752                    /usr/lib/x86_64-linux-gnu/libGLX.so.0.0.0
7f29b55ac000-7f29b55cc000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b55cc000-7f29b55df000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404826                    /usr/lib/x86_64-linux-gnu/libzip.so.4.0.0
7f29b55df000-7f29b57de000 ---p 00013000 103:09 404826                    /usr/lib/x86_64-linux-gnu/libzip.so.4.0.0
7f29b57de000-7f29b57df000 r--p 00012000 103:09 404826                    /usr/lib/x86_64-linux-gnu/libzip.so.4.0.0
7f29b57df000-7f29b57e0000 rw-p 00013000 103:09 404826                    /usr/lib/x86_64-linux-gnu/libzip.so.4.0.0
7f29b57e0000-7f29b5811000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402993                    /usr/lib/x86_64-linux-gnu/libjsoncpp.so.1.7.4
7f29b5811000-7f29b5a10000 ---p 00031000 103:09 402993                    /usr/lib/x86_64-linux-gnu/libjsoncpp.so.1.7.4
7f29b5a10000-7f29b5a11000 r--p 00030000 103:09 402993                    /usr/lib/x86_64-linux-gnu/libjsoncpp.so.1.7.4
7f29b5a11000-7f29b5a12000 rw-p 00031000 103:09 402993                    /usr/lib/x86_64-linux-gnu/libjsoncpp.so.1.7.4
7f29b5a12000-7f29b5a8d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397280                    /usr/lib/x86_64-linux-gnu/libcurl.so.4.5.0
7f29b5a8d000-7f29b5c8d000 ---p 0007b000 103:09 397280                    /usr/lib/x86_64-linux-gnu/libcurl.so.4.5.0
7f29b5c8d000-7f29b5c90000 r--p 0007b000 103:09 397280                    /usr/lib/x86_64-linux-gnu/libcurl.so.4.5.0
7f29b5c90000-7f29b5c91000 rw-p 0007e000 103:09 397280                    /usr/lib/x86_64-linux-gnu/libcurl.so.4.5.0
7f29b5c91000-7f29b5ca5000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400690                    /usr/lib/x86_64-linux-gnu/libtinyxml.so.2.6.2
7f29b5ca5000-7f29b5ea4000 ---p 00014000 103:09 400690                    /usr/lib/x86_64-linux-gnu/libtinyxml.so.2.6.2
7f29b5ea4000-7f29b5ea5000 r--p 00013000 103:09 400690                    /usr/lib/x86_64-linux-gnu/libtinyxml.so.2.6.2
7f29b5ea5000-7f29b5ea6000 rw-p 00014000 103:09 400690                    /usr/lib/x86_64-linux-gnu/libtinyxml.so.2.6.2
7f29b5ea6000-7f29b5fba000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397216                    /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0.5600.4
7f29b5fba000-7f29b61ba000 ---p 00114000 103:09 397216                    /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0.5600.4
7f29b61ba000-7f29b61bb000 r--p 00114000 103:09 397216                    /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0.5600.4
7f29b61bb000-7f29b61bc000 rw-p 00115000 103:09 397216                    /usr/lib/x86_64-linux-gnu/libglib-2.0.so.0.5600.4
7f29b61bc000-7f29b61bd000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b61bd000-7f29b61cd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400520                    /usr/lib/x86_64-linux-gnu/libdouble-conversion.so.1.0
7f29b61cd000-7f29b63cc000 ---p 00010000 103:09 400520                    /usr/lib/x86_64-linux-gnu/libdouble-conversion.so.1.0
7f29b63cc000-7f29b63cd000 r--p 0000f000 103:09 400520                    /usr/lib/x86_64-linux-gnu/libdouble-conversion.so.1.0
7f29b63cd000-7f29b63ce000 rw-p 00010000 103:09 400520                    /usr/lib/x86_64-linux-gnu/libdouble-conversion.so.1.0
7f29b63ce000-7f29b6571000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401911                    /usr/lib/x86_64-linux-gnu/libicuuc.so.60.2
7f29b6571000-7f29b6770000 ---p 001a3000 103:09 401911                    /usr/lib/x86_64-linux-gnu/libicuuc.so.60.2
7f29b6770000-7f29b6783000 r--p 001a2000 103:09 401911                    /usr/lib/x86_64-linux-gnu/libicuuc.so.60.2
7f29b6783000-7f29b6784000 rw-p 001b5000 103:09 401911                    /usr/lib/x86_64-linux-gnu/libicuuc.so.60.2
7f29b6784000-7f29b6785000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b6785000-7f29b6a17000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401903                    /usr/lib/x86_64-linux-gnu/libicui18n.so.60.2
7f29b6a17000-7f29b6c16000 ---p 00292000 103:09 401903                    /usr/lib/x86_64-linux-gnu/libicui18n.so.60.2
7f29b6c16000-7f29b6c25000 r--p 00291000 103:09 401903                    /usr/lib/x86_64-linux-gnu/libicui18n.so.60.2
7f29b6c25000-7f29b6c26000 rw-p 002a0000 103:09 401903                    /usr/lib/x86_64-linux-gnu/libicui18n.so.60.2
7f29b6c26000-7f29b6cb9000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 397188                    /usr/lib/x86_64-linux-gnu/libzmq.so.5.1.5
7f29b6cb9000-7f29b6eb9000 ---p 00093000 103:09 397188                    /usr/lib/x86_64-linux-gnu/libzmq.so.5.1.5
7f29b6eb9000-7f29b6ebf000 r--p 00093000 103:09 397188                    /usr/lib/x86_64-linux-gnu/libzmq.so.5.1.5
7f29b6ebf000-7f29b6ec0000 rw-p 00099000 103:09 397188                    /usr/lib/x86_64-linux-gnu/libzmq.so.5.1.5
7f29b6ec0000-7f29b6edc000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840206                   /lib/x86_64-linux-gnu/libz.so.1.2.11
7f29b6edc000-7f29b70db000 ---p 0001c000 103:09 1840206                   /lib/x86_64-linux-gnu/libz.so.1.2.11
7f29b70db000-7f29b70dc000 r--p 0001b000 103:09 1840206                   /lib/x86_64-linux-gnu/libz.so.1.2.11
7f29b70dc000-7f29b70dd000 rw-p 0001c000 103:09 1840206                   /lib/x86_64-linux-gnu/libz.so.1.2.11
7f29b70dd000-7f29b7179000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401863                    /usr/lib/x86_64-linux-gnu/libharfbuzz.so.0.10702.0
7f29b7179000-7f29b7379000 ---p 0009c000 103:09 401863                    /usr/lib/x86_64-linux-gnu/libharfbuzz.so.0.10702.0
7f29b7379000-7f29b737a000 r--p 0009c000 103:09 401863                    /usr/lib/x86_64-linux-gnu/libharfbuzz.so.0.10702.0
7f29b737a000-7f29b737b000 rw-p 0009d000 103:09 401863                    /usr/lib/x86_64-linux-gnu/libharfbuzz.so.0.10702.0
7f29b737b000-7f29b73ac000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 403380                    /usr/lib/x86_64-linux-gnu/libpng16.so.16.34.0
7f29b73ac000-7f29b75ab000 ---p 00031000 103:09 403380                    /usr/lib/x86_64-linux-gnu/libpng16.so.16.34.0
7f29b75ab000-7f29b75ac000 r--p 00030000 103:09 403380                    /usr/lib/x86_64-linux-gnu/libpng16.so.16.34.0
7f29b75ac000-7f29b75ad000 rw-p 00031000 103:09 403380                    /usr/lib/x86_64-linux-gnu/libpng16.so.16.34.0
7f29b75ad000-7f29b761e000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400747                    /usr/lib/x86_64-linux-gnu/libGL.so.1.0.0
7f29b761e000-7f29b781d000 ---p 00071000 103:09 400747                    /usr/lib/x86_64-linux-gnu/libGL.so.1.0.0
7f29b781d000-7f29b7837000 r--p 00070000 103:09 400747                    /usr/lib/x86_64-linux-gnu/libGL.so.1.0.0
7f29b7837000-7f29b7838000 rw-p 0008a000 103:09 400747                    /usr/lib/x86_64-linux-gnu/libGL.so.1.0.0
7f29b7838000-7f29b7839000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b7839000-7f29b79bc000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398876                    /usr/lib/x86_64-linux-gnu/libQt5Network.so.5.9.5
7f29b79bc000-7f29b7bbc000 ---p 00183000 103:09 398876                    /usr/lib/x86_64-linux-gnu/libQt5Network.so.5.9.5
7f29b7bbc000-7f29b7bc2000 r--p 00183000 103:09 398876                    /usr/lib/x86_64-linux-gnu/libQt5Network.so.5.9.5
7f29b7bc2000-7f29b7bc4000 rw-p 00189000 103:09 398876                    /usr/lib/x86_64-linux-gnu/libQt5Network.so.5.9.5
7f29b7bc4000-7f29b7bc5000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b7bc5000-7f29b7bcb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1836457                   /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7f29b7bcb000-7f29b7dca000 ---p 00006000 103:09 1836457                   /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7f29b7dca000-7f29b7dcb000 r--p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 1836457                   /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7f29b7dcb000-7f29b7dcc000 rw-p 00006000 103:09 1836457                   /lib/x86_64-linux-gnu/libuuid.so.1.3.0
7f29b7dcc000-7f29b7dd0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398633                    /usr/lib/x86_64-linux-gnu/libignition-common3-events.so.3.3.0
7f29b7dd0000-7f29b7fcf000 ---p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 398633                    /usr/lib/x86_64-linux-gnu/libignition-common3-events.so.3.3.0
7f29b7fcf000-7f29b7fd0000 r--p d72edde1b5da441a550262cce0ea172460bf453d 103:09 398633                    /usr/lib/x86_64-linux-gnu/libignition-common3-events.so.3.3.0
7f29b7fd0000-7f29b7fd1000 rw-p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 398633                    /usr/lib/x86_64-linux-gnu/libignition-common3-events.so.3.3.0
7f29b7fd1000-7f29b7fda000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398680                    /usr/lib/x86_64-linux-gnu/libignition-plugin1.so.1.0.0
7f29b7fda000-7f29b81da000 ---p 00009000 103:09 398680                    /usr/lib/x86_64-linux-gnu/libignition-plugin1.so.1.0.0
7f29b81da000-7f29b81db000 r--p 00009000 103:09 398680                    /usr/lib/x86_64-linux-gnu/libignition-plugin1.so.1.0.0
7f29b81db000-7f29b81dc000 rw-p 0000a000 103:09 398680                    /usr/lib/x86_64-linux-gnu/libignition-plugin1.so.1.0.0
7f29b81dc000-7f29b81ee000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398679                    /usr/lib/x86_64-linux-gnu/libignition-plugin1-loader.so.1.0.0
7f29b81ee000-7f29b83ed000 ---p 00012000 103:09 398679                    /usr/lib/x86_64-linux-gnu/libignition-plugin1-loader.so.1.0.0
7f29b83ed000-7f29b83ee000 r--p 00011000 103:09 398679                    /usr/lib/x86_64-linux-gnu/libignition-plugin1-loader.so.1.0.0
7f29b83ee000-7f29b83ef000 rw-p 00012000 103:09 398679                    /usr/lib/x86_64-linux-gnu/libignition-plugin1-loader.so.1.0.0
7f29b83ef000-7f29b845b000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398644                    /usr/lib/x86_64-linux-gnu/libignition-fuel_tools3.so.3.2.1
7f29b845b000-7f29b865b000 ---p 0006c000 103:09 398644                    /usr/lib/x86_64-linux-gnu/libignition-fuel_tools3.so.3.2.1
7f29b865b000-7f29b865c000 r--p 0006c000 103:09 398644                    /usr/lib/x86_64-linux-gnu/libignition-fuel_tools3.so.3.2.1
7f29b865c000-7f29b865d000 rw-p 0006d000 103:09 398644                    /usr/lib/x86_64-linux-gnu/libignition-fuel_tools3.so.3.2.1
7f29b865d000-7f29b8690000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398966                    /usr/lib/x86_64-linux-gnu/libignition-math6.so.6.4.0
7f29b8690000-7f29b8890000 ---p 00033000 103:09 398966                    /usr/lib/x86_64-linux-gnu/libignition-math6.so.6.4.0
7f29b8890000-7f29b8891000 r--p 00033000 103:09 398966                    /usr/lib/x86_64-linux-gnu/libignition-math6.so.6.4.0
7f29b8891000-7f29b8892000 rw-p 00034000 103:09 398966                    /usr/lib/x86_64-linux-gnu/libignition-math6.so.6.4.0
7f29b8892000-7f29b8893000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b8893000-7f29b8a04000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398992                    /usr/lib/x86_64-linux-gnu/libsdformat8.so.8.4.0
7f29b8a04000-7f29b8c04000 ---p 00171000 103:09 398992                    /usr/lib/x86_64-linux-gnu/libsdformat8.so.8.4.0
7f29b8c04000-7f29b8c06000 r--p 00171000 103:09 398992                    /usr/lib/x86_64-linux-gnu/libsdformat8.so.8.4.0
7f29b8c06000-7f29b8c08000 rw-p 00173000 103:09 398992                    /usr/lib/x86_64-linux-gnu/libsdformat8.so.8.4.0
7f29b8c08000-7f29b8c09000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b8c09000-7f29b8c20000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1839973                   /lib/x86_64-linux-gnu/libgcc_s.so.1
7f29b8c20000-7f29b8e1f000 ---p 00017000 103:09 1839973                   /lib/x86_64-linux-gnu/libgcc_s.so.1
7f29b8e1f000-7f29b8e20000 r--p 00016000 103:09 1839973                   /lib/x86_64-linux-gnu/libgcc_s.so.1
7f29b8e20000-7f29b8e21000 rw-p 00017000 103:09 1839973                   /lib/x86_64-linux-gnu/libgcc_s.so.1
7f29b8e21000-7f29b8f9a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400516                    /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.25
7f29b8f9a000-7f29b919a000 ---p 00179000 103:09 400516                    /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.25
7f29b919a000-7f29b91a4000 r--p 00179000 103:09 400516                    /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.25
7f29b91a4000-7f29b91a6000 rw-p 00183000 103:09 400516                    /usr/lib/x86_64-linux-gnu/libstdc++.so.6.0.25
7f29b91a6000-7f29b91aa000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b91aa000-7f29b96e5000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398866                    /usr/lib/x86_64-linux-gnu/libQt5Core.so.5.9.5
7f29b96e5000-7f29b98e4000 ---p 0053b000 103:09 398866                    /usr/lib/x86_64-linux-gnu/libQt5Core.so.5.9.5
7f29b98e4000-7f29b98f0000 r--p 0053a000 103:09 398866                    /usr/lib/x86_64-linux-gnu/libQt5Core.so.5.9.5
7f29b98f0000-7f29b98f2000 rw-p 00546000 103:09 398866                    /usr/lib/x86_64-linux-gnu/libQt5Core.so.5.9.5
7f29b98f2000-7f29b98f5000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29b98f5000-7f29b9b45000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402173                    /usr/lib/x86_64-linux-gnu/libprotobuf.so.10.0.0
7f29b9b45000-7f29b9d45000 ---p 00250000 103:09 402173                    /usr/lib/x86_64-linux-gnu/libprotobuf.so.10.0.0
7f29b9d45000-7f29b9d4d000 r--p 00250000 103:09 402173                    /usr/lib/x86_64-linux-gnu/libprotobuf.so.10.0.0
7f29b9d4d000-7f29b9d4e000 rw-p 00258000 103:09 402173                    /usr/lib/x86_64-linux-gnu/libprotobuf.so.10.0.0
7f29b9d4e000-7f29ba02c000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398973                    /usr/lib/x86_64-linux-gnu/libignition-msgs4.so.4.7.0
7f29ba02c000-7f29ba22c000 ---p 002de000 103:09 398973                    /usr/lib/x86_64-linux-gnu/libignition-msgs4.so.4.7.0
7f29ba22c000-7f29ba23a000 r--p 002de000 103:09 398973                    /usr/lib/x86_64-linux-gnu/libignition-msgs4.so.4.7.0
7f29ba23a000-7f29ba23b000 rw-p 002ec000 103:09 398973                    /usr/lib/x86_64-linux-gnu/libignition-msgs4.so.4.7.0
7f29ba23b000-7f29ba23d000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29ba23d000-7f29ba2bb000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398975                    /usr/lib/x86_64-linux-gnu/libignition-transport7.so.7.1.0
7f29ba2bb000-7f29ba4ba000 ---p 0007e000 103:09 398975                    /usr/lib/x86_64-linux-gnu/libignition-transport7.so.7.1.0
7f29ba4ba000-7f29ba4bc000 r--p 0007d000 103:09 398975                    /usr/lib/x86_64-linux-gnu/libignition-transport7.so.7.1.0
7f29ba4bc000-7f29ba4bd000 rw-p 0007f000 103:09 398975                    /usr/lib/x86_64-linux-gnu/libignition-transport7.so.7.1.0
7f29ba4bd000-7f29ba4cf000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 404822                    /usr/lib/x86_64-linux-gnu/libtinyxml2.so.6.0.0
7f29ba4cf000-7f29ba6cf000 ---p 00012000 103:09 404822                    /usr/lib/x86_64-linux-gnu/libtinyxml2.so.6.0.0
7f29ba6cf000-7f29ba6d0000 r--p 00012000 103:09 404822                    /usr/lib/x86_64-linux-gnu/libtinyxml2.so.6.0.0
7f29ba6d0000-7f29ba6d1000 rw-p 00013000 103:09 404822                    /usr/lib/x86_64-linux-gnu/libtinyxml2.so.6.0.0
7f29ba6d1000-7f29bac20000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398888                    /usr/lib/x86_64-linux-gnu/libQt5Gui.so.5.9.5
7f29bac20000-7f29bae20000 ---p 0054f000 103:09 398888                    /usr/lib/x86_64-linux-gnu/libQt5Gui.so.5.9.5
7f29bae20000-7f29bae2f000 r--p 0054f000 103:09 398888                    /usr/lib/x86_64-linux-gnu/libQt5Gui.so.5.9.5
7f29bae2f000-7f29bae35000 rw-p 0055e000 103:09 398888                    /usr/lib/x86_64-linux-gnu/libQt5Gui.so.5.9.5
7f29bae35000-7f29bae3a000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bae3a000-7f29bb21d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400560                    /usr/lib/x86_64-linux-gnu/libQt5Qml.so.5.9.5
7f29bb21d000-7f29bb41d000 ---p 003e3000 103:09 400560                    /usr/lib/x86_64-linux-gnu/libQt5Qml.so.5.9.5
7f29bb41d000-7f29bb42e000 r--p 003e3000 103:09 400560                    /usr/lib/x86_64-linux-gnu/libQt5Qml.so.5.9.5
7f29bb42e000-7f29bb434000 rw-p 003f4000 103:09 400560                    /usr/lib/x86_64-linux-gnu/libQt5Qml.so.5.9.5
7f29bb434000-7f29bb437000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bb437000-7f29bb858000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400563                    /usr/lib/x86_64-linux-gnu/libQt5Quick.so.5.9.5
7f29bb858000-7f29bba58000 ---p 00421000 103:09 400563                    /usr/lib/x86_64-linux-gnu/libQt5Quick.so.5.9.5
7f29bba58000-7f29bba7a000 r--p 00421000 103:09 400563                    /usr/lib/x86_64-linux-gnu/libQt5Quick.so.5.9.5
7f29bba7a000-7f29bba7f000 rw-p 00443000 103:09 400563                    /usr/lib/x86_64-linux-gnu/libQt5Quick.so.5.9.5
7f29bba7f000-7f29bba80000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bba80000-7f29bbac1000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 393347                    /usr/lib/x86_64-linux-gnu/libignition-common3.so.3.3.0
7f29bbac1000-7f29bbcc1000 ---p 00041000 103:09 393347                    /usr/lib/x86_64-linux-gnu/libignition-common3.so.3.3.0
7f29bbcc1000-7f29bbcc2000 r--p 00041000 103:09 393347                    /usr/lib/x86_64-linux-gnu/libignition-common3.so.3.3.0
7f29bbcc2000-7f29bbcc3000 rw-p 00042000 103:09 393347                    /usr/lib/x86_64-linux-gnu/libignition-common3.so.3.3.0
7f29bbcc3000-7f29bbcff000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 398988                    /usr/lib/x86_64-linux-gnu/libignition-gui2.so.2.0.1
7f29bbcff000-7f29bbefe000 ---p 0003c000 103:09 398988                    /usr/lib/x86_64-linux-gnu/libignition-gui2.so.2.0.1
7f29bbefe000-7f29bbeff000 r--p 0003b000 103:09 398988                    /usr/lib/x86_64-linux-gnu/libignition-gui2.so.2.0.1
7f29bbeff000-7f29bbf00000 rw-p 0003c000 103:09 398988                    /usr/lib/x86_64-linux-gnu/libignition-gui2.so.2.0.1
7f29bbf00000-7f29bc0c3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399061                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2.so.2.11.0
7f29bc0c3000-7f29bc2c3000 ---p 001c3000 103:09 399061                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2.so.2.11.0
7f29bc2c3000-7f29bc2cc000 r--p 001c3000 103:09 399061                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2.so.2.11.0
7f29bc2cc000-7f29bc2ce000 rw-p 001cc000 103:09 399061                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2.so.2.11.0
7f29bc2ce000-7f29bc2d0000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bc2d0000-7f29bc4a4000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399042                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-gui.so.2.11.0
7f29bc4a4000-7f29bc6a3000 ---p 001d4000 103:09 399042                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-gui.so.2.11.0
7f29bc6a3000-7f29bc6ab000 r--p 001d3000 103:09 399042                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-gui.so.2.11.0
7f29bc6ab000-7f29bc6ac000 rw-p 001db000 103:09 399042                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-gui.so.2.11.0
7f29bc6ac000-7f29bc6ad000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bc6ad000-7f29bc6c3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 399043                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-ign.so.2.11.0
7f29bc6c3000-7f29bc8c2000 ---p 00016000 103:09 399043                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-ign.so.2.11.0
7f29bc8c2000-7f29bc8c3000 r--p 00015000 103:09 399043                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-ign.so.2.11.0
7f29bc8c3000-7f29bc8c4000 rw-p 00016000 103:09 399043                    /usr/lib/x86_64-linux-gnu/libignition-gazebo2-ign.so.2.11.0
7f29bc8c4000-7f29bc8c7000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553633                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/cgi/escape.so
7f29bc8c7000-7f29bcac6000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 553633                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/cgi/escape.so
7f29bcac6000-7f29bcac7000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 553633                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/cgi/escape.so
7f29bcac7000-7f29bcac8000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 553633                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/cgi/escape.so
7f29bcac8000-7f29bcacf000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401637                    /usr/lib/x86_64-linux-gnu/libffi.so.6.0.4
7f29bcacf000-7f29bccce000 ---p 00007000 103:09 401637                    /usr/lib/x86_64-linux-gnu/libffi.so.6.0.4
7f29bccce000-7f29bcccf000 r--p 00006000 103:09 401637                    /usr/lib/x86_64-linux-gnu/libffi.so.6.0.4
7f29bcccf000-7f29bccd0000 rw-p 00007000 103:09 401637                    /usr/lib/x86_64-linux-gnu/libffi.so.6.0.4
7f29bccd0000-7f29bccd8000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553647                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/fiddle.so
7f29bccd8000-7f29bced8000 ---p 00008000 103:09 553647                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/fiddle.so
7f29bced8000-7f29bced9000 r--p 00008000 103:09 553647                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/fiddle.so
7f29bced9000-7f29bceda000 rw-p 00009000 103:09 553647                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/fiddle.so
7f29bceda000-7f29bcedf000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553661                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/strscan.so
7f29bcedf000-7f29bd0de000 ---p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 553661                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/strscan.so
7f29bd0de000-7f29bd0df000 r--p ffd64f1e5f65b62fdc6e1462aad6c9defee3be40 103:09 553661                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/strscan.so
7f29bd0df000-7f29bd0e0000 rw-p 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:09 553661                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/strscan.so
7f29bd0e0000-7f29bd0fd000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 402526                    /usr/lib/x86_64-linux-gnu/libyaml-0.so.2.0.5
7f29bd0fd000-7f29bd2fc000 ---p 0001d000 103:09 402526                    /usr/lib/x86_64-linux-gnu/libyaml-0.so.2.0.5
7f29bd2fc000-7f29bd2fd000 r--p 0001c000 103:09 402526                    /usr/lib/x86_64-linux-gnu/libyaml-0.so.2.0.5
7f29bd2fd000-7f29bd2fe000 rw-p 0001d000 103:09 402526                    /usr/lib/x86_64-linux-gnu/libyaml-0.so.2.0.5
7f29bd2fe000-7f29bd304000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553653                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/psych.so
7f29bd304000-7f29bd504000 ---p 00006000 103:09 553653                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/psych.so
7f29bd504000-7f29bd505000 r--p 00006000 103:09 553653                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/psych.so
7f29bd505000-7f29bd506000 rw-p 00007000 103:09 553653                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/psych.so
7f29bd506000-7f29bd50d000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 553660                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/stringio.so
7f29bd50d000-7f29bd70d000 ---p 00007000 103:09 553660                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/stringio.so
7f29bd70d000-7f29bd70e000 r--p 00007000 103:09 553660                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/stringio.so
7f29bd70e000-7f29bd70f000 rw-p 00008000 103:09 553660                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/stringio.so
7f29bd70f000-7f29bd711000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 658051                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/trans/transdb.so
7f29bd711000-7f29bd911000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 658051                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/trans/transdb.so
7f29bd911000-7f29bd912000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 658051                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/trans/transdb.so
7f29bd912000-7f29bd913000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 658051                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/trans/transdb.so
7f29bd913000-7f29bd915000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 655938                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/encdb.so
7f29bd915000-7f29bdb14000 ---p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 655938                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/encdb.so
7f29bdb14000-7f29bdb15000 r--p 234cbf2026d34890ec438b8dfc899423746a3abc 103:09 655938                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/encdb.so
7f29bdb15000-7f29bdb16000 rw-p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 655938                    /usr/lib/x86_64-linux-gnu/ruby/2.5.0/enc/encdb.so
7f29bdb16000-7f29be673000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 400070                    /usr/lib/locale/locale-archive
7f29be673000-7f29be810000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840097                   /lib/x86_64-linux-gnu/libm-2.27.so
7f29be810000-7f29bea0f000 ---p 0019d000 103:09 1840097                   /lib/x86_64-linux-gnu/libm-2.27.so
7f29bea0f000-7f29bea10000 r--p 0019c000 103:09 1840097                   /lib/x86_64-linux-gnu/libm-2.27.so
7f29bea10000-7f29bea11000 rw-p 0019d000 103:09 1840097                   /lib/x86_64-linux-gnu/libm-2.27.so
7f29bea11000-7f29bea1a000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840044                   /lib/x86_64-linux-gnu/libcrypt-2.27.so
7f29bea1a000-7f29bec19000 ---p 00009000 103:09 1840044                   /lib/x86_64-linux-gnu/libcrypt-2.27.so
7f29bec19000-7f29bec1a000 r--p 00008000 103:09 1840044                   /lib/x86_64-linux-gnu/libcrypt-2.27.so
7f29bec1a000-7f29bec1b000 rw-p 00009000 103:09 1840044                   /lib/x86_64-linux-gnu/libcrypt-2.27.so
7f29bec1b000-7f29bec49000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bec49000-7f29bec4c000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840057                   /lib/x86_64-linux-gnu/libdl-2.27.so
7f29bec4c000-7f29bee4b000 ---p d72edde1b5da441a550262cce0ea172460bf453d 103:09 1840057                   /lib/x86_64-linux-gnu/libdl-2.27.so
7f29bee4b000-7f29bee4c000 r--p cf2946d43c3d41f00c8a154e61be36948bc24ac9 103:09 1840057                   /lib/x86_64-linux-gnu/libdl-2.27.so
7f29bee4c000-7f29bee4d000 rw-p d72edde1b5da441a550262cce0ea172460bf453d 103:09 1840057                   /lib/x86_64-linux-gnu/libdl-2.27.so
7f29bee4d000-7f29beecc000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 401737                    /usr/lib/x86_64-linux-gnu/libgmp.so.10.3.2
7f29beecc000-7f29bf0cc000 ---p 0007f000 103:09 401737                    /usr/lib/x86_64-linux-gnu/libgmp.so.10.3.2
7f29bf0cc000-7f29bf0cd000 r--p 0007f000 103:09 401737                    /usr/lib/x86_64-linux-gnu/libgmp.so.10.3.2
7f29bf0cd000-7f29bf0ce000 rw-p 00080000 103:09 401737                    /usr/lib/x86_64-linux-gnu/libgmp.so.10.3.2
7f29bf0ce000-7f29bf0e8000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840167                   /lib/x86_64-linux-gnu/libpthread-2.27.so
7f29bf0e8000-7f29bf2e7000 ---p 0001a000 103:09 1840167                   /lib/x86_64-linux-gnu/libpthread-2.27.so
7f29bf2e7000-7f29bf2e8000 r--p 00019000 103:09 1840167                   /lib/x86_64-linux-gnu/libpthread-2.27.so
7f29bf2e8000-7f29bf2e9000 rw-p 0001a000 103:09 1840167                   /lib/x86_64-linux-gnu/libpthread-2.27.so
7f29bf2e9000-7f29bf2ed000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bf2ed000-7f29bf4d4000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840034                   /lib/x86_64-linux-gnu/libc-2.27.so
7f29bf4d4000-7f29bf6d4000 ---p 001e7000 103:09 1840034                   /lib/x86_64-linux-gnu/libc-2.27.so
7f29bf6d4000-7f29bf6d8000 r--p 001e7000 103:09 1840034                   /lib/x86_64-linux-gnu/libc-2.27.so
7f29bf6d8000-7f29bf6da000 rw-p 001eb000 103:09 1840034                   /lib/x86_64-linux-gnu/libc-2.27.so
7f29bf6da000-7f29bf6de000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bf6de000-7f29bf979000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 396941                    /usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5.1
7f29bf979000-7f29bfb78000 ---p 0029b000 103:09 396941                    /usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5.1
7f29bfb78000-7f29bfb7e000 r--p 0029a000 103:09 396941                    /usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5.1
7f29bfb7e000-7f29bfb7f000 rw-p 002a0000 103:09 396941                    /usr/lib/x86_64-linux-gnu/libruby-2.5.so.2.5.1
7f29bfb7f000-7f29bfb8f000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bfb8f000-7f29bfbb6000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1840006                   /lib/x86_64-linux-gnu/ld-2.27.so
7f29bfbb6000-7f29bfbb9000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525742                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/SystemPaletteSingleton.qmlc
7f29bfbb9000-7f29bfbba000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525736                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/StackView.jsc
7f29bfbba000-7f29bfbbb000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525761                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/style.jsc
7f29bfbbb000-7f29bfbbe000 r-xs 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 525704                    /usr/lib/x86_64-linux-gnu/qt5/qml/QtQuick/Controls/Private/CalendarUtils.jsc
7f29bfbbe000-7f29bfbc3000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053702                   /var/cache/fontconfig/2300eef321c393bfd76478a5c0e95b23-le64.cache-7
7f29bfbc3000-7f29bfbc4000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053695                   /var/cache/fontconfig/0d8c3b2ac0904cb8a57a757ad11a4a08-le64.cache-7
7f29bfbc4000-7f29bfbc8000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1056931                   /var/cache/fontconfig/6d41288fd70b0be22e8c3a91e032eec0-le64.cache-7
7f29bfbc8000-7f29bfbcc000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1056930                   /var/cache/fontconfig/de156ccd2eddbdc19d37a45b8b2aac9c-le64.cache-7
7f29bfbcc000-7f29bfbe1000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053691                   /var/cache/fontconfig/04aabc0a78ac019cf9454389977116d2-le64.cache-7
7f29bfbe1000-7f29bfbe2000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053699                   /var/cache/fontconfig/1ac9eb803944fde146138c791f5cc56a-le64.cache-7
7f29bfbe2000-7f29bfbe3000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053750                   /var/cache/fontconfig/dc05db6664285cc2f12bf69c139ae4c3-le64.cache-7
7f29bfbe3000-7f29bfbe5000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053696                   /var/cache/fontconfig/14a5e22175779b556eaa434240950366-le64.cache-7
7f29bfbe5000-7f29bfbe6000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053723                   /var/cache/fontconfig/660208299946a285a940457d1287da33-le64.cache-7
7f29bfbe6000-7f29bfbe8000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053714                   /var/cache/fontconfig/4f3e3037c9980c83b53a9351efadef62-le64.cache-7
7f29bfbe8000-7f29bfbea000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053728                   /var/cache/fontconfig/767a8244fc0220cfb567a839d0392e0b-le64.cache-7
7f29bfbea000-7f29bfbeb000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053253                   /var/cache/fontconfig/4794a0821666d79190d59a36cb4f44b5-le64.cache-7
7f29bfbeb000-7f29bfbed000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053693                   /var/cache/fontconfig/0bd3dc0958fa2205aaaa8ebb13e2872b-le64.cache-7
7f29bfbed000-7f29bfbf2000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053751                   /var/cache/fontconfig/def309198bfa603429122923fa2bb2d4-le64.cache-7
7f29bfbf2000-7f29bfbf6000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1056929                   /var/cache/fontconfig/c57959a16110560c8d0fcea73374aeeb-le64.cache-7
7f29bfbf6000-7f29bfbf7000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053739                   /var/cache/fontconfig/b872e6e592da6075ffa4ab0a1fcc0c75-le64.cache-7
7f29bfbf7000-7f29bfbf8000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053756                   /var/cache/fontconfig/f6d4eedfaab2589bde49f7a3ff831d22-le64.cache-7
7f29bfbf8000-7f29bfbf9000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053721                   /var/cache/fontconfig/589f83ef4c36d296ce6e1c846f468f08-le64.cache-7
7f29bfbf9000-7f29bfbfa000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053741                   /var/cache/fontconfig/bab58bb527bb656aaa9f116d68a48d89-le64.cache-7
7f29bfbfa000-7f29bfbfb000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053700                   /var/cache/fontconfig/2171a34dccabdb6bcbbc728186263178-le64.cache-7
7f29bfbfb000-7f29bfbfc000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053742                   /var/cache/fontconfig/c5c45a61289222e0d30b1a26ef4effbe-le64.cache-7
7f29bfbfc000-7f29bfbfd000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053737                   /var/cache/fontconfig/aec30016f93e1b46d1a973dce0d74068-le64.cache-7
7f29bfbfd000-7f29bfbfe000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053707                   /var/cache/fontconfig/3f589640d34b7dc9042c8d453f7c8b9c-le64.cache-7
7f29bfbfe000-7f29bfbff000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053697                   /var/cache/fontconfig/16c2fda60d1b4b719f4b3d06fd951d25-le64.cache-7
7f29bfbff000-7f29bfc00000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053736                   /var/cache/fontconfig/a48eab177a16e4f3713381162db2f3e9-le64.cache-7
7f29bfc00000-7f29bfc01000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053717                   /var/cache/fontconfig/564b2e68ac9bc4e36a6f7f6d6125ec1c-le64.cache-7
7f29bfc01000-7f29bfc06000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1055671                   /var/cache/fontconfig/9d2451b1fd30e5bffe8383fd27c35478-le64.cache-7
7f29bfc06000-7f29bfc0c000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053703                   /var/cache/fontconfig/3047814df9a2f067bd2d96a2b9c36e5a-le64.cache-7
7f29bfc0c000-7f29bfc14000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1056927                   /var/cache/fontconfig/bf3b770c553c462765856025a94f1ce6-le64.cache-7
7f29bfc14000-7f29bfc15000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053718                   /var/cache/fontconfig/56cf4f4769d0f4abc89a4895d7bd3ae1-le64.cache-7
7f29bfc15000-7f29bfc16000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053740                   /var/cache/fontconfig/b9d506c9ac06c20b433354fa67a72993-le64.cache-7
7f29bfc16000-7f29bfc1c000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053738                   /var/cache/fontconfig/b47c4e1ecd0709278f4910c18777a504-le64.cache-7
7f29bfc1c000-7f29bfc2f000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053747                   /var/cache/fontconfig/d52a8644073d54c13679302ca1180695-le64.cache-7
7f29bfc2f000-7f29bfc30000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053705                   /var/cache/fontconfig/370e5b74bf5dafc30834de68e24a87a4-le64.cache-7
7f29bfc30000-7f29bfc31000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053726                   /var/cache/fontconfig/6b2c5944714ca7831b25bed9e85cb5c8-le64.cache-7
7f29bfc31000-7f29bfc32000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053746                   /var/cache/fontconfig/d5178ab6d91b49bf20a416737dcea9e8-le64.cache-7
7f29bfc32000-7f29bfc33000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053716                   /var/cache/fontconfig/551ecf3b0e8b0bca0f25c0944f561853-le64.cache-7
7f29bfc33000-7f29bfc36000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053755                   /var/cache/fontconfig/f259c2cffa685e28062317905db73c4a-le64.cache-7
7f29bfc36000-7f29bfc39000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053724                   /var/cache/fontconfig/674d1711f2d1d2a09646eb0bdcadee49-le64.cache-7
7f29bfc39000-7f29bfc45000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1054864                   /var/cache/fontconfig/d589a48862398ed80a3d6066f4f56f4c-le64.cache-7
7f29bfc45000-7f29bfc64000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1060624                   /var/cache/fontconfig/9b89f8e3dae116d678bbf48e5f21f69b-le64.cache-7
7f29bfc64000-7f29bfd6c000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bfd6c000-7f29bfd6e000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053715                   /var/cache/fontconfig/550f3886151c940c12a5ed35f6a00586-le64.cache-7
7f29bfd6e000-7f29bfd6f000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053708                   /var/cache/fontconfig/3f7329c5293ffd510edef78f73874cfd-le64.cache-7
7f29bfd6f000-7f29bfd95000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bfd95000-7f29bfd96000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053694                   /var/cache/fontconfig/0c9eb80ebd1c36541ebe2852d3bb0c49-le64.cache-7
7f29bfd96000-7f29bfd97000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053701                   /var/cache/fontconfig/22368d551a680bfe5a62c02760edf4ea-le64.cache-7
7f29bfd97000-7f29bfd98000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053713                   /var/cache/fontconfig/4d9c95eba1cb85bbcf2878543262124a-le64.cache-7
7f29bfd98000-7f29bfd99000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053730                   /var/cache/fontconfig/85e0a52ce643a7ba2ae53e5d6949cead-le64.cache-7
7f29bfd99000-7f29bfd9a000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053710                   /var/cache/fontconfig/49f0de54bdd920fe4f0dfd4cbac43e6b-le64.cache-7
7f29bfd9a000-7f29bfd9b000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053757                   /var/cache/fontconfig/f6e6e0a5c3d2f6ae0c0c2e0ecd42a997-le64.cache-7
7f29bfd9b000-7f29bfd9c000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053711                   /var/cache/fontconfig/4b2eda6bb976bda485cb2176619421d5-le64.cache-7
7f29bfd9c000-7f29bfd9e000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053725                   /var/cache/fontconfig/6afa1bb216ce958c1589e297e8008489-le64.cache-7
7f29bfd9e000-7f29bfda1000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 1053752                   /var/cache/fontconfig/e13b20fdb08344e0e664864cc2ede53d-le64.cache-7
7f29bfda1000-7f29bfda6000 r--s 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:0a 9714796                   /home/jaeyoung/.cache/qmlcache/5b2121aef63192755e7fa30131090501014c6cc0.qmlc
7f29bfda6000-7f29bfdae000 r-xs 8c9c481dc5695251e8b3eb0777f53f8f3763cbcb 103:0a 9714796                   /home/jaeyoung/.cache/qmlcache/5b2121aef63192755e7fa30131090501014c6cc0.qmlc
7f29bfdae000-7f29bfdaf000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bfdaf000-7f29bfdb0000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bfdb0000-7f29bfdb1000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 103:09 921618                    /usr/share/locale-langpack/en/LC_MESSAGES/gtk30.mo
7f29bfdb1000-7f29bfdb2000 ---p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bfdb2000-7f29bfdb6000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7f29bfdb6000-7f29bfdb7000 r--p 00027000 103:09 1840006                   /lib/x86_64-linux-gnu/ld-2.27.so
7f29bfdb7000-7f29bfdb8000 rw-p 00028000 103:09 1840006                   /lib/x86_64-linux-gnu/ld-2.27.so
7f29bfdb8000-7f29bfdb9000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0 
7ffea4f4a000-7ffea5749000 rw-p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0                          [stack]
7ffea57bf000-7ffea57c2000 r--p 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0                          [vvar]
7ffea57c2000-7ffea57c3000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0                          [vdso]
ffffffffff600000-ffffffffff601000 r-xp 772cb837ce08fa8e7338217ec7d827fc3ddeed79 00:00 0                  [vsyscall]

Actual behavior:

[What actually happens]

Reproduces how often:
Always

ignition-gazebo major version is hard-coded in plugin filenames in sdf files

Original report (archived issue) by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


Summary

The ign-gazebo major version is embedded in the plugin filenames in many sdf files (see pull request #210 for an example of this). This makes it a hassle to share sdf files across different versions of ignition-gazebo. If there are behavior changes between major versions, it can be helpful to have this specificity, but if the behavior is not changed, it's just a hassle.

What if the plugins installed an unversioned copy of themselves into a versioned folder? For example, gazebo9's plugins are installed to:

/usr/lib/x86_64-linux-gnu/gazebo-9/plugins/

If the unversioned plugins are to be used, then the versioned folder should be added to the path. Otherwise just use the versioned name.

Of course, maybe this isn't a big deal. I'm open to that outcome, but it currently seems like a hassle to have sdf files that are so dependent on the plugin major version.

Regression for systems that use rendering

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Description

Until version 2.6.1, it was possible to run multiple systems which accessed the rendering engine. This is how ros1_ign_point_cloud used to work. But since pull request #387, when 2 systems call ignition::rendering::engine, the 2nd call crashes with:

ruby: /var/lib/jenkins/workspace/ogre-2.1-debbuilder/repo/OgreMain/include/OgreSingleton.h:80: Ogre::Singleton<T>::Singleton() [with T = Ogre::LogManager]: Assertion !msSingle
ton' failed.`

Steps to Reproduce

I created a simple example (861af48) in a branch which reproduces the issue:

hg up rendering_plugin
# follow README instructions

Or you could try using ros1_ign_point_cloud like this:

roslaunch ros1_ign_gazebo_demos depth_camera.launch

Expected behavior:

No crash when running ign gazebo -s -v 4 rendering_plugin.sdf

Actual behavior:

Crash with the Ogre assertion above.

Reproduces how often:

100%

Versions

Current ign-gazebo2 branch (the last release was 2.7.1) crashes. If you build Gazebo from the 2.6.1 tag, you can see there's no crash.

Additional Information

We could consider the performance improvements from pull request #387 to be more important than this use case and no longer support it. But we could also see if it's possible to fix it.

Insert model from the GUI

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


It is convenient for users to construct environments through the UI. To be able to do that, they need to be able to insert new models into simulation. This issue is about creating a GUI plugin which allows users to inspect and insert SDF models from:

  • custom local paths (Requires #123)
  • Fuel's local cache
  • Fuel's online models

A few more nice features:

  • Display resource names and thumbnails
  • Display resources organized by folders
  • Search bar to filter folders and resources
  • A button to add new local folders to be listed
  • Drag resources from one local folder to another to copy / move them
  • Drag resources into a Fuel user to upload to that user's account

Alternatives

  • Since Blueprint, users are already able to drag models directly from Fuel on the browser. That doesn't cover local models though.
  • It's common on various programs for the user to drag SDF files from a file browser. We should also support that use case besides the plugin in question.

Additional resources

  • Feature request: osrf/subt#130
  • Create entity service
  • Gazebo-classic's InsertModelWidget
    • Lists model by their name in model.config
    • Lists all local paths in GAZEBO_MODEL_PATH
    • Lists all models in https://models.gazebosim.org
    • Has partial support for Fuel
    • Interaction:
      1. Click on model name
      2. A temp preview visual is attached to mouse, at Z = 0 height
      3. Click on 3D scene, model is spawned
        classic_insert
  • GzWeb's insert menu
    • Lists a hardcoded list of models organized by categories
    • Lists models by their name and thumbnail
    • Same interaction as Gazebo-classic
      gzweb_insert

Load model during runtime: how to run model plugins?

Original report (archived issue) by Diego Ferigo (Bitbucket: dgferigo).


The support of loading models during runtime was implemented months ago in PR143.

It doesn’t seem that the UserCommands system has the support to load a plugin if its element is included in the SDF file passed to the protobuf message. In fact, it seems being ignored. Is there any way to do it? In other words, is there any way to load a system defined in a plugin during runtime?

Btw: I know that there is Server::AddSystem, that it only requires the server not being in running state. Using this call, though, is not optimal because the system would be added in the world SDF context and it would require manually loading the plugin library. Even more relevant, it would be impossible to pass any configuration to the plugin like the one that could be passed with custom XML properties listed in the plugin SDF element.

INTEGRATION_physics_system fails locally

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


The test always fails for me, but it passes on pipelines.

The tolerance already seems pretty high, should we increase it further or is there anything else that can be tried to improve precision? I tried stepping more to see if it would settle better, but had no success.

/home/developer/ign-gazebo/test/integration/physics_system.cc:181: Failure
The difference between spherePoses.back().Pos().Z() and zStopped is 0.031200947452871164, which exceeds 5e-3, where
spherePoses.back().Pos().Z() evaluates to 1.1.0312009964860931,
zStopped evaluates to 1, and
5e-3 evaluates to 0.0050000000000000001.

Levels are not get loaded correctly on log playbck

Original report (archived issue) by Ian Chen (Bitbucket: Ian Chen, GitHub: iche033).

The original report had attachments: state.tlog


Description

When seeking to a particular time in the log file, the levels may not be loaded correctly

Steps to Reproduce

You can skip step 1 and 2 if using the attached state.tlog file

  1. launch examples/levels.sdf with recording enabled

    • ign gazebo -v 4 --record -r --record_path /tmp/level_log src/ign-gazebo/examples/worlds/levels.sdf --levels
  2. publish cmd vel to move the blue vehicle and wait for it to reach the end of the road (note down this sim time):

    • ign topic -t "/model/vehicle_blue/cmd_vel" -m ignition.msgs.Twist -p "linear: {x: 4.0}"
  3. Exit gazebo and launch playback:

    • ign gazebo -v 4 -p /tmp/level_log
  4. Seek to the time when the vehicle is at the end of the road, e.g. with the attached state.tlog,

    • ign service -s /world/default/playback/control --reqtype ignition.msgs.LogPlaybackControl --reptype ignition.msgs.Boolean --timeout 5000 --req "seek: {sec: 30}, pause: false"
  5. Now seek back to an earlier time when the vehicle was half way through the levels, e.g.

    • ign service -s /world/default/playback/control --reqtype ignition.msgs.LogPlaybackControl --reptype ignition.msgs.Boolean --timeout 5000 --req "seek: {sec: 10}, pause: false"
  6. Notice that the level does not not get loaded properly:


Expected behavior:

The middle level should be loaded

Actual behavior:

  1. The level was not loaded:

Reproduces how often:

All the time

Versions

ign-gazebo 2.0

Additional Information

related subt issue

migrating a Sensor plugin

Original report (archived issue) by Felipe Inostroza (Bitbucket: Felipe Inostroza).


Hello,

I am trying to migrate a sensor plug-in that:

Takes sensor output from a gpulidar, and filters (removes) some of the points.

From the migration tutorial it says that this should be a “standalone program”, however then I don’t know how to access the sdf configuration of the sensor. And if I set it to be a system plug in I don’t know how to access the sensor data (and my callback will be executed at every physics iteration, instead of at every sensor update?).

How should I do this?

Sorry if this is not the place to ask questions but I cant find where that would be.

Thanks!

Gazebo hangs at "Requesting list of world names. The server may be busy downloading resources. Please be patient."

Original report (archived issue) by Til Hoff (Bitbucket: turakar).


Description

Gazebo hangs at "Requesting list of world names. The server may be busy downloading resources. Please be patient." during start.

Steps to Reproduce

  • use Fedora 29
  • compile assimp, dart and gflags from source (packages are non-existent or outdated in Fedora repos)
  • install dependencies
sudo dnf install cmake freeglut-devel ffmpeg-devel freeimage-devel gflags-devel glew-devel gts-devel ogre-devel protobuf-devel protobuf-c-devel qt5 tinyxml2-devel tinyxml-devel pkg-config protobuf-compiler python qt5-qtquickcontrols qt5-qtquickcontrols2 qt5-devel qt5-qtdeclarative-devel qt5-qtquickcontrols2-devel ruby rubygem-ronn uuid-devel libzip-devel jsoncpp-devel libcurl-devel libyaml-devel czmq-devel cppzmq-devel sqlite-devel libwebsockets-devel eigen3-devel
  • compile ignition based on official installation instructions
  • start Gazebo using ign gazebo -v4

Expected behaviour

Gazebo GUI starts as normal.

Actual behaviour

Gazebo opens an “empty frame” (window decorations are existent, but the frame is transparent and does not have any content). Log output:

[Msg] Ignition Gazebo GUI    v2.9.0
[Msg] Ignition Gazebo Server v2.9.0
[Msg] Loading default world.
[Dbg] [EntityComponentManager.cc:623] Using components of type [2251689575469537287] / [ign_gazebo_components.World].
[Dbg] [EntityComponentManager.cc:623] Using components of type [13994732549916512682] / [ign_gazebo_components.Name].
[Dbg] [EntityComponentManager.cc:623] Using components of type [12592746352568925681] / [ign_gazebo_components.Gravity].
[Dbg] [EntityComponentManager.cc:623] Using components of type [13224937992534617849] / [ign_gazebo_components.MagneticField].
[Dbg] [EntityComponentManager.cc:623] Using components of type [8753193699724811771] / [ign_gazebo_components.Wind].
[Dbg] [EntityComponentManager.cc:623] Using components of type [12173050716021724529] / [ign_gazebo_components.WorldLinearVelocity].
[Dbg] [EntityComponentManager.cc:623] Using components of type [15943768124495574352] / [ign_gazebo_components.WorldLinearVelocitySeed].
[Dbg] [EntityComponentManager.cc:623] Using components of type [3297509811873971798] / [ign_gazebo_components.ParentEntity].
[Dbg] [EntityComponentManager.cc:623] Using components of type [17100615127981600159] / [ign_gazebo_components.Scene].
[Dbg] [EntityComponentManager.cc:623] Using components of type [8064491505919932473] / [ign_gazebo_components.Level].
[Dbg] [EntityComponentManager.cc:623] Using components of type [2668898242563798256] / [ign_gazebo_components.DefaultLevel].
[Dbg] [EntityComponentManager.cc:623] Using components of type [11371360182141354106] / [ign_gazebo_components.LevelEntityNames].
[Dbg] [SimulationRunner.cc:688] Loaded system [ignition::gazebo::systems::SceneBroadcaster] for entity [1]
QSettings::value: Empty key passed
QSettings::value: Empty key passed
[Dbg] [Application.cc:87] Initializing application.
[GUI] [Dbg] [Application.cc:407] Create main window
[Dbg] [SimulationRunner.cc:688] Loaded system [ignition::gazebo::systems::Physics] for entity [1]
[Msg] Create service on [/world/default/create]
[Msg] Remove service on [/world/default/remove]
[Msg] Pose service on [/world/default/set_pose]
[Dbg] [SimulationRunner.cc:688] Loaded system [ignition::gazebo::systems::UserCommands] for entity [1]
[Msg] Loaded level [3]
[Msg] Serving GUI information on [/world/default/gui/info]
[Msg] World [default] initialized with [default_physics] physics profile.
[GUI] [Wrn] [Application.cc:649] [QT] file:///usr/lib64/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:102:33: QML Settings: Failed to initialize QSettings instance. Status code is: 1
[GUI] [Wrn] [Application.cc:649] [QT] file:///usr/lib64/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:102:33: QML Settings: The following application identifiers have not been set: QVector("organizationName", "organizationDomain", "applicationName")
[GUI] [Wrn] [Application.cc:649] [QT] file:///usr/lib64/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:102:33: QML Settings: Failed to initialize QSettings instance. Status code is: 1
[GUI] [Wrn] [Application.cc:649] [QT] file:///usr/lib64/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:102:33: QML Settings: The following application identifiers have not been set: QVector("organizationName", "organizationDomain", "applicationName")
[GUI] [Msg] Loading config [/home/t/projects/debris/approach-simulator/ignitionrobotics/install/share/ignition/ignition-gazebo2/gui/gui.config]
[GUI] [Dbg] [Application.cc:266] Loading window config
[GUI] [Dbg] [Application.cc:421] Applying config
[GUI] [Wrn] [Application.cc:649] [QT] file:///usr/lib64/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:102:33: QML Settings: Failed to initialize QSettings instance. Status code is: 1
[GUI] [Wrn] [Application.cc:649] [QT] file:///usr/lib64/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:102:33: QML Settings: The following application identifiers have not been set: QVector("organizationName", "organizationDomain", "applicationName")
[GUI] [Wrn] [Application.cc:649] [QT] file:///usr/lib64/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:102:33: QML Settings: Failed to initialize QSettings instance. Status code is: 1
[GUI] [Wrn] [Application.cc:649] [QT] file:///usr/lib64/qt5/qml/QtQuick/Dialogs/DefaultFileDialog.qml:102:33: QML Settings: The following application identifiers have not been set: QVector("organizationName", "organizationDomain", "applicationName")
[GUI] [Dbg] [ign.cc:227] Requesting list of world names. The server may be busy downloading resources. Please be patient.
[Msg] Found no publishers on /stats, adding root stats topic
[Msg] Found no publishers on /clock, adding root clock topic
[Dbg] [SimulationRunner.cc:343] Creating PostUpdate worker threads: 2
[Dbg] [SimulationRunner.cc:356] Creating postupdate worker thread (0)
[Msg] Serving scene information on [/world/default/scene/info]
[Msg] Serving graph information on [/world/default/scene/graph]
[Msg] Serving full state on [/world/default/state]
[Msg] Publishing scene information on [/world/default/scene/info]
[Msg] Publishing entity deletions on [/world/default/scene/deletion]
[Msg] Publishing state changes on [/world/default/state]
[Msg] Publishing pose messages on [/world/default/pose/info]
[Msg] Publishing dynamic pose messages on [/world/default/dynamic_pose/info]
[GUI] [Dbg] [ign.cc:227] Requesting list of world names. The server may be busy downloading resources. Please be patient.
[GUI] [Dbg] [ign.cc:227] Requesting list of world names. The server may be busy downloading resources. Please be patient.

The last line is repeatedly print for over one hour.

Versions

  • Fedora 29
  • source install (for details see above)
  • latest ignition

Additional information

  • I can access https://app.ignitionrobotics.org/fuel using my web browser
  • I have a good internet connection
  • Gazebo does not seem to use >50kB/s bandwidth (my network provides a bandwidth of at least >1MB/s)

Thank you for sharing this great software :slight_smile:

Sloped plane snaps back to horizontal on rendering

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Prerequisites

  • [ X ] Put an X between the brackets on this line if you have done all of the following:

Description

It looks like plane updates are resetting the normal direction, but not the pose.

Steps to Reproduce

  1. Load the sloped_normal world, which has this ground plane:

     <model name="ground_plane">
      ...
     <visual name="visual">
       <geometry>
         <plane>
           <normal>0.2 0.0 1</normal>
           <size>100 100</size>
         </plane>
       </geometry>
     </visual>
     ...
     </model>
    
  2. Press play and see the world snap to horizontal:

    planesnap.gif

  3. Now try the sloped_pose world, which has a slope due to model pose, not normal, i.e.:

     <model name="ground_plane">
       <pose>0 0 0 0.1 0 0</pose>
         ...
        <visual name="visual">
           <geometry>
         <plane>
           <normal>0 0 1</normal>
           <size>100 100</size>
         </plane>
       </geometry>
     </visual>
     ...
     </model>
    
  4. Press play, and the plane doesn't move, as it should be.

Expected behavior:

The plane should maintain its normal direction once simulation starts.

Actual behavior:

It looks like the plane's normal is being reset to unit Z.

Reproduces how often:

100%

Versions

default branch, version 2 candidate

Additional Information

I suspect we may be forgetting to propagate the normal correctly at some point.

Ign gazebo render window does not work in same process as server on macOS

Original report (archived issue) by Ian Chen (Bitbucket: Ian Chen, GitHub: iche033).


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

The ign gazebo render window (scene3d plugin) fails to render the scene on macOS.

This is likely a QtQuick + Ogre2 integration issue.

Steps to Reproduce

  1. Run ign gazebo on macOS

Expected behavior:

See the 3D scene in the render window

Actual behavior:

Nothing is rendered

Reproduces how often:

All the time

Versions

All versions

Support for multiple worlds

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Description

Since the very beginning we've had support for multiple <world> tags within a single SDF file. The current behaviour is that a simulation runner is started for each of them. However, as the code evolved, that use case became less well supported.

Steps to Reproduce

At the moment, the following crashes with an ODE assertion:

ign-gazebo -f test/worlds/multiple_worlds.sdf

ODE INTERNAL ERROR 1: assertion "!colliders_initialized" failed in dInitColliders() [collision_kernel.cpp:168]

ODE INTERNAL ERROR 1: assertion "!colliders_initialized" failed in dInitColliders() [collision_kernel.cpp:168]

Expected behavior:

At a minimum, no crash. At a maximum, multiple worlds spun up in parallel and running in lockstep, the UI displaying all of them side-by-side.

Actual behavior:

Server crashes, UI freezes.

Reproduces how often:

100% of the time

Versions

ign-gazebo1

Additional Information

I'm not sure if it's best at the moment to:

  • print a warning and only load the first world
  • catch the physics problem before the crash and only disable the bit that is having trouble running in the same process (some singleton within ODE?)
  • leave it as it is but discourage people from trying to use it. It should be possible to avoid the crash, like using a different physics engine or even no physics.

OSX Citadel Crash segmentation fault when running actor.sdf

Original report (archived issue) by Claire Wang (Bitbucket: Claire Wang, GitHub: claireyywang).


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

[Description of the issue]
Segmentatin fault after ctrl-c

Steps to Reproduce

  1. [First Step] ign gazebo -s -v 4 actor.sdf
  2. [Second Step] ctrl-c after all msgs printed
  3. [and so on...]

Expected behavior:

[What you expect to happen]

Program exits gracefully.

Actual behavior:

[What actually happens]

[BUG] Segmentation fault at 0x0000000000001280
ruby 2.3.7p456 (2018-03-28 revision 63024) [universal.x86_64-darwin18]

-- Crash Report log information --------------------------------------------
   See Crash Report log file under the one of following:                    
     * ~/Library/Logs/CrashReporter                                         
     * /Library/Logs/CrashReporter                                          
     * ~/Library/Logs/DiagnosticReports                                     
     * /Library/Logs/DiagnosticReports                                      
   for more details.                                                        
Don't forget to include the above Crash Report log file in bug reports.     

-- Machine register context ------------------------------------------------
 rax: 0x0000000000000010 rbx: 0x0000000115e77fc8 rcx: 0x0000000000000000
 rdx: 0x0000000000000004 rdi: 0x0000000000000010 rsi: 0x0000000115fd7149
 rbp: 0x00007ffee93d45c0 rsp: 0x00007ffee93d45c0  r8: 0x000000000000006c
  r9: 0x00007ff3e13d4000 r10: 0x0000000000000003 r11: 0x0000000000000003
 r12: 0x00000001161d0c18 r13: 0x00000001161d0d38 r14: 0x0000000000000002
 r15: 0x0000000115de2ea8 rip: 0x00007fff3c0e9cc4 rfl: 0x0000000000010202

-- C level backtrace information -------------------------------------------
0   libruby.2.3.0.dylib                 0x00007fff3de73102 rb_print_backtrace + 29
1   libruby.2.3.0.dylib                 0x00007fff3de7333d rb_vm_bugreport + 463
2   libruby.2.3.0.dylib                 0x00007fff3dd6e711 rb_bug_context + 206
3   libruby.2.3.0.dylib                 0x00007fff3de0994c Init_signal + 3247
4   libsystem_platform.dylib            0x00007fff5f190b5d _sigtramp + 29
5   libGL.dylib                         0x00007fff3c0e9cc4 glDeleteObjectARB + 16
6   libRenderSystem_GL.dylib            0x00000001167dbdb9 _ZN4Ogre4GLSL11GLSLProgram19unloadHighLevelImplEv + 37
7   libOgreMain.1.9.0.dylib             0x00000001156f8745 _ZN4Ogre19HighLevelGpuProgram15unloadHighLevelEv + 31
8   libOgreMain.1.9.0.dylib             0x00000001157bd705 _ZN4Ogre8Resource6unloadEv + 107
9   libRenderSystem_GL.dylib            0x00000001167db4d7 _ZN4Ogre4GLSL11GLSLProgramD2Ev + 39
10  libRenderSystem_GL.dylib            0x00000001167db595 _ZN4Ogre4GLSL11GLSLProgramD0Ev + 15
11  libOgreRTShaderSystem.1.9.0.dylib   0x0000000115c352c2 _ZNSt3__16__treeINS_12__value_typeINS_12basic_stringIcNS_11char_traitsIcEENS_9allocatorIcEEEEN4Ogre9SharedPtrINS8_10GpuProgramEEEEENS_19__map_value_compareIS7_SC_NS_4lessIS7_EELb1EEENS8_12STLAllocatorISC_NS8_22CategorisedAllocPolicyILNS8_14MemoryCategoryE0EEEEEE5eraseENS_21__tree_const_iteratorISC_PNS_11__tree_nodeISC_PvEElEE + 116
12  libOgreRTShaderSystem.1.9.0.dylib   0x0000000115c32f1c _ZN4Ogre8RTShader14ProgramManager15releaseProgramsEPNS_4PassEPNS0_17TargetRenderStateE + 330
13  libOgreRTShaderSystem.1.9.0.dylib   0x0000000115c21ee7 _ZN4Ogre8RTShader15ShaderGenerator11SGTechniqueD2Ev + 239
14  libOgreRTShaderSystem.1.9.0.dylib   0x0000000115c1bc7a _ZN4Ogre8RTShader15ShaderGenerator8_destroyEv + 78
15  libOgreRTShaderSystem.1.9.0.dylib   0x0000000115c1bbe2 _ZN4Ogre8RTShader15ShaderGenerator7destroyEv + 24
16  libignition-rendering3-ogre.dylib   0x00000001154c1a96 _ZN8ignition9rendering2v318OgreRTShaderSystem4FiniEv + 70
17  libignition-rendering3-ogre.dylib   0x00000001154c1bb9 _ZN8ignition9rendering2v318OgreRTShaderSystemD1Ev + 25
18  libsystem_c.dylib                   0x00007fff5f04b3cf __cxa_finalize_ranges + 319
19  libsystem_c.dylib                   0x00007fff5f04b6b3 exit + 55

[NOTE]
You may have encountered a bug in the Ruby interpreter or extension libraries.
Bug reports are welcome.
For details: http://www.ruby-lang.org/bugreport.html

Abort trap: 6

Reproduces how often:

[What percentage of the time does it occur?]
all the time

Versions

[Include information about relevant software versions, and your OS type and version.]

  • OS: Mojave 10.14
  • Ignition: Citadel
  • Xcode: 10.3
  • Ruby: 2.3.7p456 (2018-03-28 revision 63024) [universal.x86_64-darwin18]

ignition-gazebo binaries conflict with ignition-gazebo2 binaries

Original report (archived issue) by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

ign-gazebo1 and ign-gazebo2 both install unversioned symlinks to versioned binaries:

  • /usr/bin/ign-gazebo
  • /usr/bin/ign-gazebo-gui
  • /usr/bin/ign-gazebo-server

This causes the ignition-gazebo and ignition-gazebo2 debs to conflict with each other. I also noticed it during a failed bottle build:

Steps to Reproduce

  1. Add stable and nightly repo to apt sources on bionic
  2. Install ignition-gazebo and ignition-gazebo2
  3. Observe conflict

Expected behavior:

Side-by-side install.

Actual behavior:

Conflict.

Reproduces how often:

💯 %

Versions

Major versions 1 and 2 conflict.

Additional Information

Transport segfault on shutdown

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


I observed that at times ign-gazebo crashes on shutdown. It doesn't happen every time. The backtrace points to ign-transport's WorkerPool:

#0  0x00007ffff7bb7d34 in std::_Sp_counted_base<(__gnu_cxx::_Lock_policy)2>::_M_release (this=0x555555be1de0) at /usr/include/c++/8/ext/atomicity.h:69
#1  0x00007ffff4c06546 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::~__shared_count (this=0x7fffc406e3f8, __in_chrg=<optimized out>)
    at /usr/include/c++/8/bits/shared_ptr_base.h:1151
#2  std::__shared_ptr<ignition::transport::v6::ISubscriptionHandler, (__gnu_cxx::_Lock_policy)2>::~__shared_ptr (this=0x7fffc406e3f0, __in_chrg=<optimized out>)
    at /usr/include/c++/8/bits/shared_ptr_base.h:1151
#3  std::shared_ptr<ignition::transport::v6::ISubscriptionHandler>::~shared_ptr (
    this=0x7fffc406e3f0, __in_chrg=<optimized out>)
    at /usr/include/c++/8/bits/shared_ptr.h:103
#4  ignition::transport::v6::Node::Publisher::<lambda()>::~<lambda> (
    this=0x7fffc406e3f0, __in_chrg=<optimized out>)
    at /home/developer/ign-transport/src/Node.cc:337
#5  std::_Function_base::_Base_manager<ignition::transport::v6::Node::Publisher::Publish(const ProtoMsg&)::<lambda()> >::_M_destroy (__victim=...)
    at /usr/include/c++/8/bits/std_function.h:188
#6  std::_Function_base::_Base_manager<ignition::transport::v6::Node::Publisher::Publish(const ProtoMsg&)::<lambda()> >::_M_manager(std::_Any_data &, const std::_Any_data &, std::_Manager_operation) (__dest=..., __source=..., __op=<optimized out>)
    at /usr/include/c++/8/bits/std_function.h:212
#7  0x00007ffff4c3660a in std::_Function_base::~_Function_base (
    this=0x7fffe05b4970, __in_chrg=<optimized out>)
    at /usr/include/c++/8/bits/std_function.h:257
#8  std::function<void ()>::~function() (this=0x7fffe05b4970, 
    __in_chrg=<optimized out>) at /usr/include/c++/8/bits/std_function.h:370
#9  std::function<void ()>::operator=(std::function<void ()>&&) (__x=..., 
    this=0x7fffe05b4990) at /usr/include/c++/8/bits/std_function.h:481
#10 ignition::transport::v6::WorkOrder::operator= (this=0x7fffe05b4990)
    at /home/developer/ign-transport/src/WorkerPool.cc:35
#11 ignition::transport::v6::WorkerPoolPrivate::Worker() ()
    at /home/developer/ign-transport/src/WorkerPool.cc:98
#12 0x00007ffff551a733 in ?? () from /usr/lib/x86_64-linux-gnu/libstdc++.so.6
#13 0x00007ffff3fc16db in start_thread (arg=0x7fffe05b5700) at pthread_create.c:463
#14 0x00007ffff4f7488f in clone () at ../sysdeps/unix/sysv/linux/x86_64/clone.S:95

Possible memory management issues in DART BoxedLcpConstrainedSolver?

Original report (archived issue) by Jaldert Rombouts (Bitbucket: Jaldert).

The original report had attachments: conveyor_with_box_crash.gif, conveyor_with_box_experiments.tgz


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

Thanks for building Ignition Gazebo. I've been experimenting with it and I really like the new architecture.

One of my experiments was building a conveyor model and system plugin. The model consists of a box with a set of rollers (cylinders) with revolute joints on top. I've written a custom system plugin to set JointVelocityCmds for all these rollers.

The model runs fine when it is alone in the world - I've left it running for hours without issues.

However, I’m running into issues when I drop a box on top of the running conveyor: I quickly get memory errors like free(): invalid next size (fast) and occasionally a segmentation fault or double free or corruption (out). Interestingly, this issue seems to require a combination of the conveyor running and the box moving along it. I tried variations where the model is not running and the box is dropped/placed at similar poses where the simulation crashes and I didn't manage to crash it in this manner.

Taking the GDB backtrace at face value, it seems to be an issue in DART: In particular it seems to happen in constraint::BoxedLcpConstraintSolver::solveConstrainedGroup(dart::constraint::ConstrainedGroup&) () from /usr/lib/x86_64-linux-gnu/libdart.so.6.10 (link)


(see attachment for high resolution version).

I was not entirely sure if this issue should be posted here or on ign-physics . I’ve posted it here because reproduction requires ign-gazebo , but I’m also happy to open the issue elsewhere.

Steps to Reproduce

  1. Build the RevoluteConveyorController.so library
# Gist with plugin system, and example world SDF
git clone https://gist.github.com/84eaf1c8006e80a4afa30858b296f681.git example

cd example
cmake -H. -Bbuild
cmake --build build

# This step copies plugin to ~/.ignition/gazebo/plugins s.t. dynamic loader can find it.
cmake --build build --target install

2. Run the conveyor_with_box.sdf example

ign gazebo conveyor_with_box.sdf # with gui
# ign gazebo -s -r conveyor_with_box.sdf # headless

Expected behavior:

The box should drop onto the rollers, move along it and finally fall off the end. The simulation should keep running.

Actual behavior:

The box drops, and starts moving along conveyor, then ignition gazebo crashes with memory errors like free(): invalid next size (fast) and occasionally a segmentation fault or double free or corruption (out).

Reproduces how often:

Always. There is variation in the exact timing to crash (looking at the number of simulation iterations) as well as the exact error (see detailed description above).

Versions

  • OS: Ubuntu 18.04 Bionic
  • Ignition Version: Clean build of all Ignition Citadel packages, following install_ubuntu_src.

Additional Information

  • Virtual machine: No, running native.

Touch plugin test failing on OSX

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Description

INTEGRATION_touch_plugin has been failing on OSX. Pull request #244 is disabling them so we get a clean CI, but we should go back and fix this before the 2.0 release.

Steps to Reproduce

  • Search in the homebrew CI results for INTEGRATION_touch_plugin
  • or, if you have a mac, you should be able to reproduce it locally

Expected behavior:

Test passes

Actual behavior:

Test fails because box contacts are not detected past a certain time.

These are the two failures:

71: [Dbg] [TouchPlugin.cc:295] Model [white_box] touched [green_box_for_white] exclusively for 3 s
71: [Dbg] [TouchPlugin.cc:214] Stopped touch plugin [white_touches_only_green]
71: [Dbg] [TouchPlugin.cc:207] Started touch plugin [white_touches_only_green]
71: [Dbg] [TouchPlugin.cc:281] Model [white_box] started touching [green_box_for_white] at 7.201 s
71: [Dbg] [TouchPlugin.cc:267] Not touching anything
71: [Dbg] [TouchPlugin.cc:281] Model [white_box] started touching [green_box_for_white] at 8.721 s
71: /Users/jenkins/workspace/ignition_gazebo-ci-pr_any-homebrew-amd64/ign-gazebo/test/integration/touch_plugin.cc:105: Failure
71: Value of: whiteTouched
71:   Actual: false
71: Expected: true
71: [  FAILED  ] TouchPluginTest.OneLink (10580 ms)

and

71: [Dbg] [TouchPlugin.cc:281] Model [blue_box] started touching [green_box_for_blue] at 3.001 s
71: [Dbg] [TouchPlugin.cc:295] Model [white_box] touched [green_box_for_white] exclusively for 3 s
71: [Dbg] [TouchPlugin.cc:214] Stopped touch plugin [white_touches_only_green]
71: [Dbg] [TouchPlugin.cc:267] Not touching anything
71: [Dbg] [TouchPlugin.cc:281] Model [blue_box] started touching [green_box_for_blue] at 3.855 s
71: [Dbg] [TouchPlugin.cc:267] Not touching anything
71: [Dbg] [TouchPlugin.cc:281] Model [blue_box] started touching [green_box_for_blue] at 5.476 s
71: /Users/jenkins/workspace/ignition_gazebo-ci-pr_any-homebrew-amd64/ign-gazebo/test/integration/touch_plugin.cc:182: Failure
71: Value of: blueTouched
71:   Actual: false
71: Expected: true
71: [  FAILED  ] TouchPluginTest.StartDisabled (7071 ms)

This is how it looks like on success, note that there's no message about "Not touching anything".

71: [Dbg] [TouchPlugin.cc:295] Model [white_box] touched [green_box_for_white] exclusively for 3 s
71: [Dbg] [TouchPlugin.cc:214] Stopped touch plugin [white_touches_only_green]
71: [Dbg] [TouchPlugin.cc:207] Started touch plugin [white_touches_only_green]
71: [Dbg] [TouchPlugin.cc:281] Model [white_box] started touching [green_box_for_white] at 7.201 s
71: [Dbg] [TouchPlugin.cc:295] Model [white_box] touched [green_box_for_white] exclusively for 3 s
71: [Dbg] [TouchPlugin.cc:214] Stopped touch plugin [white_touches_only_green]
71: [       OK ] TouchPluginTest.OneLink (3370 ms)
71: [Dbg] [TouchPlugin.cc:281] Model [blue_box] started touching [green_box_for_blue] at 3.001 s
71: [Dbg] [TouchPlugin.cc:295] Model [white_box] touched [green_box_for_white] exclusively for 3 s
71: [Dbg] [TouchPlugin.cc:214] Stopped touch plugin [white_touches_only_green]
71: [Dbg] [TouchPlugin.cc:295] Model [blue_box] touched [green_box_for_blue] exclusively for 2 s
71: [Dbg] [TouchPlugin.cc:214] Stopped touch plugin [blue_touches_only_green]
71: [       OK ] TouchPluginTest.StartDisabled (1900 ms)

Reproduces how often:

100% on homebrew

Versions

All

Additional Information

Flaky / failing / disabled tests

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


This issue collects all known flaky tests, we should update it as we observe new flaky tests or if they stop flaking.

❄️ ❄️ ❄️

PERFORMANCE_each

Platforms: Jenkins Ubuntu and Pipelines

Failures:

39: [ RUN      ] EntityComponentManagerPerfrormance.Each
39: /opt/atlassian/pipelines/agent/build/test/performance/each.cc:141: Failure
39: Expected: (cacheEntityAvg) < (cachelessEntityAvg), actual: 7200.83 vs 7170.62
39: [  FAILED  ] EntityComponentManagerPerfrormance.Each (60561 ms)

UNIT_SimulationRunner_TEST

Platforms: Pipelines

Failures:

19: /opt/atlassian/pipelines/agent/build/src/SimulationRunner_TEST.cc:958: Failure
19: Value of: simTime.second
19:   Actual: 100000000
19: Expected: clockMsgs.back().mutable_sim()->nsec()
19: Which is: 99000000

INTEGRATION_network_handshake

Platforms: Homebrew

Failures:

/Users/jenkins/workspace/ignition_gazebo-ci-pr_any-homebrew-amd64/ign-gazebo/test/integration/network_handshake.cc:56
Value of: success
  Actual: 4-byte object <01-00 00-00>
Expected: std::cv_status::no_timeout
Which is: 4-byte object <00-00 00-00>

Platforms: Pipelines

Failures:

59: [ RUN      ] NetworkHandshake.Handshake
59: �[1;31m[Err] �[0m�[1;31m[�[0m�[1;31mLevelManager.cc�[0m�[1;31m:�[0m�[1;31m108�[0m�[1;31m] �[0m�[1;31mCould not find a plugin tag with name �[0m�[1;31mignition::gazebo�[0m�[1;31m. Levels and distributed simulation will not work.�[0m
59: �[1;31m[Err] �[0m�[1;31m[�[0m�[1;31mLevelManager.cc�[0m�[1;31m:�[0m�[1;31m108�[0m�[1;31m] �[0m�[1;31mCould not find a plugin tag with name �[0m�[1;31mignition::gazebo�[0m�[1;31m. Levels and distributed simulation will not work.�[0m
59: �[1;31m[Err] �[0m�[1;31m[�[0m�[1;31mLevelManager.cc�[0m�[1;31m:�[0m�[1;31m108�[0m�[1;31m] �[0m�[1;31mCould not find a plugin tag with name �[0m�[1;31mignition::gazebo�[0m�[1;31m. Levels and distributed simulation will not work.�[0m
59/80 Test #59: INTEGRATION_network_handshake ................***Timeout 240.01 sec

Platforms: Jenkins Ubuntu

Date added: 2019-04-11

Failures:

61: [----------] 2 tests from NetworkHandshake
61: [ RUN      ] NetworkHandshake.Handshake
61: [Msg] Loading SDF string.
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [2251689575469537287] / [ign_gazebo_components.World].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [13994732549916512682] / [ign_gazebo_components.Name].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [12592746352568925681] / [ign_gazebo_components.Gravity].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [13224937992534617849] / [ign_gazebo_components.MagneticField].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [8064491505919932473] / [ign_gazebo_components.Level].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [2668898242563798256] / [ign_gazebo_components.DefaultLevel].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [11371360182141354106] / [ign_gazebo_components.LevelEntityNames].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [3297509811873971798] / [ign_gazebo_components.ParentEntity].
61: [Msg] Serving scene information on [/world/default/scene/info]
61: [Msg] Serving graph information on [/world/default/scene/graph]
61: [Msg] Serving scene information on [/world/default/scene/info]
61: [Msg] Publishing entity deletions on [/world/default/scene/deletion]
61: [Msg] Publishing pose messages on [/world/default/pose/info]
61: [Dbg] [SimulationRunner.cc:543] Loaded system [ignition::gazebo::systems::SceneBroadcaster] for entity [1]
61: [Msg] Create service on [/world/default/create]
61: [Msg] Remove service on [/world/default/remove]
61: [Dbg] [SimulationRunner.cc:543] Loaded system [ignition::gazebo::systems::UserCommands] for entity [1]
61: [Msg] Network Primary, expects [2] secondaries.
61: [Msg] Serving GUI information on [/world/default/gui/info]
61: [Msg] World [default] initialized with [default_physics] physics profile.
61: [Msg] Loading SDF string.
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [2251689575469537287] / [ign_gazebo_components.World].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [13994732549916512682] / [ign_gazebo_components.Name].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [12592746352568925681] / [ign_gazebo_components.Gravity].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [13224937992534617849] / [ign_gazebo_components.MagneticField].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [8064491505919932473] / [ign_gazebo_components.Level].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [2668898242563798256] / [ign_gazebo_components.DefaultLevel].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [11371360182141354106] / [ign_gazebo_components.LevelEntityNames].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [3297509811873971798] / [ign_gazebo_components.ParentEntity].
61: [Msg] Serving scene information on [/world/default/scene/info]
61: [Msg] Serving graph information on [/world/default/scene/graph]
61: [Msg] Serving scene information on [/world/default/scene/info]
61: [Msg] Publishing entity deletions on [/world/default/scene/deletion]
61: [Msg] Publishing pose messages on [/world/default/pose/info]
61: [Dbg] [SimulationRunner.cc:543] Loaded system [ignition::gazebo::systems::SceneBroadcaster] for entity [1]
61: [Msg] Create service on [/world/default/create]
61: [Msg] Remove service on [/world/default/remove]
61: [Dbg] [SimulationRunner.cc:543] Loaded system [ignition::gazebo::systems::UserCommands] for entity [1]
61: [Dbg] [NetworkManagerSecondary.cc:49] Advertised PeerControl service on [d235de65/control]
61: [Msg] Network Secondary, with namespace [d235de65].
61: [Msg] Serving GUI information on [d235de65/world/default/gui/info]
61: [Msg] World [default] initialized with [default_physics] physics profile.
61: [Msg] Loading SDF string.
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [2251689575469537287] / [ign_gazebo_components.World].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [13994732549916512682] / [ign_gazebo_components.Name].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [12592746352568925681] / [ign_gazebo_components.Gravity].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [13224937992534617849] / [ign_gazebo_components.MagneticField].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [8064491505919932473] / [ign_gazebo_components.Level].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [2668898242563798256] / [ign_gazebo_components.DefaultLevel].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [11371360182141354106] / [ign_gazebo_components.LevelEntityNames].
61: [Dbg] [EntityComponentManager.cc:544] Using components of type [3297509811873971798] / [ign_gazebo_components.ParentEntity].
61: [Msg] Serving scene information on [/world/default/scene/info�[�[1;33m[WWrn] [Componet[WWrn] [ComponetTrying to serialize copmponent of type [Trying to serialize copmponent of type [22516895754695372872251689575469537287], which hasn't implemented the `Serialize` function. Component will not be serialized.
61: ], which hasn't implemented the `Serialize` function. Component will not be serialized.
61/82 Test #61: INTEGRATION_network_handshake ................***Exception: SegFault  3.07 sec

INTEGRATION_physics_system

Platforms: Homebrew

Failures

Unable to find test results for INTEGRATION_physics_system.xml, test did not run. Expected results in /Users/jenkins/workspace/ignition_gazebo-ci-ign-gazebo3-homebrew-amd64/build/test_results/INTEGRATION_physics_system.xml

Date added: 2020-07-10

UNIT_PeerTracker_TEST

Platforms: Homebrew

Failures:

/Users/jenkins/workspace/ignition_gazebo-ci-pr_any-homebrew-amd64/ign-gazebo/src/network/PeerTracker_TEST.cc:258
Value of: tracker3.NumPeers()
  Actual: 0
Expected: 1u
Which is: 1
/Users/jenkins/workspace/ignition_gazebo-ci-pr_any-homebrew-amd64/ign-gazebo/src/network/PeerTracker_TEST.cc:84
Value of: tracker5->NumPeers()
  Actual: 2
Expected: 5u
Which is: 5
/Users/jenkins/workspace/ignition_gazebo-ci-pr_any-homebrew-amd64/ign-gazebo/src/network/PeerTracker_TEST.cc:163
Value of: stalePeers
  Actual: 0
Expected: 1
/Users/jenkins/workspace/ignition_gazebo-ci-ign-gazebo2-homebrew-amd64/ign-gazebo/src/network/PeerTracker_TEST.cc:167
Value of: tracker1->NumPeers()
  Actual: 1
Expected: 0u
Which is: 0

UNIT_NetworkManager_TEST

Platforms: Pipelines

Failures:

31: [ RUN      ] NetworkManager.Step
31: �[1;33m[Wrn] �[0m�[1;33m[�[0m�[1;33mNetworkManagerPrimary.cc�[0m�[1;33m:�[0m�[1;33m69�[0m�[1;33m] �[0m�[1;33mNetworkManager started without EventManager. �[0m�[1;33mDistributed environment may not terminate correctly�[0m�[1;33m�[0m
31/82 Test #31: UNIT_NetworkManager_TEST .....................***Exception: SegFault  1.15 sec

INTEGRATION_gpu_lidar failing on homebrew

Original report (archived issue) by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

The INTEGRATION_gpu_lidar test has been failing consistently for a while on homebrew with the following output:

97: [ RUN      ] GpuLidarTest.GpuLidarBox
97: objc[94474]: Class OgreConfigWindowDelegate is implemented in both /usr/local/opt/ogre1.9/lib/libOgreMain.1.9.0.dylib (0x110913dc0) and /usr/local/opt/ogre2.1/lib/libOgreMain.2.1.0.dylib (0x110334838). One of the two will be used. Which one is undefined.
97: dyld: lazy symbol binding failed: Symbol not found: __ZN4Ogre2v113OverlaySystemC1Ev
97:   Referenced from: /usr/local/Cellar/ignition-rendering2/2.0.0/lib/libignition-rendering2-ogre2.dylib
97:   Expected in: flat namespace
97: 
97: dyld: Symbol not found: __ZN4Ogre2v113OverlaySystemC1Ev
97:   Referenced from: /usr/local/Cellar/ignition-rendering2/2.0.0/lib/libignition-rendering2-ogre2.dylib
97:   Expected in: flat namespace
97: 
 97/104 Test  #97: INTEGRATION_gpu_lidar ................................Child aborted***Exception:   0.13 sec

As of this writing, the earliest jenkins build failure is from Jun 7, 2019 10:06:04 PM UTC (3 PM Pacific time).

In my email notifications from jenkins, I see failures of this test going back to May 16, then a big gap, and lots of failures from Feb 28 and earlier.

Steps to Reproduce

  1. Build ign-gazebo2 branch on a macOS machine that has XQuartz running
  2. Run the INTEGRATION_gpu_lidar test

Expected behavior:

The test passes on Ubuntu locally for me, though I noticed that the Ubuntu CI hasn't been running this test either recently.

Actual behavior:

Test seg-faults.

Reproduces how often:

100%

Versions

ign-gazebo2 2.0.0

macOS mojave

Additional Information

Move user camera to model

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Summary

On Gazebo-classic, double-clicking a model or right-click -> move to is a convenient way of teleporting the user camera to a specific model.

Motivation

It's convenient to be able to quickly zoom into a specific model in the world.

Describe alternatives you've considered

This feature is closely related to model tracking, #29.

We've heard user complaints about the double-click behaviour on Gazebo classic, so we could reconsider that interaction and think of something more intuitive.

Additional context

Expose scene properties through the UI

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Summary

It's often helpful to change properties such as lighting and background color after the simulation has been launched. Exposing these options through the UI would be convenient to users. We could also expose services that can be called from code or command line.

Motivation

While inspecting a 3D scene, it's often helpful to tweak environment settings.

Describe alternatives you've considered

  • Expose properties through the UI, like Gazebo classic's Scene dropdown under the world tree
  • Ignition services that can be called from code or command line

Additional context

Gazebo classic:

scene_props.gif

These properties are already held by components::Scene. We could add a UserCommand to change it and have the Scene3D plugin detect and apply the changes.

Create GUI on demand

Original report (archived issue) by Mabel Zhang (Bitbucket: mabelmzhang, GitHub: mabelzhang).


Summary

Feature to create / change GUI on demand, and expose it in e.g. SdfEntityCreator->CreateEntities(sdf::Gui) along with the other entities.

Motivation

Logging playback currently must ignore <gui> tag in the recorded SDF file, since the GUI can only be created at startup. This results in behavior like https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-gazebo/pull-requests/181/acropolis-add-logging/activity#comment-94389783 , i.e. the recorded file uses <engine>ogre2</engine>, and the playback defaults to ogre, which results in the whole scene being a lot brighter.

macOS tests seg-fault during teardown

Original report (archived issue) by Steve Peters (Bitbucket: Steven Peters, GitHub: scpeters).


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

Many tests fail on homebrew.

Build Status https://build.osrfoundation.org/view/main/view/ignition/job/ignition_gazebo-ci-default-homebrew-amd64/3/testReport/

Steps to Reproduce

  1. Build ignition-gazebo on homebrew.
  2. Run make test

Expected behavior:

Tests pass on Ubuntu, so they should pass on homebrew too.

Actual behavior:

Tests fail. The console output includes Illegal instruction: 4.

$ bin/INTEGRATION_physics_system 
Running main() from gtest_main.cc
[==========] Running 4 tests from 1 test case.
[----------] Global test environment set-up.
[----------] 4 tests from PhysicsSystemFixture
[ RUN      ] PhysicsSystemFixture.CreatePhysicsWorld
Error setting socket option (IP_ADD_MEMBERSHIP).
Error setting socket option (IP_ADD_MEMBERSHIP).
Illegal instruction: 4 (core dumped)

I've collected a backtrace and posted it:

It's very long and implicates the destructors of various objects.

Reproduces how often:

100%

Versions

macOS mojave

Additional Information

Playback latest timestamped log file

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Summary

Log files are saved in a ~/.ignition/gazebo/log/<timestamp> directory unless a path is specified. It would be nice to be able to easily playback the latest log file without needing to navigate to the correct timestamp.

Motivation

It can be tedious to find the latest log by autocompleting the files under ~/.ignition/gazebo/log. We often just want to playback the latest log.

Describe alternatives you've considered

One possible implementation could be that passing --playback with an empty argument, would be interpreted as "play the latest log file in ~/.ignition/gazebo/log"

Another option would be to keep a ~/.ignition/gazebo/log/latest directory which symlinks to the latest log. This would make it easier to also quickly inspect the server_console.log.

ODE crash on `rolling_shapes.sdf`

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Prerequisites

  • [ X ] Put an X between the brackets on this line if you have done all of the following:

Description

rolling_shapes.sdf crashes after about 20s sim time with:

ODE INTERNAL ERROR 1: assertion "bNormalizationResult" failed in _dNormalize4() [odemath.h:42]

Steps to Reproduce

  1. ign-gazebo -v 4 -f rolling_shapes.sdf-r
  2. Wait 20 seconds

Expected behavior:

No crash

Actual behavior:

Crash

Reproduces how often:

100% of tries

Versions

ign-gazebo1

Additional Information

N/A

Cannot launch on first install on Ubuntu 18.04

Original report (archived issue) by Pierre Paques (Bitbucket: ppaques).


  • [ x] Put an X between the brackets on this line if you have done all of the following:

Description

After installing ignition gazebo using standard tutorial, ignition gazebo 2.8.0 is not starting due to missing files:/usr/share/ignition/ignition-gazebo2/gui/gui.config

Here is the log (-v 4)

[Msg] Ignition Gazebo Server v2.8.0
[Msg] Ignition Gazebo GUI    v2.8.0
[Msg] Loading default world.
[Dbg] [EntityComponentManager.cc:623] Using components of type [2251689575469537287] / [ign_gazebo_components.World].
[Dbg] [EntityComponentManager.cc:623] Using components of type [13994732549916512682] / [ign_gazebo_components.Name].
[Dbg] [EntityComponentManager.cc:623] Using components of type [12592746352568925681] / [ign_gazebo_components.Gravity].
[Dbg] [EntityComponentManager.cc:623] Using components of type [13224937992534617849] / [ign_gazebo_components.MagneticField].
[Dbg] [EntityComponentManager.cc:623] Using components of type [8753193699724811771] / [ign_gazebo_components.Wind].
[Dbg] [EntityComponentManager.cc:623] Using components of type [12173050716021724529] / [ign_gazebo_components.WorldLinearVelocity].
[Dbg] [EntityComponentManager.cc:623] Using components of type [15943768124495574352] / [ign_gazebo_components.WorldLinearVelocitySeed].
[Dbg] [EntityComponentManager.cc:623] Using components of type [3297509811873971798] / [ign_gazebo_components.ParentEntity].
[Dbg] [EntityComponentManager.cc:623] Using components of type [17100615127981600159] / [ign_gazebo_components.Scene].
[Dbg] [EntityComponentManager.cc:623] Using components of type [8064491505919932473] / [ign_gazebo_components.Level].
[Dbg] [EntityComponentManager.cc:623] Using components of type [2668898242563798256] / [ign_gazebo_components.DefaultLevel].
[Dbg] [EntityComponentManager.cc:623] Using components of type [11371360182141354106] / [ign_gazebo_components.LevelEntityNames].
[Dbg] [SimulationRunner.cc:688] Loaded system [ignition::gazebo::systems::SceneBroadcaster] for entity [1]
[Dbg] [Application.cc:87] Initializing application.
[GUI] [Dbg] [Application.cc:407] Create main window
[Dbg] [SimulationRunner.cc:688] Loaded system [ignition::gazebo::systems::Physics] for entity [1]
[Msg] Create service on [/world/default/create]
[Msg] Remove service on [/world/default/remove]
[Msg] Pose service on [/world/default/set_pose]
[Dbg] [SimulationRunner.cc:688] Loaded system [ignition::gazebo::systems::UserCommands] for entity [1]
[Msg] Loaded level [3]
[Msg] Serving GUI information on [/world/default/gui/info]
[Msg] World [default] initialized with [default_physics] physics profile.
[GUI] [Err] [Application.cc:233] Failed to load file [/usr/share/ignition/ignition-gazebo2/gui/gui.config]: XMLError
[GUI] [Dbg] [Application.cc:130] Terminating application.
[Dbg] [SignalHandler.cc:141] Received signal[2].
[Dbg] [ServerPrivate.cc:106] Server received signal[2]
[Msg] Found no publishers on /stats, adding root stats topic
[Msg] Found no publishers on /clock, adding root clock topic

OS:

  • Ubuntu 18.04 LTS
  • use of official packages in apt.

Steps to Reproduce

  1. Clean ubuntu install (no other gazebo install)
  2. Install using tutorials and packages
  3. launch in console ign gazebo

**Expected behavior:**

Out of the box start

**Actual behavior:**

…died

Reproduces how often:

100 percent

Soution to load:

sudo mkdir -p /usr/share/ignition/ignition-gazebo2/gui
vim /usr/share/ignition/ignition-gazebo2/gui/gui.config
   =&amp;gt; copy content https://github.com/ignitionrobotics/ign-gazebo/blob/master/include/ignition/gazebo/gui/gui.config
   sudo chmod -R 655 /usr/share/ignition/ignition-gazebo2/gui

After the system crashes inside ruby interpreter but not got the time to investigate more

dae file not display on gazebo

Original report (archived issue) by clementbubus (Bitbucket: clementbus).


Prerequisites

  • Put an X between the brackets on this line if you have done all of the following:

Description

Hi,
I have just installed Ignition Acropolis to test the actual features. I have tried to launch a world
with the basics (light & ground plane) with success.
After that I have add a model with a dae file as shown below :

<model name="duck1">
  <pose>0 1 3 0.0 0.0 1.57</pose>
  <link name="duck_link">
    <inertial>
      <inertia>
        <ixx>3.92</ixx>
        <ixy>0</ixy>
        <ixz>0</ixz>
        <iyy>3.92</iyy>
        <iyz>0</iyz>
        <izz>3.92</izz>
      </inertia>
      <mass>39</mass>
    </inertial>
    <collision name="duck_collision">
      <pose>0 0 -0.4 1.57 0.0 0.0</pose>
      <geometry>
        <mesh>
          <scale>0.5 0.5 0.5</scale>
          <uri>file://test/media/duck.dae</uri>
        </mesh>
      </geometry>
    </collision>

    <visual name="duck_visual">
      <pose>0 0 -0.4 1.57 0.0 0.0</pose>
      <geometry>
        <mesh>
          <scale>0.5 0.5 0.5</scale>
          <uri>file://test/media/duck.dae</uri>
        </mesh>
      </geometry>
    </visual>
  </link>
</model>

I launch ign-gazebo like that: ign-gazebo -v 4 -f world/x8.world

Everything seems to be ok in the terminal but the model isn't visible on the screen.

Msg] Ignition Gazebo        v1.1.0
[Msg] Ignition Gazebo GUI    v1.1.0
[Msg] Ignition Gazebo Server v1.1.0
[Msg] Loading SDF world file[/mnt/workbench/ignition_gazebo_ws/ignition_gazebo_ws/world/x8.world].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [2251689575469537287].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [13994732549916512682].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [12592746352568925681].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [13224937992534617849].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [8064491505919932473].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [2668898242563798256].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [11371360182141354106].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [3297509811873971798].
[Dbg] [Application.cc:87] Initializing application.
[GUI] [Dbg] [Application.cc:395] Create main window
[Msg] Create service on [/world/empty/create]
[Msg] Remove service on [/world/empty/remove]
[Msg] Serving scene information on [/world/empty/scene/info]
[Msg] Serving graph information on [/world/empty/scene/graph]
[Msg] Serving scene information on [/world/empty/scene/info]
[Msg] Publishing entity deletions on [/world/empty/scene/deletion]
[Msg] Publishing pose messages on [/world/empty/pose/info]
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [6687176221774458630].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [6612894081701502240].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [8546580419506082455].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [5081358965268446661].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [8112400427272910195].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [16454635107327670381].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [17121648710877364109].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [9853217982010720764].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [17938588655714334139].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [10522242218202596205].
[Dbg] [EntityComponentManager.cc:537] Created storage for component type [3866641186784191835].
[Msg] Serving GUI information on [/world/empty/gui/info]
[Msg] World [empty] initialized with [1ms] physics profile.
[GUI] [Msg] Loading config [/usr/share/ignition/ignition-gazebo1/gui/gui.config]
[GUI] [Dbg] [Application.cc:267] Loading window config
[GUI] [Dbg] [Application.cc:409] Applying config
[GUI] [Dbg] [gui_main.cc:186] Requesting list of world names. The server may be busy downloading resources. Please be patient.
[GUI] [Dbg] [gui_main.cc:207] Requesting GUI from [/world/empty/gui/info]...
[GUI] [Msg] Loading plugin [Scene3D]
[GUI] [Msg] Added plugin [3D View] to main window
[GUI] [Msg] Loading plugin [WorldControl]
[GUI] [Msg] Added plugin [World control] to main window
[GUI] [Msg] Loading plugin [WorldStats]
[GUI] [Msg] Added plugin [World stats] to main window
[GUI] [Msg] Loading plugin [ignition-rendering1-ogre]
[GUI] [Dbg] [Scene3D.cc:912] Create scene [scene]
[GUI] [Dbg] [gui_main.cc:237] Shutting down ign-gazebo-gui
[GUI] [Dbg] [Application.cc:130] Terminating application.
[GUI] [Dbg] [Scene3D.cc:962] Destroy scene [scene]
[Dbg] [SignalHandler.cc:141] Received signal[2].
[Dbg] [SignalHandler.cc:141] Received signal[2].
[Dbg] [ServerPrivate.cc:57] Server received signal[2]
[Dbg] [server_main.cc:186] Shutting down ign-gazebo-server
[Dbg] [main.cc:276] Shutting down ign-gazebo

Steps to Reproduce

  1. [First Step]
    Launch the following sdf file with the dae file into the good folder.
<?xml version="1.0" ?>
<sdf version="1.6">
  <world name="empty">
   <physics name="1ms" type="ode">
      <max_step_size>0.001</max_step_size>
      <real_time_factor>1.0</real_time_factor>
    </physics>
    <plugin
      filename="libignition-gazebo-physics-system.so"
      name="ignition::gazebo::systems::Physics">
    </plugin>
    <plugin
      filename="libignition-gazebo-user-commands-system.so"
      name="ignition::gazebo::systems::UserCommands">
    </plugin>
    <plugin
      filename="libignition-gazebo-scene-broadcaster-system.so"
      name="ignition::gazebo::systems::SceneBroadcaster">
    </plugin>
    <plugin
      filename="libignition-gazebo-contact-system.so"
      name="ignition::gazebo::systems::Contact">
    </plugin>
 
    <gui fullscreen="0">

      <!-- 3D scene -->
      <plugin filename="Scene3D" name="3D View">
        <ignition-gui>
          <title>3D View</title>
          <property type="bool" key="showTitleBar">false</property>
          <property type="string" key="state">docked</property>
        </ignition-gui>

        <engine>ogre2</engine>
        <scene>scene</scene>
        <ambient_light>0.4 0.4 0.4</ambient_light>
        <background_color>0.8 0.8 0.8</background_color>
        <camera_pose>-6 0 6 0 0.5 0</camera_pose>
        <service>/world/empty/scene/info</service>
        <pose_topic>/world/empty/pose/info</pose_topic>
        <scene_topic>/world/empty/scene/info</scene_topic>
        <deletion_topic>/world/empty/scene/deletion</deletion_topic>
      </plugin>

      <!-- World control -->
      <plugin filename="WorldControl" name="World control">
        <ignition-gui>
          <title>World control</title>
          <property type="bool" key="showTitleBar">false</property>
          <property type="bool" key="resizable">false</property>
          <property type="double" key="height">72</property>
          <property type="double" key="width">121</property>
          <property type="double" key="z">1</property>

          <property type="string" key="state">floating</property>
          <anchors target="3D View">
            <line own="left" target="left"/>
            <line own="bottom" target="bottom"/>
          </anchors>
        </ignition-gui>

        <play_pause>true</play_pause>
        <step>true</step>
        <start_paused>true</start_paused>
        <service>/world/empty/control</service>
        <stats_topic>/world/empty/stats</stats_topic>

      </plugin>

      <!-- World statistics -->
      <plugin filename="WorldStats" name="World stats">
        <ignition-gui>
          <title>World stats</title>
          <property type="bool" key="showTitleBar">false</property>
          <property type="bool" key="resizable">false</property>
          <property type="double" key="height">110</property>
          <property type="double" key="width">290</property>
          <property type="double" key="z">1</property>

          <property type="string" key="state">floating</property>
          <anchors target="3D View">
            <line own="right" target="right"/>
            <line own="bottom" target="bottom"/>
          </anchors>
        </ignition-gui>

        <sim_time>true</sim_time>
        <real_time>true</real_time>
        <real_time_factor>true</real_time_factor>
        <iterations>true</iterations>
        <topic>/world/empty/stats</topic>

      </plugin>

    </gui>

    <light type="directional" name="sun">
      <cast_shadows>true</cast_shadows>
      <pose>0 0 10 0 0 0</pose>
      <diffuse>0.8 0.8 0.8 1</diffuse>
      <specular>0.2 0.2 0.2 1</specular>
      <attenuation>
        <range>1000</range>
        <constant>0.9</constant>
        <linear>0.01</linear>
        <quadratic>0.001</quadratic>
      </attenuation>
      <direction>-0.5 0.1 -0.9</direction>
    </light> 

    <model name="ground_plane">
      <static>true</static>
      <link name="link">
        <collision name="collision">
          <geometry>
            <box>
              <size>20 20 0.1</size>
            </box>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <box>
              <size>20 20 0.1</size>
            </box>
          </geometry>
          <material>
            <ambient>0.8 0.8 0.8 1</ambient>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.8 0.8 0.8 1</specular>
            <emissive>0.8 0.8 0.8 1</emissive>
          </material>
        </visual>
      </link>
    </model>
    <model name="duck1">
      <pose>0 1 3 0.0 0.0 1.57</pose>
      <link name="duck_link">
        <inertial>
          <inertia>
            <ixx>3.92</ixx>
            <ixy>0</ixy>
            <ixz>0</ixz>
            <iyy>3.92</iyy>
            <iyz>0</iyz>
            <izz>3.92</izz>
          </inertia>
          <mass>39</mass>
        </inertial>
        <collision name="duck_collision">
          <pose>0 0 -0.4 1.57 0.0 0.0</pose>
          <geometry>
            <mesh>
              <scale>0.5 0.5 0.5</scale>
              <uri>file://test/media/duck.dae</uri>
            </mesh>
          </geometry>
        </collision>

        <visual name="duck_visual">
          <pose>0 0 -0.4 1.57 0.0 0.0</pose>
          <geometry>
            <mesh>
              <scale>0.5 0.5 0.5</scale>
              <uri>file://test/media/duck.dae</uri>
            </mesh>
          </geometry>
        </visual>
      </link>
    </model>

  </world>
</sdf>
  1. [Second Step]
  2. [and so on...]

Expected behavior:

[What you expect to happen]
A gazebo screen with the duck on the ground plane

Actual behavior:

[What actually happens]
I just see a ground plane without my model loaded
Reproduces how often:

[What percentage of the time does it occur?]
Every time

Versions

Ignition Gazebo, version 1.1.0
[Include information about relevant software versions, and your OS type and version.]

Additional Information

[Any additional information, configuration or data that might be necessary to reproduce the issue.]

Fix levels documentation

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Description

The tutorial says that a level will be loaded as a performer enters its buffer zone, but that's not true. The buffer zone is taken into consideration when a model is leaving a level, not when it's coming in. That makes sense; if the buffer were used in both directions, then the level size itself would be useless.

Versions

All

Additional Information

We need to change the text and one of the images.

Plugin callbacks execution when the gazebo server is paused

Original report (archived issue) by Diego Ferigo (Bitbucket: dgferigo).


Prerequisites

Description

If the server starts in a paused state, the callbacks of the loaded plugins are executed.

Steps to Reproduce

Assuming:

  • A world with at least 1 plugin that implements at least one of the following callbacks: PreUpdate Update PostUpdate
  • The gazebo::Server started paused as non-blocking (that means on a different thread) with server->Run(/*blocking=*/false, numOfIterations, /*paused=*/true)

The server is later unpaused with:

server->SetPaused(false);

Expected behavior:

I would expect that the execution of the plugin callbacks begins only when the server is unpaused.

Actual behavior:

Between the call of server->Run and server->SetPaused(false), the callbacks are called. For instance, this is the case of systems::Physics::Update.

Reproduces how often:

Every time.

Versions

Current ign-gazebo1 branch (I have some local modifications but they are unrelated).

Additional Information

I am not sure if this is the intended behavior. I would expect that the Configure callback is executed even if the server is paused, not all the other ones.

Widget to choose / reset camera angles

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Summary

Have a widget that allows moving the camera to canonical angles, focused on given robots, as well as resetting to the initial view.

Motivation

When navigating a 3D environment, it's helpful to be able to switch the camera view to canonical angles, as well as resetting to the initial world view.

Describe alternatives you've considered

Gazebo-classic has a widget with all 6 canonical angles, zoom, and a reset view button. The view focused on the currently selected model.

We could implement this in different ways, like right-clicking the model, having keyboard shortcuts, etc.

Additional context

Weird sphere movement

Original report (archived issue) by Louise Poubel (Bitbucket: chapulina, GitHub: chapulina).


Pull request #51 adds an example world which has a sphere on top of a large box representing the ground plane. I'd expect the sphere, which has no link, visual, collision or inertia poses, to sit still on top of the floor, but instead it sways back and forth as if its CoM wasn't centered or its collision shape a smooth sphere:

moving_sphere.gif

I'm ticketing this here because I'm not sure if the issue is coming from ign-physics or the integration.

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.