├── .github
└── workflows
│ ├── humble.yaml
│ └── jazzy.yaml
├── .resources
├── floor_is_lava_map.png
├── floor_is_lava_world.png
├── parking_garage_map.png
├── parking_garage_world.png
├── tray_map.png
└── tray_world.png
├── CONTRIBUTING.md
├── LICENSE
├── README.md
├── mesh_navigation_tutorials
├── CMakeLists.txt
├── config
│ ├── ekf.yaml
│ ├── mbf_mesh_nav.yaml
│ └── rmcl_micpl.yaml
├── launch
│ ├── mbf_mesh_navigation_server_launch.py
│ └── mesh_navigation_tutorial_launch.py
├── maps
│ ├── floor_is_lava.dae
│ ├── floor_is_lava.h5
│ ├── floor_is_lava.ply
│ ├── floor_is_lava_s3.dae
│ ├── floor_is_lava_s3.h5
│ ├── floor_is_lava_s3.ply
│ ├── parking_garage.dae
│ ├── parking_garage.h5
│ ├── parking_garage.ply
│ ├── parking_garage_s4.dae
│ ├── parking_garage_s4.h5
│ ├── parking_garage_s4.ply
│ ├── tray.dae
│ ├── tray.h5
│ ├── tray.ply
│ ├── tray_s4.dae
│ ├── tray_s4.h5
│ └── tray_s4.ply
├── package.xml
└── rviz
│ └── default.rviz
├── mesh_navigation_tutorials_sim
├── CMakeLists.txt
├── config
│ └── ros_gazebo_bridge.yaml
├── hooks
│ ├── mesh_navigation_tutorials_sim.dsv.in
│ └── mesh_navigation_tutorials_sim.sh.in
├── launch
│ ├── ground_truth_localization_launch.xml
│ └── simulation_launch.py
├── meshes
│ └── wheel.stl
├── models
│ ├── floor_is_lava
│ │ ├── meshes
│ │ │ ├── floor_is_lava.dae
│ │ │ └── floor_is_lava.ply
│ │ ├── model.config
│ │ └── model.sdf
│ ├── parking_garage
│ │ ├── meshes
│ │ │ ├── parking_garage.dae
│ │ │ └── parking_garage_flipped.dae
│ │ ├── model.config
│ │ └── model.sdf
│ └── tray
│ │ ├── meshes
│ │ ├── tray.dae
│ │ └── tray.ply
│ │ ├── model.config
│ │ └── model.sdf
├── package.xml
├── src
│ └── ground_truth_localization.cpp
├── urdf
│ ├── ceres.urdf.xacro
│ ├── common.urdf.xacro
│ └── wheel.urdf.xacro
└── worlds
│ ├── floor_is_lava.sdf
│ ├── parking_garage.sdf
│ └── tray.sdf
├── pyproject.toml
└── source_dependencies.yaml
/.github/workflows/humble.yaml:
--------------------------------------------------------------------------------
1 | name: Humble CI
2 |
3 | on:
4 | push:
5 | branches:
6 | - 'main'
7 | pull_request:
8 | workflow_dispatch:
9 | branches:
10 | - '*'
11 |
12 | jobs:
13 | humble_build_and_test:
14 | uses: naturerobots/github_automation_public/.github/workflows/ros_ci.yaml@main
15 | secrets: inherit
16 | with:
17 | ros_distro: humble
18 |
--------------------------------------------------------------------------------
/.github/workflows/jazzy.yaml:
--------------------------------------------------------------------------------
1 | name: Jazzy CI
2 |
3 | on:
4 | push:
5 | branches:
6 | - 'main'
7 | pull_request:
8 | workflow_dispatch:
9 | branches:
10 | - '*'
11 |
12 | jobs:
13 | jazzy_build_and_test:
14 | uses: naturerobots/github_automation_public/.github/workflows/ros_ci.yaml@main
15 | secrets: inherit
16 | with:
17 | ros_distro: jazzy
18 |
--------------------------------------------------------------------------------
/.resources/floor_is_lava_map.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/.resources/floor_is_lava_map.png
--------------------------------------------------------------------------------
/.resources/floor_is_lava_world.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/.resources/floor_is_lava_world.png
--------------------------------------------------------------------------------
/.resources/parking_garage_map.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/.resources/parking_garage_map.png
--------------------------------------------------------------------------------
/.resources/parking_garage_world.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/.resources/parking_garage_world.png
--------------------------------------------------------------------------------
/.resources/tray_map.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/.resources/tray_map.png
--------------------------------------------------------------------------------
/.resources/tray_world.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/.resources/tray_world.png
--------------------------------------------------------------------------------
/CONTRIBUTING.md:
--------------------------------------------------------------------------------
1 | Any contribution that you make to this repository will
2 | be under the 3-Clause BSD License, as dictated by that
3 | [license](https://opensource.org/licenses/BSD-3-Clause).
4 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | BSD 3-Clause License
2 |
3 | Copyright (c) 2024, Nature Robots
4 |
5 | Redistribution and use in source and binary forms, with or without
6 | modification, are permitted provided that the following conditions are met:
7 |
8 | 1. Redistributions of source code must retain the above copyright notice, this
9 | list of conditions and the following disclaimer.
10 |
11 | 2. Redistributions in binary form must reproduce the above copyright notice,
12 | this list of conditions and the following disclaimer in the documentation
13 | and/or other materials provided with the distribution.
14 |
15 | 3. Neither the name of the copyright holder nor the names of its
16 | contributors may be used to endorse or promote products derived from
17 | this software without specific prior written permission.
18 |
19 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
23 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
24 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
25 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
27 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
28 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
29 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | [](https://github.com/naturerobots/mesh_navigation_tutorials/actions/workflows/jazzy.yaml)
2 | [](https://github.com/naturerobots/mesh_navigation_tutorials/actions/workflows/humble.yaml)
3 |
4 |
5 |
6 | Mesh Navigation Tutorials
7 |
8 |
9 |
10 |
20 |
21 |
22 |
23 |
24 | This repository contains a set of examples to quickly and easily start with [mesh_navigation](https://github.com/naturerobots/mesh_navigation).
25 | We provide different scenarios where our approach excels over state-of-the art 2D or 2.5D approaches.
26 | We will explain different parameter sets in more detail and show how to fine-tune [mesh_navigation](https://github.com/naturerobots/mesh_navigation) in various scenarios.
27 | Our example worlds consists of both real-world and hand-modelled scenarios.
28 | With the hand-modelled examples we particularly aim to support low-end computers or laptops.
29 |
30 |
31 | *Note*: Because of an great interest of people we talked to, we decided to release this repository in an unfinished state. It is still under construction and will be extended by more synthetic and real-world recorded worlds and detailed docs. It's open-source: Feel free to contribute.
32 |
33 | ## Requirements and Installation
34 |
35 | * You need a working ROS 2 installation. We target `humble` at the moment.
36 | * Go into a ROS 2 workspace's source directory `cd $YOUR_ROS_WS/src`.
37 | * Clone the tutorial code `git clone git@github.com:naturerobots/mesh_navigation_tutorials.git`
38 | * Get the tutorial's ROS 2 dependencies
39 | * Clone source dependencies: Run `vcs import --input mesh_navigation_tutorials/source_dependencies.yaml` in your ROS 2 workspace source directory.
40 | * Get packaged dependencies: Run `rosdep install --from-paths . --ignore-src -r -y` from within your ROS 2 workspace source directory.
41 | * Build: Go to workspace root `cd $YOUR_ROS_WS` and run `colcon build --packages-up-to mesh_navigation_tutorials`.
42 |
43 | ## Run the Examples
44 |
45 | ### Launch
46 | ```console
47 | ros2 launch mesh_navigation_tutorials mesh_navigation_tutorial_launch.py world_name:=floor_is_lava
48 | ```
49 |
50 | You change `floor_is_lava` by any world name that is available with this repository (see all by calling launch file with `--show-args`). Those are:
51 |
52 | | Name | World | Default Map | Description |
53 | |------|-------|-----|-------------|
54 | | tray |  | | This world is a rectangular area with a wall around the perimeter. |
55 | | floor_is_lava |  | | This world contains a square area with with two pits and a connecting section at a slightly higher elevation.
56 | | parking_garage |  | | This world represents a parking garage with multiple floors connected by ramps. |
57 |
58 | When running a simulated world, you can save some resources by not running the gazebo GUI: Add the `start_gazebo_gui:=False` launch argument.
59 |
60 | ### Rviz GUI
61 | In rviz, you should be able to see the mesh map.
62 | This map is being used for navigation.
63 |
64 | In order to make the robot move, find the "Mesh Goal" tool at the top.
65 | With it, you can click on any part of the mesh.
66 | Click and hold to set a goal pose.
67 | The MbfGoalActions rviz plugin contains a very tiny state machine that performs the following actions:
68 | * subscribe to that goal pose
69 | * get a path to that pose
70 | * execute that path
71 |
72 | ## Detailed Instructions
73 |
74 | For more detailed instructions on how to parameterize things or what things can be changed see the [wiki](https://github.com/naturerobots/mesh_navigation_tutorials/wiki)
75 |
76 |
77 | ## Related Repositories
78 | - [Move Base Flex](https://github.com/magazino/move_base_flex) ([IROS 2018](https://doi.org/10.1109/IROS.2018.8593829))
79 | - [Mesh Tools](https://github.com/naturerobots/mesh_tools) ([RAS 2021](https://doi.org/10.1016/j.robot.2020.103688))
80 | - [Mesh Navigation](https://github.com/naturerobots/mesh_navigation) ([ICRA 2021 paper for Continuous Vector Field Planner, CVP](https://doi.org/10.1109/ICRA48506.2021.9560981))
81 | - [Rmagine](https://github.com/uos/rmagine) ([ICRA 2023](https://doi.org/10.1109/ICRA48891.2023.10161388))
82 | - [MICP-L](https://github.com/uos/rmcl) ([IROS 2024](https://arxiv.org/abs/2210.13904))
83 | - [RMCL](https://github.com/uos/rmcl)
84 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.8)
2 | project(mesh_navigation_tutorials)
3 |
4 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
5 | add_compile_options(-Wall -Wextra -Wpedantic -Werror)
6 | endif()
7 |
8 | # find dependencies
9 | find_package(ament_cmake REQUIRED)
10 |
11 | # install
12 | install(DIRECTORY config launch rviz maps
13 | DESTINATION share/${PROJECT_NAME}
14 | )
15 |
16 | # test
17 | if(BUILD_TESTING)
18 | find_package(ament_lint_auto REQUIRED)
19 | ament_lint_auto_find_test_dependencies()
20 | endif()
21 |
22 | ament_package()
23 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/config/ekf.yaml:
--------------------------------------------------------------------------------
1 | ekf_filter_node:
2 | ros__parameters:
3 | frequency: 50.0
4 | two_d_mode: true
5 |
6 | debug: false
7 |
8 | map_frame: map # Defaults to "map" if unspecified
9 | odom_frame: odom # Defaults to "odom" if unspecified
10 | base_link_frame: base_footprint # Defaults to "base_link" if unspecified
11 | world_frame: odom # Defaults to the value of odom_frame if unspecified
12 |
13 | odom0: /odom
14 | odom0_config: [false, false, false, #xyz
15 | false, false, false, # rpy
16 | true, false, false, #vxyz
17 | false, false, true, #vrpy
18 | false, false, false] #axyz
19 |
20 | odom0_differential: false
21 | # odom0_relative: true
22 |
23 | imu0: /imu/data
24 | imu0_config: [false, false, false, #xyz
25 | false, false, false, # rpy
26 | false, false, false, #vxyz
27 | true, true, true, #vrpy
28 | false, false, false] #axyz
29 | imu0_differential: false
30 |
31 | use_control: false
32 |
33 | # Whether the input (assumed to be cmd_vel) is a geometry_msgs/Twist or geometry_msgs/TwistStamped message. Defaults to
34 | # false.
35 | stamped_control: true
36 |
37 | # The last issued control command will be used in prediction for this period. Defaults to 0.2.
38 | control_timeout: 0.2
39 |
40 | # Which velocities are being controlled. Order is vx, vy, vz, vroll, vpitch, vyaw.
41 | control_config: [true, false, false, false, false, true]
42 |
43 | # Places limits on how large the acceleration term will be. Should match your robot's kinematics.
44 | acceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 3.4]
45 |
46 | # Acceleration and deceleration limits are not always the same for robots.
47 | deceleration_limits: [1.3, 0.0, 0.0, 0.0, 0.0, 4.5]
48 |
49 | # If your robot cannot instantaneously reach its acceleration limit, the permitted change can be controlled with these
50 | # gains
51 | acceleration_gains: [0.8, 0.0, 0.0, 0.0, 0.0, 0.9]
52 |
53 | # If your robot cannot instantaneously reach its deceleration limit, the permitted change can be controlled with these
54 | # gains
55 | deceleration_gains: [1.0, 0.0, 0.0, 0.0, 0.0, 1.0]
56 | # imu0_relative: true
57 |
58 | # imu0_remove_gravitational_acceleration: true
59 |
60 | # process_noise_covariance: [0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
61 | # 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
62 | # 0.0, 0.0, 0.2, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
63 | # 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
64 | # 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
65 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
66 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
67 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.025, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
68 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
69 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0,
70 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0,
71 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0,
72 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0, 0.0,
73 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1, 0.0,
74 | # 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.1]
75 |
76 | # [ADVANCED] This represents the initial value for the state estimate error covariance matrix. Setting a diagonal
77 | # value (variance) to a large value will result in rapid convergence for initial measurements of the variable in
78 | # question. Users should take care not to use large values for variables that will not be measured directly. The values
79 | # are ordered as x, y, z, roll, pitch, yaw, vx, vy, vz, vroll, vpitch, vyaw, ax, ay, az. Defaults to the diagonal values below
80 | # if unspecified. In this example, we specify only the diagonal of the matrix.
81 | # initial_estimate_covariance: [1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9, 1e-9]
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/config/mbf_mesh_nav.yaml:
--------------------------------------------------------------------------------
1 | move_base_flex:
2 | ros__parameters:
3 | global_frame: 'map'
4 | robot_frame: 'base_footprint'
5 | odom_topic: 'odom'
6 |
7 | use_sim_time: true
8 | force_stop_at_goal: true
9 | force_stop_on_cancel: true
10 |
11 | planners: ['mesh_planner']
12 | mesh_planner:
13 | type: 'cvp_mesh_planner/CVPMeshPlanner'
14 | cost_limit: 0.8
15 | publish_vector_field: true
16 | planner_patience: 10.0
17 | planner_max_retries: 2
18 | project_path_onto_mesh: false
19 |
20 | controllers: ['mesh_controller']
21 | mesh_controller:
22 | type: 'mesh_controller/MeshController'
23 | ang_vel_factor: 7.0
24 | lin_vel_factor: 1.0
25 |
26 | controller_patience: 2.0
27 | controller_max_retries: 4
28 | dist_tolerance: 0.2
29 | angle_tolerance: 0.8
30 | cmd_vel_ignored_tolerance: 10.0
31 |
32 | mesh_map:
33 | # input
34 | # mesh_file: '/home/amock/mesh_nav_ws/src/mesh_navigation_tutorials/mesh_navigation_tutorials/maps/parking_garage.ply'
35 | mesh_part: '/'
36 | # storage
37 | # mesh_working_file: 'parking_garage.h5'
38 | mesh_working_part: 'mesh'
39 |
40 | # half-edge-mesh implementation
41 | hem: pmp # pmp (default), lvr
42 |
43 | layers: ['border', 'height_diff', 'roughness', 'inflation']
44 |
45 | height_diff:
46 | type: 'mesh_layers/HeightDiffLayer'
47 | factor: 1.0
48 | threshold: 0.8
49 |
50 | border:
51 | type: 'mesh_layers/BorderLayer'
52 | factor: 1.0
53 | border_cost: 1.0
54 | threshold: 0.2
55 |
56 | roughness:
57 | type: 'mesh_layers/RoughnessLayer'
58 | factor: 1.0
59 | threshold: 0.8
60 |
61 | inflation:
62 | type: 'mesh_layers/InflationLayer'
63 | factor: 1.0
64 | inflation_radius: 0.2
65 | inscribed_radius: 0.4
66 | lethal_value: 1.0
67 | inscribed_value: 0.8
68 | repulsive_field: false
69 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/config/rmcl_micpl.yaml:
--------------------------------------------------------------------------------
1 | micp_localization:
2 | ros__parameters:
3 |
4 | # required
5 | base_frame: base_footprint
6 | map_frame: map
7 | odom_frame: odom
8 |
9 | # rate of broadcasting tf transformations
10 | tf_rate: 50.0
11 |
12 | micp:
13 | # merging on gpu or cpu
14 | combining_unit: cpu
15 | # maximum number of correction steps per second
16 | # lower this to decrease the correction speed but save energy
17 | corr_rate_max: 20.0
18 |
19 | # adjust max distance dependend of the state of localization
20 | adaptive_max_dist: True # enable adaptive max dist
21 |
22 | # DEBUGGING
23 | # corr = correspondences
24 | viz_corr: True
25 | # corr = correction
26 | print_corr_rate: False
27 | disable_corr: False
28 |
29 | # initial pose changes
30 | trans: [0.0, 0.0, 0.0]
31 | rot: [0.0, 0.0, 0.0] # euler angles (3) or quaternion (4)
32 |
33 | # describe your sensor setup here
34 | sensors: # list of range sensors - at least one is required
35 | laser3d:
36 | topic: cloud
37 | topic_type: sensor_msgs/msg/PointCloud2
38 | # normally it could also be a more memory-friendly spherical sensor model.
39 | # However, I dont trust the Gazebo sensor
40 | type: o1dn
41 | model:
42 | range_min: 0.5
43 | range_max: 130.0
44 | orig: [0.0, 0.0, 0.0]
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/launch/mbf_mesh_navigation_server_launch.py:
--------------------------------------------------------------------------------
1 | # Copyright 2024 Nature Robots GmbH
2 | #
3 | # Redistribution and use in source and binary forms, with or without
4 | # modification, are permitted provided that the following conditions are met:
5 | #
6 | # * Redistributions of source code must retain the above copyright
7 | # notice, this list of conditions and the following disclaimer.
8 | #
9 | # * Redistributions in binary form must reproduce the above copyright
10 | # notice, this list of conditions and the following disclaimer in the
11 | # documentation and/or other materials provided with the distribution.
12 | #
13 | # * Neither the name of the Nature Robots GmbH nor the names of its
14 | # contributors may be used to endorse or promote products derived from
15 | # this software without specific prior written permission.
16 | #
17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 | # POSSIBILITY OF SUCH DAMAGE.
28 |
29 |
30 | import os
31 |
32 | from ament_index_python.packages import get_package_share_directory
33 |
34 | from launch import LaunchDescription
35 | from launch.actions import DeclareLaunchArgument
36 | from launch.substitutions import LaunchConfiguration
37 |
38 | from launch_ros.actions import Node
39 |
40 |
41 | def generate_launch_description():
42 | launch_args = [
43 | DeclareLaunchArgument(
44 | "mesh_map_path",
45 | description="Path to the mesh file that defines the map."
46 | "Allowed formats are our internal HDF5 format and all"
47 | "standard mesh formats loadable by Assimp.",
48 | ),
49 | DeclareLaunchArgument(
50 | "mesh_map_working_path",
51 | description="Path to the mesh file used by the mesh navigation "
52 | "to store costs during operation. Only HDF5 formats are permitted.",
53 | ),
54 | ]
55 | mesh_map_path = LaunchConfiguration("mesh_map_path")
56 | mesh_map_working_path = LaunchConfiguration("mesh_map_working_path")
57 |
58 | mbf_mesh_nav_config = os.path.join(
59 | get_package_share_directory("mesh_navigation_tutorials"), "config", "mbf_mesh_nav.yaml"
60 | )
61 |
62 | mesh_nav_server = Node(
63 | name="move_base_flex",
64 | package="mbf_mesh_nav",
65 | executable="mbf_mesh_nav",
66 | remappings=[
67 | ("/move_base_flex/cmd_vel", "/cmd_vel"),
68 | ],
69 | parameters=[
70 | mbf_mesh_nav_config,
71 | {
72 | "mesh_map.mesh_file": mesh_map_path,
73 | "mesh_map.mesh_working_file": mesh_map_working_path
74 | }
75 | ]
76 | )
77 |
78 | return LaunchDescription(
79 | launch_args
80 | + [
81 | mesh_nav_server,
82 | ]
83 | )
84 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/launch/mesh_navigation_tutorial_launch.py:
--------------------------------------------------------------------------------
1 | # Copyright 2024 Nature Robots GmbH
2 | #
3 | # Redistribution and use in source and binary forms, with or without
4 | # modification, are permitted provided that the following conditions are met:
5 | #
6 | # * Redistributions of source code must retain the above copyright
7 | # notice, this list of conditions and the following disclaimer.
8 | #
9 | # * Redistributions in binary form must reproduce the above copyright
10 | # notice, this list of conditions and the following disclaimer in the
11 | # documentation and/or other materials provided with the distribution.
12 | #
13 | # * Neither the name of the Nature Robots GmbH nor the names of its
14 | # contributors may be used to endorse or promote products derived from
15 | # this software without specific prior written permission.
16 | #
17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 | # POSSIBILITY OF SUCH DAMAGE.
28 |
29 |
30 | import os
31 |
32 | from ament_index_python.packages import get_package_share_directory
33 |
34 | from launch import LaunchDescription
35 | from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
36 | from launch.conditions import IfCondition
37 | from launch.substitutions import PathJoinSubstitution, PythonExpression, LaunchConfiguration
38 | from launch.launch_description_sources import PythonLaunchDescriptionSource
39 |
40 | from launch_ros.actions import Node
41 |
42 |
43 | def generate_launch_description():
44 | # path to this pkg
45 | pkg_mesh_navigation_tutorials_sim = get_package_share_directory(
46 | "mesh_navigation_tutorials_sim"
47 | )
48 | pkg_mesh_navigation_tutorials = get_package_share_directory("mesh_navigation_tutorials")
49 |
50 | # Comment Alex: One can have different maps for same worlds
51 | # Is this to much choice for a tutorial?
52 |
53 | # Loading a map files with the following extension
54 | mesh_nav_map_ext = ".ply"
55 |
56 | available_map_names = [
57 | f[:-len(mesh_nav_map_ext)]
58 | for f in os.listdir(os.path.join(pkg_mesh_navigation_tutorials, "maps"))
59 | if f.endswith(mesh_nav_map_ext)
60 | ]
61 |
62 | # Launch arguments
63 | launch_args = [
64 | DeclareLaunchArgument(
65 | "map_name",
66 | description="Name of the map to be used for navigation"
67 | + '(see mesh_navigation_tutorials\' "maps" directory).',
68 | default_value=LaunchConfiguration("world_name"),
69 | choices=available_map_names,
70 | ),
71 | DeclareLaunchArgument(
72 | "localization_type",
73 | description="How the robot shall localize itself",
74 | default_value="ground_truth",
75 | choices=["ground_truth", "rmcl_micpl"],
76 | ),
77 | DeclareLaunchArgument(
78 | "start_rviz",
79 | description="Whether rviz shall be started.",
80 | default_value="True",
81 | choices=["True", "False"],
82 | ),
83 | ]
84 | map_name = LaunchConfiguration("map_name")
85 | world_name = LaunchConfiguration("world_name")
86 | start_rviz = LaunchConfiguration("start_rviz")
87 | localization_type = LaunchConfiguration("localization_type")
88 |
89 | # suggestion:
90 | # - every world has one map with same name as default
91 | # - only if map_name is specified another map than default is loaded
92 | # map_name = world_name
93 |
94 | # Launch simulation environment and robot
95 | simulation = IncludeLaunchDescription(
96 | PythonLaunchDescriptionSource(
97 | PathJoinSubstitution(
98 | [pkg_mesh_navigation_tutorials_sim, "launch", "simulation_launch.py"]
99 | )
100 | )
101 | )
102 |
103 | # odom -> base_footprint
104 | ekf = Node(
105 | package="robot_localization",
106 | executable="ekf_node",
107 | name="ekf_filter_node",
108 | output="screen",
109 | parameters=[
110 | {"use_sim_time": True},
111 | PathJoinSubstitution([pkg_mesh_navigation_tutorials, "config", "ekf.yaml"]),
112 | ],
113 | )
114 |
115 | # Ground truth map localization
116 | map_loc_gt = Node(
117 | package="mesh_navigation_tutorials_sim",
118 | executable="ground_truth_localization_node",
119 | name="ground_truth_localization_node",
120 | output="screen",
121 | parameters=[
122 | {
123 | "use_sim_time": True,
124 | "gz_parent_frame": world_name,
125 | "gz_child_frame": "robot",
126 | "ros_parent_frame": "map",
127 | "ros_child_frame": "base_footprint",
128 | "ros_odom_frame": "odom",
129 | }
130 | ],
131 | condition=IfCondition(PythonExpression(['"', localization_type, '" == "ground_truth"'])),
132 | )
133 |
134 | # RMCL Localization
135 | map_loc_rmcl_micp = Node(
136 | package="rmcl",
137 | executable="micp_localization",
138 | name="micp_localization",
139 | output="screen",
140 | remappings=[
141 | ("pose_wc", "/initialpose"),
142 | ],
143 | parameters=[
144 | {
145 | "use_sim_time": True,
146 | "map_file": PathJoinSubstitution(
147 | [
148 | pkg_mesh_navigation_tutorials,
149 | "maps",
150 | PythonExpression(['"', map_name, '" + ".dae"']),
151 | ]
152 | ),
153 | },
154 | PathJoinSubstitution([pkg_mesh_navigation_tutorials, "config", "rmcl_micpl.yaml"]),
155 | ],
156 | condition=IfCondition(PythonExpression(['"', localization_type, '" == "rmcl_micpl"'])),
157 | )
158 |
159 | # Move Base Flex
160 | move_base_flex = IncludeLaunchDescription(
161 | PythonLaunchDescriptionSource(
162 | PathJoinSubstitution(
163 | [pkg_mesh_navigation_tutorials, "launch", "mbf_mesh_navigation_server_launch.py"]
164 | )
165 | ),
166 | launch_arguments={
167 | "mesh_map_path": PathJoinSubstitution(
168 | [
169 | pkg_mesh_navigation_tutorials,
170 | "maps",
171 | PythonExpression(['"', map_name, mesh_nav_map_ext, '"']),
172 | ]
173 | ),
174 | "mesh_map_working_path": PythonExpression(['"', map_name, '" + ".h5"'])
175 | }.items(),
176 | )
177 |
178 | # Start rviz, if desired
179 | rviz = Node(
180 | package="rviz2",
181 | executable="rviz2",
182 | parameters=[
183 | {"use_sim_time": True},
184 | ],
185 | arguments=[
186 | "-d",
187 | PathJoinSubstitution([pkg_mesh_navigation_tutorials, "rviz", "default.rviz"]),
188 | ],
189 | condition=IfCondition(start_rviz),
190 | )
191 |
192 | return LaunchDescription(
193 | launch_args
194 | + [
195 | simulation,
196 | ekf,
197 | map_loc_gt,
198 | map_loc_rmcl_micp,
199 | move_base_flex,
200 | rviz,
201 | ]
202 | )
203 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/floor_is_lava.h5:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/floor_is_lava.h5
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/floor_is_lava.ply:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/floor_is_lava.ply
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/floor_is_lava_s3.h5:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/floor_is_lava_s3.h5
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/floor_is_lava_s3.ply:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/floor_is_lava_s3.ply
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/parking_garage.h5:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/parking_garage.h5
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/parking_garage.ply:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/parking_garage.ply
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/parking_garage_s4.h5:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/parking_garage_s4.h5
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/parking_garage_s4.ply:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/parking_garage_s4.ply
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/tray.h5:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/tray.h5
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/tray.ply:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/tray.ply
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/tray_s4.h5:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/tray_s4.h5
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/maps/tray_s4.ply:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials/maps/tray_s4.ply
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | mesh_navigation_tutorials
5 | 0.0.1
6 | Tutorials for mobile robot navigation in 3D, using mesh maps.
7 |
8 | Matthias Holoch
9 | Alexander Mock
10 |
11 | BSD-3-Clause
12 |
13 | ament_cmake
14 |
15 | cvp_mesh_planner
16 | mbf_mesh_nav
17 | mesh_controller
18 | mesh_layers
19 | mesh_map
20 | mesh_navigation_tutorials_sim
21 | robot_localization
22 | rviz_mbf_plugins
23 | rviz_mesh_tools_plugins
24 | tf2_ros
25 |
26 | ament_lint_auto
27 | ament_cmake_copyright
28 | ament_cmake_cppcheck
29 | ament_cmake_pep257
30 | ament_cmake_uncrustify
31 |
32 |
33 | ament_cmake
34 |
35 |
36 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials/rviz/default.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz_common/Displays
3 | Help Height: 108
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Move Base Flex1
8 | - /Move Base Flex1/Mesh Map1/Display Type1/Vertex Colors Topic1
9 | - /Move Base Flex1/Planner Debug Marker1/Namespaces1
10 | Splitter Ratio: 0.7377892136573792
11 | Tree Height: 671
12 | - Class: rviz_common/Selection
13 | Name: Selection
14 | - Class: rviz_common/Tool Properties
15 | Expanded:
16 | - /Mesh Goal1
17 | Name: Tool Properties
18 | Splitter Ratio: 0.6294963955879211
19 | - Class: rviz_common/Views
20 | Expanded:
21 | - /Current View1
22 | Name: Views
23 | Splitter Ratio: 0.5
24 | - Class: rviz_common/Time
25 | Experimental: false
26 | Name: Time
27 | SyncMode: 0
28 | SyncSource: PointCloud2
29 | - Class: rviz_mbf_plugins/MbfGoalActions
30 | Name: MbfGoalActions
31 | exe_path_action_server_path: /move_base_flex/exe_path
32 | get_path_action_server_path: /move_base_flex/get_path
33 | goal_input_topic: /rviz/goal_pose
34 | Visualization Manager:
35 | Class: ""
36 | Displays:
37 | - Class: rviz_default_plugins/TF
38 | Enabled: false
39 | Frame Timeout: 15
40 | Frames:
41 | All Enabled: true
42 | Marker Scale: 1
43 | Name: TF
44 | Show Arrows: true
45 | Show Axes: true
46 | Show Names: true
47 | Tree:
48 | {}
49 | Update Interval: 0
50 | Value: false
51 | - Alpha: 0.5
52 | Cell Size: 1
53 | Class: rviz_default_plugins/Grid
54 | Color: 160; 160; 164
55 | Enabled: false
56 | Line Style:
57 | Line Width: 0.029999999329447746
58 | Value: Lines
59 | Name: Grid
60 | Normal Cell Count: 0
61 | Offset:
62 | X: 0
63 | Y: 0
64 | Z: 0
65 | Plane: XY
66 | Plane Cell Count: 10
67 | Reference Frame:
68 | Value: false
69 | - Class: rviz_common/Group
70 | Displays:
71 | - Alpha: 1
72 | Axes Length: 1
73 | Axes Radius: 0.10000000149011612
74 | Class: rviz_default_plugins/Pose
75 | Color: 255; 25; 0
76 | Enabled: true
77 | Head Length: 0.30000001192092896
78 | Head Radius: 0.10000000149011612
79 | Name: Goal Pose
80 | Shaft Length: 1
81 | Shaft Radius: 0.05000000074505806
82 | Shape: Arrow
83 | Topic:
84 | Depth: 5
85 | Durability Policy: Volatile
86 | Filter size: 10
87 | History Policy: Keep Last
88 | Reliability Policy: Reliable
89 | Value: /move_base_flex/current_goal
90 | Value: true
91 | - Alpha: 1
92 | Buffer Length: 1
93 | Class: rviz_default_plugins/Path
94 | Color: 255; 0; 0
95 | Enabled: true
96 | Head Diameter: 0.30000001192092896
97 | Head Length: 0.20000000298023224
98 | Length: 0.30000001192092896
99 | Line Style: Billboards
100 | Line Width: 0.029999999329447746
101 | Name: Latest Path
102 | Offset:
103 | X: 0
104 | Y: 0
105 | Z: 0
106 | Pose Color: 255; 85; 255
107 | Pose Style: None
108 | Radius: 0.029999999329447746
109 | Shaft Diameter: 0.10000000149011612
110 | Shaft Length: 0.10000000149011612
111 | Topic:
112 | Depth: 5
113 | Durability Policy: Volatile
114 | Filter size: 10
115 | History Policy: Keep Last
116 | Reliability Policy: Reliable
117 | Value: /move_base_flex/path
118 | Value: true
119 | - Buffer Size: 1
120 | Class: rviz_mesh_tools_plugins/Mesh
121 | Display Type:
122 | Color Scale: Red Green
123 | Faces Alpha: 0.30000001192092896
124 | Faces Color: 255; 255; 255
125 | Material Service Name: get_materials
126 | Show textured faces only: false
127 | Texture Service Name: get_texture
128 | Use Custom limits:
129 | Value: false
130 | Vertex Costs Lower Limit: 0
131 | Vertex Costs Upper Limit: 1
132 | Value: Vertex Costs
133 | Vertex Color Service Name: get_vertex_colors
134 | Vertex Colors Topic:
135 | Depth: 1
136 | Durability Policy: Transient Local
137 | History Policy: Keep Last
138 | Reliability Policy: Reliable
139 | Value: /move_base_flex/vertex_colors
140 | Vertex Costs Topic:
141 | Depth: 1
142 | Durability Policy: System Default
143 | History Policy: Keep All
144 | Reliability Policy: System Default
145 | Value: /move_base_flex/vertex_costs
146 | Vertex Costs Type: Combined Costs
147 | Enabled: true
148 | Geometry Topic:
149 | Depth: 1
150 | Durability Policy: Transient Local
151 | History Policy: Keep Last
152 | Reliability Policy: Reliable
153 | Value: /move_base_flex/mesh
154 | Name: Mesh Map
155 | Show Normals:
156 | Normals Alpha: 1
157 | Normals Color: 255; 0; 255
158 | Normals Scaling Factor: 1
159 | Value: false
160 | Show Wireframe:
161 | Value: true
162 | Wireframe Alpha: 1
163 | Wireframe Color: 0; 0; 0
164 | Value: true
165 | - Class: rviz_default_plugins/Marker
166 | Enabled: true
167 | Name: Planner Vectorfield
168 | Namespaces:
169 | {}
170 | Topic:
171 | Depth: 5
172 | Durability Policy: Volatile
173 | Filter size: 10
174 | History Policy: Keep Last
175 | Reliability Policy: Reliable
176 | Value: /move_base_flex/vector_field
177 | Value: true
178 | - Class: rviz_default_plugins/Marker
179 | Enabled: false
180 | Name: Planner Debug Marker
181 | Namespaces:
182 | {}
183 | Topic:
184 | Depth: 5
185 | Durability Policy: Volatile
186 | Filter size: 10
187 | History Policy: Keep All
188 | Reliability Policy: Reliable
189 | Value: /move_base_flex/marker
190 | Value: false
191 | Enabled: true
192 | Name: Move Base Flex
193 | - Alpha: 1
194 | Class: rviz_default_plugins/RobotModel
195 | Collision Enabled: false
196 | Description File: ""
197 | Description Source: Topic
198 | Description Topic:
199 | Depth: 5
200 | Durability Policy: Volatile
201 | History Policy: Keep Last
202 | Reliability Policy: Reliable
203 | Value: /robot_description
204 | Enabled: true
205 | Links:
206 | All Links Enabled: true
207 | Expand Joint Details: false
208 | Expand Link Details: false
209 | Expand Tree: false
210 | Link Tree Style: Links in Alphabetic Order
211 | base_footprint:
212 | Alpha: 1
213 | Show Axes: false
214 | Show Trail: false
215 | base_link:
216 | Alpha: 1
217 | Show Axes: false
218 | Show Trail: false
219 | Value: true
220 | imu:
221 | Alpha: 1
222 | Show Axes: false
223 | Show Trail: false
224 | Value: true
225 | laser2d:
226 | Alpha: 1
227 | Show Axes: false
228 | Show Trail: false
229 | Value: true
230 | laser3d:
231 | Alpha: 1
232 | Show Axes: false
233 | Show Trail: false
234 | Value: true
235 | left_front_wheel_link:
236 | Alpha: 1
237 | Show Axes: false
238 | Show Trail: false
239 | Value: true
240 | left_rear_wheel_link:
241 | Alpha: 1
242 | Show Axes: false
243 | Show Trail: false
244 | Value: true
245 | right_front_wheel_link:
246 | Alpha: 1
247 | Show Axes: false
248 | Show Trail: false
249 | Value: true
250 | right_rear_wheel_link:
251 | Alpha: 1
252 | Show Axes: false
253 | Show Trail: false
254 | Value: true
255 | Mass Properties:
256 | Inertia: false
257 | Mass: false
258 | Name: RobotModel
259 | TF Prefix: ""
260 | Update Interval: 0
261 | Value: true
262 | Visual Enabled: true
263 | - Alpha: 1
264 | Autocompute Intensity Bounds: true
265 | Autocompute Value Bounds:
266 | Max Value: 1.0365432500839233
267 | Min Value: -0.8400940895080566
268 | Value: true
269 | Axis: Z
270 | Channel Name: intensity
271 | Class: rviz_default_plugins/PointCloud2
272 | Color: 255; 255; 255
273 | Color Transformer: AxisColor
274 | Decay Time: 0
275 | Enabled: true
276 | Invert Rainbow: false
277 | Max Color: 255; 255; 255
278 | Max Intensity: 0
279 | Min Color: 0; 0; 0
280 | Min Intensity: 0
281 | Name: PointCloud2
282 | Position Transformer: XYZ
283 | Selectable: true
284 | Size (Pixels): 3
285 | Size (m): 0.009999999776482582
286 | Style: Points
287 | Topic:
288 | Depth: 5
289 | Durability Policy: Volatile
290 | Filter size: 10
291 | History Policy: Keep Last
292 | Reliability Policy: Reliable
293 | Value: /cloud
294 | Use Fixed Frame: true
295 | Use rainbow: true
296 | Value: true
297 | Enabled: true
298 | Global Options:
299 | Background Color: 48; 48; 48
300 | Fixed Frame: map
301 | Frame Rate: 30
302 | Name: root
303 | Tools:
304 | - Class: rviz_default_plugins/Interact
305 | Hide Inactive Objects: true
306 | - Class: rviz_default_plugins/MoveCamera
307 | - Class: rviz_default_plugins/FocusCamera
308 | - Class: rviz_default_plugins/Measure
309 | Line color: 128; 128; 0
310 | - Class: rviz_mesh_tools_plugins/MeshGoal
311 | Switch Bottom/Top: false
312 | Topic: /rviz/goal_pose
313 | - Class: rviz_mesh_tools_plugins/MeshPoseGuess
314 | Covariance orientation x: 0.010000000707805157
315 | Covariance orientation y: 0.010000000707805157
316 | Covariance orientation z: 0.06853891909122467
317 | Covariance position x: 0.25
318 | Covariance position y: 0.25
319 | Covariance position z: 0.010000000707805157
320 | Switch Bottom/Top: false
321 | Topic:
322 | Depth: 5
323 | Durability Policy: Volatile
324 | History Policy: Keep Last
325 | Reliability Policy: Reliable
326 | Value: initialpose
327 | - Class: rviz_mesh_tools_plugins/ClusterLabel
328 | Transformation:
329 | Current:
330 | Class: rviz_default_plugins/TF
331 | Value: true
332 | Views:
333 | Current:
334 | Class: rviz_default_plugins/Orbit
335 | Distance: 17.99980926513672
336 | Enable Stereo Rendering:
337 | Stereo Eye Separation: 0.05999999865889549
338 | Stereo Focal Distance: 1
339 | Swap Stereo Eyes: false
340 | Value: false
341 | Focal Point:
342 | X: 6.068273544311523
343 | Y: -0.9949296712875366
344 | Z: 0.17818385362625122
345 | Focal Shape Fixed Size: false
346 | Focal Shape Size: 0.05000000074505806
347 | Invert Z Axis: false
348 | Name: Current View
349 | Near Clip Distance: 0.009999999776482582
350 | Pitch: 0.6403999924659729
351 | Target Frame:
352 | Value: Orbit (rviz)
353 | Yaw: 3.140411138534546
354 | Saved: ~
355 | Window Geometry:
356 | Displays:
357 | collapsed: false
358 | Height: 1011
359 | Hide Left Dock: false
360 | Hide Right Dock: false
361 | MbfGoalActions:
362 | collapsed: false
363 | QMainWindow State: 000000ff00000000fd0000000400000000000001560000034bfc0200000007fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003f0000034b000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000011b0000034bfc0200000005fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730000000054000000870000005d00fffffffb0000000a00560069006500770073010000003f000001a1000000a900fffffffb0000001c004d006200660047006f0061006c0041006300740069006f006e007301000001e6000001a40000017600fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007301000003a9000001510000000000000000fb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000078000000044fc0100000002fb0000000800540069006d00650100000000000007800000027b00fffffffb0000000800540069006d00650100000000000004500000000000000000000005030000034b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
364 | Selection:
365 | collapsed: false
366 | Time:
367 | collapsed: false
368 | Tool Properties:
369 | collapsed: false
370 | Views:
371 | collapsed: false
372 | Width: 1920
373 | X: 0
374 | Y: 32
375 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.8)
2 | project(mesh_navigation_tutorials_sim)
3 |
4 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
5 | add_compile_options(-Wall -Wextra -Wpedantic -Werror)
6 | endif()
7 |
8 | if (NOT EXISTS ${CMAKE_BINARY_DIR}/CMakeCache.txt)
9 | if (NOT CMAKE_BUILD_TYPE)
10 | set(CMAKE_BUILD_TYPE "Release" CACHE STRING "" FORCE)
11 | endif()
12 | endif()
13 |
14 |
15 | # find dependencies
16 | find_package(ament_cmake REQUIRED)
17 | find_package(rclcpp REQUIRED)
18 | find_package(rclcpp_components REQUIRED)
19 | find_package(geometry_msgs REQUIRED)
20 | find_package(tf2_ros REQUIRED)
21 | find_package(tf2_eigen REQUIRED)
22 | find_package(tf2_geometry_msgs REQUIRED)
23 | find_package(Eigen3 3.3 REQUIRED NO_MODULE)
24 |
25 |
26 | # set env var such that gazebo simulation finds this packages' resources
27 | ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in")
28 | ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.sh.in")
29 |
30 | # install
31 | install(DIRECTORY config launch models worlds meshes urdf
32 | DESTINATION share/${PROJECT_NAME}
33 | )
34 |
35 |
36 |
37 | # Ground Truth Localization Node
38 | add_library(ground_truth_localization SHARED
39 | src/ground_truth_localization.cpp)
40 |
41 | target_include_directories(ground_truth_localization
42 | PRIVATE
43 | $
44 | $)
45 |
46 | target_link_libraries(ground_truth_localization
47 | Eigen3::Eigen
48 | )
49 |
50 | ament_target_dependencies(ground_truth_localization
51 | rclcpp
52 | rclcpp_components
53 | geometry_msgs
54 | tf2_ros
55 | tf2_eigen
56 | tf2_geometry_msgs
57 | )
58 |
59 | rclcpp_components_register_node(ground_truth_localization PLUGIN "mesh_navigation_tutorials_sim::GroundTruthLocalizationNode" EXECUTABLE ground_truth_localization_node)
60 |
61 | install(TARGETS ground_truth_localization
62 | ARCHIVE DESTINATION lib
63 | LIBRARY DESTINATION lib
64 | RUNTIME DESTINATION bin
65 | )
66 |
67 |
68 |
69 | # test
70 | if(BUILD_TESTING)
71 | find_package(ament_lint_auto REQUIRED)
72 | ament_lint_auto_find_test_dependencies()
73 | endif()
74 |
75 | ament_package()
76 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/config/ros_gazebo_bridge.yaml:
--------------------------------------------------------------------------------
1 | - topic_name: "/clock"
2 | ros_type_name: "rosgraph_msgs/msg/Clock"
3 | gz_type_name: "ignition.msgs.Clock"
4 | direction: GZ_TO_ROS
5 |
6 | - ros_topic_name: "/odom"
7 | gz_topic_name: "model/robot/odometry"
8 | ros_type_name: "nav_msgs/msg/Odometry"
9 | gz_type_name: "ignition.msgs.Odometry"
10 | direction: GZ_TO_ROS
11 |
12 | - ros_topic_name: "/imu/data"
13 | ros_type_name: "sensor_msgs/msg/Imu"
14 | gz_topic_name: "/model/robot/imu"
15 | gz_type_name: "ignition.msgs.IMU"
16 | direction: GZ_TO_ROS
17 |
18 | - ros_topic_name: "/scan"
19 | ros_type_name: "sensor_msgs/msg/LaserScan"
20 | gz_topic_name: "/model/robot/scan"
21 | gz_type_name: "ignition.msgs.LaserScan"
22 | direction: GZ_TO_ROS
23 |
24 | - ros_topic_name: "/cloud"
25 | ros_type_name: "sensor_msgs/msg/PointCloud2"
26 | gz_topic_name: "/model/robot/cloud/points"
27 | gz_type_name: "ignition.msgs.PointCloudPacked"
28 | direction: GZ_TO_ROS
29 |
30 | - ros_topic_name: "/joint_states"
31 | ros_type_name: "sensor_msgs/msg/JointState"
32 | gz_topic_name: "/model/robot/joint_states"
33 | gz_type_name: "ignition.msgs.Model"
34 | direction: GZ_TO_ROS
35 |
36 | # Teleop nodes need 'Twist'
37 | # - ros_topic_name: "/cmd_vel"
38 | # ros_type_name: "geometry_msgs/msg/Twist"
39 | # gz_topic_name: "/model/robot/cmd_vel"
40 | # gz_type_name: "ignition.msgs.Twist"
41 | # direction: ROS_TO_GZ
42 |
43 | # Mesh Nav publishes 'TwistStamped'
44 | - ros_topic_name: "/cmd_vel"
45 | ros_type_name: "geometry_msgs/msg/TwistStamped"
46 | gz_topic_name: "/model/robot/cmd_vel"
47 | gz_type_name: "ignition.msgs.Twist"
48 | direction: ROS_TO_GZ
49 |
50 | # GT Poses
51 | - ros_topic_name: "/tf_gt"
52 | gz_topic_name: "model/robot/pose_static"
53 | ros_type_name: "tf2_msgs/msg/TFMessage"
54 | gz_type_name: "gz.msgs.Pose_V"
55 | direction: GZ_TO_ROS
56 |
57 | # DiffDrive Odom TF
58 | - ros_topic_name: "/tf_odom"
59 | gz_topic_name: "model/robot/tf_odom"
60 | ros_type_name: "tf2_msgs/msg/TFMessage"
61 | gz_type_name: "gz.msgs.Pose_V"
62 | direction: GZ_TO_ROS
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/hooks/mesh_navigation_tutorials_sim.dsv.in:
--------------------------------------------------------------------------------
1 | prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;share/@PROJECT_NAME@/models
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/hooks/mesh_navigation_tutorials_sim.sh.in:
--------------------------------------------------------------------------------
1 | ament_prepend_unique_value GZ_SIM_RESOURCE_PATH "$AMENT_CURRENT_PREFIX/share/@PROJECT_NAME@/models"
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/launch/ground_truth_localization_launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/launch/simulation_launch.py:
--------------------------------------------------------------------------------
1 | # Copyright 2024 Nature Robots GmbH
2 | #
3 | # Redistribution and use in source and binary forms, with or without
4 | # modification, are permitted provided that the following conditions are met:
5 | #
6 | # * Redistributions of source code must retain the above copyright
7 | # notice, this list of conditions and the following disclaimer.
8 | #
9 | # * Redistributions in binary form must reproduce the above copyright
10 | # notice, this list of conditions and the following disclaimer in the
11 | # documentation and/or other materials provided with the distribution.
12 | #
13 | # * Neither the name of the Nature Robots GmbH nor the names of its
14 | # contributors may be used to endorse or promote products derived from
15 | # this software without specific prior written permission.
16 | #
17 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 | # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 | # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 | # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 | # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 | # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 | # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 | # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 | # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 | # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 | # POSSIBILITY OF SUCH DAMAGE.
28 |
29 |
30 | import os
31 |
32 | from ament_index_python.packages import get_package_share_directory
33 |
34 | from launch import LaunchDescription
35 | from launch_ros.actions import Node
36 | from launch.actions import IncludeLaunchDescription, DeclareLaunchArgument
37 | from launch.launch_description_sources import PythonLaunchDescriptionSource
38 | from launch.substitutions import Command, FindExecutable
39 | from launch.substitutions import LaunchConfiguration, PythonExpression, PathJoinSubstitution
40 |
41 |
42 | def generate_launch_description():
43 | # path to this pkg
44 | pkg_mesh_navigation_tutorials_sim = get_package_share_directory(
45 | "mesh_navigation_tutorials_sim"
46 | )
47 |
48 | # Launch arguments
49 | available_world_names = [
50 | f[:-4]
51 | for f in os.listdir(os.path.join(pkg_mesh_navigation_tutorials_sim, "worlds"))
52 | if f.endswith(".sdf")
53 | ]
54 |
55 | # Launch arguments
56 | launch_args = [
57 | DeclareLaunchArgument(
58 | "world_name",
59 | description="Name of the world to simulate"
60 | + '(see mesh_navigation_tutorials\' "worlds" directory).',
61 | default_value=available_world_names[0],
62 | choices=available_world_names,
63 | ),
64 | DeclareLaunchArgument(
65 | "start_gazebo_gui",
66 | description="Start Gazebo GUI",
67 | default_value="True",
68 | choices=["True", "False"],
69 | ),
70 | ]
71 | world_name = LaunchConfiguration("world_name")
72 | world_path = PathJoinSubstitution(
73 | [
74 | pkg_mesh_navigation_tutorials_sim,
75 | "worlds",
76 | PythonExpression(['"', world_name, '" + ".sdf"']),
77 | ]
78 | )
79 | start_gazebo_gui = LaunchConfiguration("start_gazebo_gui")
80 |
81 | robot_description = Command(
82 | [
83 | PathJoinSubstitution([FindExecutable(name="xacro")]),
84 | " ",
85 | PathJoinSubstitution([pkg_mesh_navigation_tutorials_sim, "urdf/ceres.urdf.xacro"]),
86 | " name:=robot",
87 | " prefix:='robot'",
88 | " is_sim:=true",
89 | ]
90 | )
91 |
92 | robot_state_publisher = Node(
93 | package="robot_state_publisher",
94 | executable="robot_state_publisher",
95 | output="screen",
96 | parameters=[
97 | {
98 | "use_sim_time": True,
99 | "publish_frequency": 100.0,
100 | "robot_description": robot_description,
101 | }
102 | ],
103 | )
104 |
105 | gz_sim = IncludeLaunchDescription(
106 | PythonLaunchDescriptionSource(
107 | PathJoinSubstitution(
108 | [get_package_share_directory("ros_gz_sim"), "launch", "gz_sim.launch.py"]
109 | )
110 | ),
111 | launch_arguments={
112 | "gz_args": [
113 | "-r ",
114 | world_path, # which world to load
115 | PythonExpression(
116 | ['"" if ', start_gazebo_gui, ' else " -s"']
117 | ), # whether to start gui
118 | ]
119 | }.items(),
120 | )
121 |
122 | spawn_robot = Node(
123 | package="ros_gz_sim",
124 | executable="create",
125 | name="spawn_robot",
126 | output="screen",
127 | arguments=[
128 | "-topic",
129 | "robot_description",
130 | "-name",
131 | # The robot's name in simulation is always "robot", regardless of which model is chosen
132 | # This facilitates easier topic bridging.
133 | "robot",
134 | "-z",
135 | "1",
136 | ],
137 | parameters=[
138 | {"use_sim_time": True},
139 | ],
140 | )
141 |
142 | # Bridge between ROS and Gazebo
143 | bridge = Node(
144 | package="ros_gz_bridge",
145 | executable="parameter_bridge",
146 | parameters=[
147 | {
148 | "config_file": PathJoinSubstitution(
149 | [pkg_mesh_navigation_tutorials_sim, "config", "ros_gazebo_bridge.yaml"]
150 | ),
151 | }
152 | ],
153 | output="screen",
154 | )
155 |
156 | return LaunchDescription(launch_args + [gz_sim, spawn_robot, bridge, robot_state_publisher])
157 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/meshes/wheel.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials_sim/meshes/wheel.stl
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/floor_is_lava/meshes/floor_is_lava.dae:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | Blender User
6 | Blender 3.0.1
7 |
8 | 2024-06-21T15:25:26
9 | 2024-06-21T15:25:26
10 |
11 | Z_UP
12 |
13 |
14 |
15 |
16 |
17 |
18 | 39.59775
19 | 1.777778
20 | 0.1
21 | 100
22 |
23 |
24 |
25 |
26 |
27 | 0
28 | 0
29 | 10
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 | 1000 1000 1000
39 | 1
40 | 0
41 | 0.00111109
42 |
43 |
44 |
45 |
46 | 0
47 | 0
48 | 1
49 | 1
50 | 1
51 | 1
52 | 1
53 | 0
54 | 0
55 | 0
56 | 1000
57 | 29.99998
58 | 75
59 | 0.15
60 | 0
61 | 1
62 | 2
63 | 0.04999995
64 | 30.002
65 | 1
66 | 3
67 | 2880
68 | 3
69 | 1
70 | 1
71 | 0.1
72 | 0.1
73 | 1
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 | 0 0 0 1
85 |
86 |
87 | 0.8 0.8 0.8 1
88 |
89 |
90 | 1.45
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 | 7.5 1 1 7.5 -8 1 -1.5 1 1 -1.5 -8 1 -1.5 -1.047931 -1 7.5 -1.047931 1 -1.5 -1.047931 1 7.5 -6.329365 1 -1.5 -6.329365 1 7.5 -6.329365 -1 5.90547 -8 1 5.90547 1 1 5.90547 -1.047931 -1 5.90547 -6.329365 -1 -1.5 -3.082396 1 -1.5 -3.082396 -1 7.5 -3.082396 1 5.90547 -3.082396 -1 7.5 -4.70588 1 5.90547 -4.70588 -1 -1.5 -4.70588 1 7.5 -4.70588 -1 7.5 1 -0.1104816 -1.5 -8 -0.1104816 7.5 -8 -0.1104816 -1.5 1 -0.1104816 7.5 -1.047931 -0.1104816 -1.5 -1.047931 -0.1104816 -1.5 -6.329365 -0.1104816 7.5 -6.329365 -0.1104816 5.90547 1 -0.1200016 5.90547 -8 -0.1104816 7.5 -3.082396 0.2800185 -1.5 -3.082396 0.2800183 -1.5 -4.70588 0.2800183 7.5 -4.70588 0.2800185 0.1015911 -8 1 0.1015911 -1.047931 -1 0.1015911 -6.329365 -1 0.1015911 1 1 0.1015911 -3.082396 -1 0.1015911 -4.70588 -1 0.1015911 1 -0.1200016 0.1015911 -8 -0.1104816 5.90547 -1.047931 -0.12 0.1204681 -1.047931 -0.12 5.90547 -3.082396 0.28 0.1015911 -3.082396 0.28 5.90547 -4.70588 0.28 0.1015911 -4.70588 0.28 5.90547 -6.329365 -0.12 0.1015911 -6.329365 -0.12
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 | -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 1 0 7.8583e-7 1 -0.005970299 0 0.9999822 0 -1 0 -1 4.58919e-7 0 0 7.8583e-7 1 1 0 0 -0.005969285 7.84861e-7 0.9999822 0.005943953 5.55751e-5 0.9999824 0.005873739 0 0.9999828 0 -1 0 -0.005862236 0.1884981 0.9820561 -1.13941e-5 0.1929186 0.9812148 -1.15816e-5 0 1 -1.16046e-5 0 1 1.48861e-7 1 0 1.14847e-5 0 1 1.14617e-5 0 1 1.11439e-5 -0.2338618 0.9722699 0.005770385 -0.2392254 0.970947 0.00594294 0 0.9999824 0 0.005697369 0.9999838 0 0.005697369 0.9999839 0 0.005697369 0.9999839 -0.005969285 0 0.9999822 0 0.005697369 0.9999839
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 | 0.4861898 0.556887 0.625 0.5 0.4861898 0.5 0.4861898 1 0.625 0.9555113 0.4861898 0.9555113 0.4861898 0.25 0.625 0.193113 0.4861898 0.193113 0.4861898 0.75 0.625 0.7035935 0.4861898 0.7035935 0.4861898 0.5 0.625 0.4557075 0.4861898 0.4557075 0.4861898 0.1366001 0.625 0.193113 0.625 0.1366001 0.4861898 0.0464065 0.625 0 0.4861898 0 0.4861898 0.6584967 0.625 0.7035935 0.625 0.6584967 0.3307075 0.7035935 0.375 0.6584967 0.3307075 0.6584967 0.1694886 0.7035935 0.3307075 0.6584967 0.1694886 0.6584967 0.4861898 0.4557075 0.625 0.2944886 0.4861898 0.2944886 0.4861898 0.7942925 0.625 0.75 0.4861898 0.75 0.1694886 0.6133999 0.3307075 0.556887 0.1694886 0.556887 0.4861898 0.6133999 0.625 0.556887 0.4861898 0.556887 0.4861898 0.1366001 0.625 0.09150332 0.4861898 0.09150332 0.4861898 0.09150332 0.625 0.0464065 0.4861898 0.0464065 0.4861898 0.6584967 0.625 0.6133999 0.4861898 0.6133999 0.4861898 0.4557075 0.4861898 0.2944886 0.3307075 0.556887 0.4861898 0.5 0.4861898 0.4557075 0.4861898 0.556887 0.4861898 0.193113 0.1694886 0.556887 0.170013 0.556887 0.375 0.6584967 0.4861898 0.7035935 0.4861898 0.6584967 0.170013 0.556887 0.3307075 0.556887 0.4861898 0.2944886 0.375 0.1366001 0.4861898 0.193113 0.4861898 0.1366001 0.375 0.193113 0.1694886 0.556887 0.4861898 0.193113 0.3307075 0.556887 0.4861898 0.556887 0.4861898 0.4557075 0.4861898 0.2944886 0.4861898 0.25 0.170013 0.556887 0.170013 0.556887 0.4861898 0.25 0.4861898 0.193113 0.3307075 0.556887 0.3307075 0.6133999 0.3307075 0.6133999 0.125 0.6133999 0.1694886 0.556887 0.125 0.556887 0.4861898 0.25 0.625 0.2944886 0.625 0.25 0.3307075 0.6133999 0.3307075 0.556887 0.3307075 0.556887 0.4861898 0.9555113 0.625 0.7942925 0.4861898 0.7942925 0.3307075 0.556887 0.170013 0.556887 0.1694886 0.556887 0.1694886 0.6133999 0.3307075 0.6133999 0.1694886 0.6133999 0.3307075 0.6584967 0.1694886 0.6584967 0.3307075 0.6584967 0.1694886 0.7035935 0.3307075 0.7035935 0.1694886 0.7035935 0.4861898 0.556887 0.3307075 0.556887 0.4861898 0.6133999 0.3307075 0.6133999 0.4861898 0.6133999 0.3307075 0.556887 0.3307075 0.6584967 0.375 0.6584967 0.3307075 0.6584967 0.375 0.6584967 0.4861898 0.6584967 0.3307075 0.6584967 0.4861898 0.6133999 0.3307075 0.6133999 0.4861898 0.6584967 0.3307075 0.6584967 0.4861898 0.6584967 0.3307075 0.6133999 0.3307075 0.6133999 0.1694886 0.6133999 0.3307075 0.6584967 0.3307075 0.6584967 0.1694886 0.6133999 0.1694886 0.6584967 0.1694886 0.6133999 0.125 0.6133999 0.1694886 0.6133999 0.125 0.6133999 0.4861898 0.1366001 0.1694886 0.6133999 0.4861898 0.1366001 0.4861898 0.09150332 0.1694886 0.6133999 0.1694886 0.6133999 0.4861898 0.09150332 0.1694886 0.6584967 0.1694886 0.7035935 0.1694886 0.6584967 0.1694886 0.7035935 0.1694886 0.6584967 0.1694886 0.7035935 0.1694886 0.6584967 0.4861898 0.09150332 0.4861898 0.0464065 0.1694886 0.6584967 0.1694886 0.6584967 0.4861898 0.0464065 0.1694886 0.7035935 0.4861898 0.0464065 0.4861898 0 0.1694886 0.7035935 0.4861898 0 0.4861898 0.9555113 0.1694886 0.7035935 0.4861898 0.9555113 0.4861898 0.7942925 0.1694886 0.7035935 0.1694886 0.7035935 0.4861898 0.7942925 0.3307075 0.7035935 0.375 0.7035935 0.3307075 0.7035935 0.4861898 0.7035935 0.3307075 0.7035935 0.3307075 0.7035935 0.4861898 0.7035935 0.4861898 0.7035935 0.3307075 0.7035935 0.4861898 0.75 0.4861898 0.7942925 0.4861898 0.75 0.3307075 0.7035935 0.4861898 0.556887 0.625 0.556887 0.625 0.5 0.4861898 1 0.625 1 0.625 0.9555113 0.4861898 0.25 0.625 0.25 0.625 0.193113 0.4861898 0.75 0.625 0.75 0.625 0.7035935 0.4861898 0.5 0.625 0.5 0.625 0.4557075 0.4861898 0.1366001 0.4861898 0.193113 0.625 0.193113 0.4861898 0.0464065 0.625 0.0464065 0.625 0 0.4861898 0.6584967 0.4861898 0.7035935 0.625 0.7035935 0.3307075 0.7035935 0.375 0.7035935 0.375 0.6584967 0.1694886 0.7035935 0.3307075 0.7035935 0.3307075 0.6584967 0.4861898 0.4557075 0.625 0.4557075 0.625 0.2944886 0.4861898 0.7942925 0.625 0.7942925 0.625 0.75 0.1694886 0.6133999 0.3307075 0.6133999 0.3307075 0.556887 0.4861898 0.6133999 0.625 0.6133999 0.625 0.556887 0.4861898 0.1366001 0.625 0.1366001 0.625 0.09150332 0.4861898 0.09150332 0.625 0.09150332 0.625 0.0464065 0.4861898 0.6584967 0.625 0.6584967 0.625 0.6133999 0.375 0.6584967 0.375 0.7035935 0.4861898 0.7035935 0.375 0.1366001 0.375 0.193113 0.4861898 0.193113 0.125 0.6133999 0.1694886 0.6133999 0.1694886 0.556887 0.4861898 0.25 0.4861898 0.2944886 0.625 0.2944886 0.4861898 0.9555113 0.625 0.9555113 0.625 0.7942925 0.3307075 0.556887 0.3307075 0.556887 0.170013 0.556887 0.1694886 0.6133999 0.3307075 0.6133999 0.3307075 0.6133999 0.3307075 0.6584967 0.1694886 0.6584967 0.1694886 0.6584967 0.1694886 0.7035935 0.3307075 0.7035935 0.3307075 0.7035935
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 | 26 0 0 0 0 1 22 0 2 23 1 3 36 1 4 43 1 5 25 2 6 6 2 7 27 2 8 24 0 9 7 0 10 29 0 11 22 3 12 11 3 13 30 3 14 33 2 15 6 2 16 14 2 17 28 2 18 3 2 19 23 2 20 35 0 21 7 0 22 18 0 23 13 4 24 21 4 25 19 4 26 38 4 27 19 4 28 41 4 29 30 3 30 39 3 31 42 3 32 31 1 33 1 1 34 24 1 35 40 4 36 12 4 37 37 4 38 32 0 39 5 0 40 26 0 41 33 2 42 20 2 43 34 2 44 34 2 45 8 2 46 28 2 47 35 0 48 16 0 49 32 0 50 30 5 51 42 5 52 44 5 53 22 6 54 30 6 55 26 6 56 27 7 57 37 7 58 45 7 59 21 8 60 29 8 61 35 8 62 45 9 63 44 9 64 42 9 65 15 10 66 27 10 67 33 10 68 4 3 69 37 3 70 27 3 71 44 11 72 26 11 73 30 11 74 42 12 75 25 12 76 45 12 77 45 13 78 25 13 79 27 13 80 44 0 81 17 0 82 46 0 83 15 4 84 37 4 85 4 4 86 25 3 87 39 3 88 2 3 89 17 0 90 44 0 91 12 0 92 43 1 93 10 1 94 31 1 95 12 14 96 45 14 97 37 14 98 47 1 99 17 1 100 40 1 101 48 3 102 41 3 103 19 3 104 51 1 105 13 1 106 38 1 107 26 15 108 44 15 109 32 15 110 46 16 111 32 16 112 44 16 113 19 3 114 21 3 115 48 3 116 21 3 117 35 3 118 48 3 119 32 17 120 46 17 121 35 17 122 48 18 123 35 18 124 46 18 125 46 4 126 47 4 127 48 4 128 48 4 129 47 4 130 49 4 131 40 1 132 15 1 133 47 1 134 15 19 135 33 19 136 47 19 137 33 20 138 34 20 139 47 20 140 47 21 141 34 21 142 49 21 143 38 2 144 41 2 145 51 2 146 49 2 147 51 2 148 41 2 149 34 22 150 28 22 151 49 22 152 49 23 153 28 23 154 51 23 155 28 24 156 23 24 157 51 24 158 23 25 159 43 25 160 51 25 161 43 26 162 31 26 163 51 26 164 51 27 165 31 27 166 50 27 167 9 1 168 13 1 169 29 1 170 13 1 171 50 1 172 29 1 173 29 28 174 50 28 175 24 28 176 31 29 177 24 29 178 50 29 179 26 0 180 5 0 181 0 0 182 23 1 183 3 1 184 36 1 185 25 2 186 2 2 187 6 2 188 24 0 189 1 0 190 7 0 191 22 3 192 0 3 193 11 3 194 33 2 195 27 2 196 6 2 197 28 2 198 8 2 199 3 2 200 35 0 201 29 0 202 7 0 203 13 4 204 9 4 205 21 4 206 38 4 207 13 4 208 19 4 209 30 3 210 11 3 211 39 3 212 31 1 213 10 1 214 1 1 215 40 4 216 17 4 217 12 4 218 32 0 219 16 0 220 5 0 221 33 2 222 14 2 223 20 2 224 34 2 225 20 2 226 8 2 227 35 0 228 18 0 229 16 0 230 21 0 231 9 0 232 29 0 233 15 2 234 4 2 235 27 2 236 15 4 237 40 4 238 37 4 239 25 3 240 42 3 241 39 3 242 43 1 243 36 1 244 10 1 245 12 3 246 44 3 247 45 3 248 47 1 249 46 1 250 17 1 251 48 3 252 49 3 253 41 3 254 51 1 255 50 1 256 13 1 257
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 | 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1
151 |
152 |
153 |
154 | -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1
155 |
156 |
157 |
158 | 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1
159 |
160 |
161 |
162 |
163 |
164 |
165 |
166 |
167 |
168 |
169 |
170 |
171 |
172 |
173 |
174 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/floor_is_lava/meshes/floor_is_lava.ply:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials_sim/models/floor_is_lava/meshes/floor_is_lava.ply
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/floor_is_lava/model.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | Floor is Lava
5 | 1.0
6 | model.sdf
7 |
8 |
9 | Alexander Mock
10 | amock@uos.de
11 |
12 |
13 |
14 | floor is lava
15 |
16 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/floor_is_lava/model.sdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | true
5 |
6 |
7 |
8 |
9 | 1 1 1
10 | meshes/floor_is_lava.dae
11 |
12 |
13 |
14 |
15 |
16 |
17 | 1 1 1
18 | meshes/floor_is_lava.dae
19 |
20 |
21 |
22 |
23 |
24 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/parking_garage/meshes/parking_garage.dae:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | Blender User
6 | Blender 4.2.3 LTS commit date:2024-10-14, commit time:15:20, hash:0e22e4fcea03
7 |
8 | 2024-10-21T17:19:12
9 | 2024-10-21T17:19:12
10 |
11 | Z_UP
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 | 0 0 0 1
20 |
21 |
22 | 0.8 0.8 0.8 1
23 |
24 |
25 | 1.5
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 | 20 -15 2 23 -15 2 20 -25 2 23 -25 2 53 -15 2 53 -25 2 17 -15 2 17 -25 2 20 -5 0 17 -5 0 20 5 0 17 5 0 23 -5 0 23 5 0 53 -5 0 53 5 0 -13 -5 0 -13 5 0 -13 -15 2 -13 -25 2 56 -5 0 56 5 0 59 -5 0 59 5 0 56 -15 2 56 -25 2 59 -15 2 59 -25 2 -16 -15 2 -16 -25 2 -19 -15 2 -19 -25 2 -16 -5 0 -16 5 0 -19 -5 0 -19 5 0 23 -10 0 53 -10 0 23 -10 2 53 -10 2 17 -10 2 -13 -10 2 17 -10 0 -13 -10 0 20 -15 6 23 -15 6 20 -25 6 23 -25 6 53 -15 6 53 -25 6 17 -15 6 17 -25 6 20 -5 4 17 -5 4 20 5 4 17 5 4 23 -5 4 23 5 4 53 -5 4 53 5 4 -13 -5 4 -13 5 4 -13 -15 6 -13 -25 6 56 -5 4 56 5 4 59 -5 4 59 5 4 56 -15 6 56 -25 6 59 -15 6 59 -25 6 -16 -15 6 -16 -25 6 -19 -15 6 -19 -25 6 -16 -5 4 -16 5 4 -19 -5 4 -19 5 4 23 -10 4 53 -10 4 23 -10 6 53 -10 6 17 -10 6 -13 -10 6 17 -10 4 -13 -10 4 20 -15 10 23 -15 10 20 -25 10 23 -25 10 53 -15 10 53 -25 10 17 -15 10 17 -25 10 20 -5 8 17 -5 8 20 5 8 17 5 8 23 -5 8 23 5 8 53 -5 8 53 5 8 -13 -5 8 -13 5 8 -13 -15 10 -13 -25 10 56 -5 8 56 5 8 59 -5 8 59 5 8 56 -15 10 56 -25 10 59 -15 10 59 -25 10 -16 -15 10 -16 -25 10 -19 -15 10 -19 -25 10 -16 -5 8 -16 5 8 -19 -5 8 -19 5 8 23 -10 8 53 -10 8 23 -10 10 53 -10 10 17 -10 10 -13 -10 10 17 -10 8 -13 -10 8 20 -15 14 23 -15 14 20 -25 14 23 -25 14 53 -15 14 53 -25 14 17 -15 14 17 -25 14 20 -5 12 17 -5 12 20 5 12 17 5 12 23 -5 12 23 5 12 53 -5 12 53 5 12 -13 -5 12 -13 5 12 -13 -15 14 -13 -25 14 56 -5 12 56 5 12 59 -5 12 59 5 12 56 -15 14 56 -25 14 59 -15 14 59 -25 14 -16 -15 14 -16 -25 14 -19 -15 14 -19 -25 14 -16 -5 12 -16 5 12 -19 -5 12 -19 5 12 23 -10 12 53 -10 12 23 -10 14 53 -10 14 17 -10 14 -13 -10 14 17 -10 12 -13 -10 12 20 -15 18 23 -15 18 20 -25 18 23 -25 18 53 -15 18 53 -25 18 17 -15 18 17 -25 18 20 -5 16 17 -5 16 20 5 16 17 5 16 23 -5 16 23 5 16 53 -5 16 53 5 16 -13 -5 16 -13 5 16 -13 -15 18 -13 -25 18 56 -5 16 56 5 16 59 -5 16 59 5 16 56 -15 18 56 -25 18 59 -15 18 59 -25 18 -16 -15 18 -16 -25 18 -19 -15 18 -19 -25 18 -16 -5 16 -16 5 16 -19 -5 16 -19 5 16 23 -10 16 53 -10 16 23 -10 18 53 -10 18 17 -10 18 -13 -10 18 17 -10 16 -13 -10 16 20 5 0 17 5 0 23 5 0 53 5 0 -13 5 0 56 5 0 59 -5 0 59 5 0 -16 5 0 -19 -5 0 -19 5 0 20 5 0.5 17 5 0.5 23 5 0.5 20 5 1.5 17 5 1.5 23 5 1.5 -19 5 0.5 -16 5 0.5 -19 5 1.5 -13 5 0.5 53 5 0.5 56 5 0.5 59 5 0.5 53 5 1.5 56 5 1.5 59 5 1.5 -16 5 1.5 -13 5 1.5 -19 -15 2.5 -19 -5 0.5 -19 -15 3.5 -19 -5 1.5 -13 -25 2.5 -16 -25 2.5 -19 -25 2.5 -13 -25 3.5 -16 -25 3.5 -19 -25 3.5 20 -25 2.5 23 -25 2.5 17 -25 2.5 20 -25 3.5 23 -25 3.5 17 -25 3.5 53 -25 2.5 56 -25 2.5 59 -25 2.5 53 -25 3.5 56 -25 3.5 59 -25 3.5 59 -15 2.5 59 -5 4.5 59 -15 3.5 59 -5 5.5 56 -5 0.5 59 -5 0.5 56 -5 1.5 59 -5 1.5 53 5 4.5 56 5 4.5 59 5 4.5 53 5 5.5 56 5 5.5 59 5 5.5 20 5 4.5 17 5 4.5 23 5 4.5 20 5 5.5 17 5 5.5 23 5 5.5 20 5 8.5 17 5 8.5 23 5 8.5 20 5 9.5 17 5 9.5 23 5 9.5 20 5 12.5 17 5 12.5 23 5 12.5 20 5 13.5 17 5 13.5 23 5 13.5 20 5 16.5 17 5 16.5 23 5 16.5 20 5 17.5 17 5 17.5 23 5 17.5 -13 5 4.5 -16 5 4.5 -19 5 4.5 -13 5 5.5 -16 5 5.5 -19 5 5.5 -13 5 8.5 -16 5 8.5 -19 5 8.5 -13 5 9.5 -16 5 9.5 -19 5 9.5 -13 5 12.5 -16 5 12.5 -19 5 12.5 -13 5 13.5 -16 5 13.5 -19 5 13.5 -13 5 16 -16 5 16 -16 5 16.5 -19 5 16.5 -13 5 16.5 -16 5 16.5 -16 5 17.5 -19 5 17.5 -13 5 17.5 -16 5 17.5 -13 -25 6.5 -16 -25 6.5 -19 -25 6.5 -13 -25 7.5 -16 -25 7.5 -19 -25 7.5 -13 -25 10.5 -16 -25 10.5 -19 -25 10.5 -13 -25 11.5 -16 -25 11.5 -19 -25 11.5 -13 -25 14.5 -16 -25 14.5 -19 -25 14.5 -13 -25 15.5 -16 -25 15.5 -19 -25 15.5 -13 -25 18.5 -16 -25 18.5 -19 -25 18.5 -13 -25 19.5 -16 -25 19.5 -19 -25 19.5 20 -25 6.5 23 -25 6.5 17 -25 6.5 20 -25 7.5 23 -25 7.5 17 -25 7.5 20 -25 10.5 23 -25 10.5 17 -25 10.5 20 -25 11.5 23 -25 11.5 17 -25 11.5 20 -25 14.5 23 -25 14.5 17 -25 14.5 20 -25 15.5 23 -25 15.5 17 -25 15.5 20 -25 18.5 23 -25 18.5 17 -25 18.5 20 -25 19.5 23 -25 19.5 17 -25 19.5 53 -25 6.5 56 -25 6.5 59 -25 6.5 53 -25 7.5 56 -25 7.5 59 -25 7.5 53 -25 10.5 56 -25 10.5 59 -25 10.5 53 -25 11.5 56 -25 11.5 59 -25 11.5 53 -25 14.5 56 -25 14.5 59 -25 14.5 53 -25 15.5 56 -25 15.5 59 -25 15.5 53 -25 18.5 56 -25 18.5 59 -25 18.5 53 -25 19.5 56 -25 19.5 59 -25 19.5 53 5 8.5 56 5 8.5 59 5 8.5 53 5 9.5 56 5 9.5 59 5 9.5 53 5 12.5 56 5 12.5 59 5 12.5 53 5 13.5 56 5 13.5 59 5 13.5 53 5 16.5 56 5 16.5 59 5 16.5 53 5 17.5 56 5 17.5 59 5 17.5 -16 -15 2 -16 -5 4 -19 -15 6.5 -19 -5 4.5 -19 -15 7.5 -19 -5 5.5 -19 -15 10.5 -19 -5 8.5 -19 -15 11.5 -19 -5 9.5 -19 -15 14.5 -19 -5 12.5 -19 -15 15.5 -19 -5 13.5 -19 -15 18.5 -19 -5 16.5 -19 -15 19.5 -19 -5 17.5 59 -15 6.5 59 -5 8.5 59 -15 7.5 59 -5 9.5 59 -15 10.5 59 -5 12.5 59 -15 11.5 59 -5 13.5 59 -15 14.5 59 -5 16.5 59 -15 15.5 59 -5 17.5 56 -15 18.5 59 -15 18.5 56 -15 19.5 59 -15 19.5
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 | 0 1 0 0 0 1 0 0.1961161 0.9805808 0 -0.1961161 0.9805808 0 -1 0 1 0 0 -1 0 0
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 | 37 0 38 0 39 0 0 1 3 1 1 1 3 1 4 1 1 1 0 1 7 1 2 1 0 2 9 2 6 2 8 1 11 1 9 1 8 1 13 1 10 1 12 1 15 1 13 1 11 1 16 1 9 1 6 1 19 1 7 1 14 1 21 1 15 1 20 1 23 1 21 1 5 1 24 1 4 1 25 1 26 1 24 1 18 1 29 1 19 1 28 1 31 1 29 1 17 1 32 1 16 1 33 1 34 1 32 1 41 0 42 0 43 0 4 2 20 2 14 2 32 2 30 2 28 2 12 1 37 1 14 1 4 1 38 1 1 1 6 1 41 1 18 1 16 1 42 1 9 1 81 0 82 0 83 0 44 1 47 1 45 1 47 1 48 1 45 1 44 1 51 1 46 1 44 2 53 2 50 2 52 1 55 1 53 1 52 1 57 1 54 1 56 1 59 1 57 1 55 1 60 1 53 1 50 1 63 1 51 1 58 1 65 1 59 1 64 1 67 1 65 1 49 1 68 1 48 1 69 1 70 1 68 1 62 1 73 1 63 1 72 1 75 1 73 1 61 1 76 1 60 1 77 1 78 1 76 1 85 0 86 0 87 0 48 2 64 2 58 2 76 2 74 2 72 2 56 1 81 1 58 1 48 1 82 1 45 1 50 1 85 1 62 1 60 1 86 1 53 1 125 0 126 0 127 0 88 1 91 1 89 1 91 1 92 1 89 1 88 1 95 1 90 1 88 2 97 2 94 2 96 1 99 1 97 1 96 1 101 1 98 1 100 1 103 1 101 1 99 1 104 1 97 1 94 1 107 1 95 1 102 1 109 1 103 1 108 1 111 1 109 1 93 1 112 1 92 1 113 1 114 1 112 1 106 1 117 1 107 1 116 1 119 1 117 1 105 1 120 1 104 1 121 1 122 1 120 1 129 0 130 0 131 0 92 2 108 2 102 2 120 2 118 2 116 2 100 1 125 1 102 1 92 1 126 1 89 1 94 1 129 1 106 1 104 1 130 1 97 1 169 0 170 0 171 0 132 1 135 1 133 1 135 1 136 1 133 1 132 1 139 1 134 1 132 2 141 2 138 2 140 1 143 1 141 1 140 1 145 1 142 1 144 1 147 1 145 1 143 1 148 1 141 1 138 1 151 1 139 1 146 1 153 1 147 1 152 1 155 1 153 1 137 1 156 1 136 1 157 1 158 1 156 1 150 1 161 1 151 1 160 1 163 1 161 1 149 1 164 1 148 1 165 1 166 1 164 1 173 0 174 0 175 0 136 2 152 2 146 2 164 2 162 2 160 2 144 1 169 1 146 1 136 1 170 1 133 1 138 1 173 1 150 1 148 1 174 1 141 1 213 0 214 0 215 0 176 1 179 1 177 1 179 1 180 1 177 1 176 1 183 1 178 1 176 2 185 2 182 2 184 1 187 1 185 1 184 1 189 1 186 1 188 1 191 1 189 1 187 1 192 1 185 1 182 1 195 1 183 1 190 1 197 1 191 1 196 1 199 1 197 1 181 1 200 1 180 1 201 1 202 1 200 1 194 1 205 1 195 1 204 1 207 1 205 1 193 1 208 1 192 1 209 1 210 1 208 1 217 0 218 0 219 0 180 2 196 2 190 2 208 2 206 2 204 2 188 1 213 1 190 1 180 1 214 1 177 1 182 1 217 1 194 1 192 1 218 1 185 1 1 3 52 3 0 3 26 3 64 3 24 3 18 3 76 3 28 3 62 3 120 3 72 3 106 3 164 3 116 3 150 3 208 3 160 3 45 3 96 3 44 3 89 3 140 3 88 3 133 3 184 3 132 3 70 3 108 3 68 3 114 3 152 3 112 3 158 3 196 3 156 3 10 1 221 1 11 1 15 1 222 1 13 1 33 1 230 1 35 1 13 1 220 1 10 1 11 1 224 1 17 1 22 1 227 1 23 1 17 1 228 1 33 1 23 1 225 1 21 1 35 1 229 1 34 1 21 1 223 1 15 1 222 4 231 4 220 4 220 4 232 4 221 4 233 4 234 4 231 4 231 4 235 4 232 4 224 4 238 4 228 4 240 4 247 4 238 4 228 4 237 4 230 4 227 4 242 4 225 4 225 4 241 4 223 4 243 4 245 4 242 4 242 4 244 4 241 4 241 4 236 4 233 4 238 4 239 4 237 4 248 4 232 4 235 4 30 5 250 5 249 5 249 5 252 5 251 5 252 5 237 5 239 5 31 0 254 0 29 0 29 0 253 0 19 0 255 0 257 0 254 0 254 0 256 0 253 0 258 5 249 5 251 5 7 0 259 0 2 0 2 0 260 0 3 0 261 0 262 0 259 0 259 0 263 0 260 0 264 0 253 0 256 0 25 0 267 0 27 0 5 0 266 0 25 0 266 0 270 0 267 0 265 0 269 0 266 0 268 0 260 0 263 0 66 6 271 6 272 6 272 6 273 6 274 6 273 6 267 6 270 6 20 0 276 0 22 0 275 0 278 0 276 0 276 6 246 6 243 6 67 4 280 4 65 4 65 4 279 4 59 4 281 4 283 4 280 4 280 4 282 4 279 4 284 6 272 6 274 6 57 4 285 4 54 4 54 4 286 4 55 4 287 4 288 4 285 4 285 4 289 4 286 4 101 4 291 4 98 4 98 4 292 4 99 4 293 4 294 4 291 4 291 4 295 4 292 4 145 4 297 4 142 4 142 4 298 4 143 4 299 4 300 4 297 4 297 4 301 4 298 4 189 4 303 4 186 4 186 4 304 4 187 4 305 4 306 4 303 4 303 4 307 4 304 4 77 4 311 4 79 4 61 4 310 4 77 4 310 4 314 4 311 4 309 4 313 4 310 4 121 4 317 4 123 4 105 4 316 4 121 4 316 4 320 4 317 4 315 4 319 4 316 4 165 4 323 4 167 4 149 4 322 4 165 4 322 4 326 4 323 4 321 4 325 4 322 4 193 1 328 1 209 1 327 4 332 4 328 4 209 4 330 4 211 4 331 4 336 4 332 4 329 4 334 4 330 4 75 0 338 0 73 0 73 0 337 0 63 0 339 0 341 0 338 0 338 0 340 0 337 0 119 0 344 0 117 0 117 0 343 0 107 0 345 0 347 0 344 0 344 0 346 0 343 0 163 0 350 0 161 0 161 0 349 0 151 0 351 0 353 0 350 0 350 0 352 0 349 0 207 0 356 0 205 0 205 0 355 0 195 0 357 0 359 0 356 0 356 0 358 0 355 0 51 0 361 0 46 0 46 0 362 0 47 0 363 0 364 0 361 0 361 0 365 0 362 0 95 0 367 0 90 0 90 0 368 0 91 0 369 0 370 0 367 0 367 0 371 0 368 0 139 0 373 0 134 0 134 0 374 0 135 0 375 0 376 0 373 0 373 0 377 0 374 0 183 0 379 0 178 0 178 0 380 0 179 0 381 0 382 0 379 0 379 0 383 0 380 0 69 0 387 0 71 0 49 0 386 0 69 0 386 0 390 0 387 0 385 0 389 0 386 0 113 0 393 0 115 0 93 0 392 0 113 0 392 0 396 0 393 0 391 0 395 0 392 0 157 0 399 0 159 0 137 0 398 0 157 0 398 0 402 0 399 0 397 0 401 0 398 0 201 0 405 0 203 0 181 0 404 0 201 0 404 0 408 0 405 0 403 0 407 0 404 0 111 4 410 4 109 4 109 4 409 4 103 4 411 4 413 4 410 4 410 4 412 4 409 4 155 4 416 4 153 4 153 4 415 4 147 4 417 4 419 4 416 4 416 4 418 4 415 4 199 4 422 4 197 4 197 4 421 4 191 4 423 4 425 4 422 4 422 4 424 4 421 4 76 1 427 1 28 1 74 5 430 5 429 5 429 5 432 5 431 5 432 5 311 5 314 5 429 5 342 5 339 5 118 5 434 5 433 5 433 5 436 5 435 5 162 5 438 5 437 5 437 5 440 5 439 5 206 5 442 5 441 5 441 5 444 5 443 5 110 6 445 6 446 6 446 6 447 6 448 6 154 6 449 6 450 6 450 6 451 6 452 6 198 6 453 6 454 6 454 6 455 6 456 6 388 0 362 0 365 0 394 0 368 0 371 0 400 0 374 0 377 0 406 0 380 0 383 0 384 0 355 0 358 0 378 0 349 0 352 0 372 0 343 0 346 0 366 0 337 0 340 0 447 6 387 6 390 6 451 6 393 6 396 6 455 6 399 6 402 6 454 6 426 6 423 6 450 6 420 6 417 6 446 6 414 6 411 6 421 4 308 4 305 4 415 4 302 4 299 4 409 4 296 4 293 4 290 4 279 4 282 4 312 4 286 4 289 4 318 4 292 4 295 4 324 4 298 4 301 4 335 4 304 4 307 4 436 5 317 5 320 5 440 5 323 5 326 5 444 5 330 5 334 5 441 5 360 5 357 5 437 5 354 5 351 5 433 5 348 5 345 5 202 4 457 4 200 4 458 4 459 4 457 4 460 6 405 6 408 6 37 0 36 0 38 0 0 1 2 1 3 1 3 1 5 1 4 1 0 1 6 1 7 1 0 2 8 2 9 2 8 1 10 1 11 1 8 1 12 1 13 1 12 1 14 1 15 1 11 1 17 1 16 1 6 1 18 1 19 1 14 1 20 1 21 1 20 1 22 1 23 1 5 1 25 1 24 1 25 1 27 1 26 1 18 1 28 1 29 1 28 1 30 1 31 1 17 1 33 1 32 1 33 1 35 1 34 1 41 0 40 0 42 0 4 2 24 2 20 2 32 2 34 2 30 2 12 1 36 1 37 1 4 1 39 1 38 1 6 1 40 1 41 1 16 1 43 1 42 1 81 0 80 0 82 0 44 1 46 1 47 1 47 1 49 1 48 1 44 1 50 1 51 1 44 2 52 2 53 2 52 1 54 1 55 1 52 1 56 1 57 1 56 1 58 1 59 1 55 1 61 1 60 1 50 1 62 1 63 1 58 1 64 1 65 1 64 1 66 1 67 1 49 1 69 1 68 1 69 1 71 1 70 1 62 1 72 1 73 1 72 1 74 1 75 1 61 1 77 1 76 1 77 1 79 1 78 1 85 0 84 0 86 0 48 2 68 2 64 2 76 2 78 2 74 2 56 1 80 1 81 1 48 1 83 1 82 1 50 1 84 1 85 1 60 1 87 1 86 1 125 0 124 0 126 0 88 1 90 1 91 1 91 1 93 1 92 1 88 1 94 1 95 1 88 2 96 2 97 2 96 1 98 1 99 1 96 1 100 1 101 1 100 1 102 1 103 1 99 1 105 1 104 1 94 1 106 1 107 1 102 1 108 1 109 1 108 1 110 1 111 1 93 1 113 1 112 1 113 1 115 1 114 1 106 1 116 1 117 1 116 1 118 1 119 1 105 1 121 1 120 1 121 1 123 1 122 1 129 0 128 0 130 0 92 2 112 2 108 2 120 2 122 2 118 2 100 1 124 1 125 1 92 1 127 1 126 1 94 1 128 1 129 1 104 1 131 1 130 1 169 0 168 0 170 0 132 1 134 1 135 1 135 1 137 1 136 1 132 1 138 1 139 1 132 2 140 2 141 2 140 1 142 1 143 1 140 1 144 1 145 1 144 1 146 1 147 1 143 1 149 1 148 1 138 1 150 1 151 1 146 1 152 1 153 1 152 1 154 1 155 1 137 1 157 1 156 1 157 1 159 1 158 1 150 1 160 1 161 1 160 1 162 1 163 1 149 1 165 1 164 1 165 1 167 1 166 1 173 0 172 0 174 0 136 2 156 2 152 2 164 2 166 2 162 2 144 1 168 1 169 1 136 1 171 1 170 1 138 1 172 1 173 1 148 1 175 1 174 1 213 0 212 0 214 0 176 1 178 1 179 1 179 1 181 1 180 1 176 1 182 1 183 1 176 2 184 2 185 2 184 1 186 1 187 1 184 1 188 1 189 1 188 1 190 1 191 1 187 1 193 1 192 1 182 1 194 1 195 1 190 1 196 1 197 1 196 1 198 1 199 1 181 1 201 1 200 1 201 1 203 1 202 1 194 1 204 1 205 1 204 1 206 1 207 1 193 1 209 1 208 1 209 1 211 1 210 1 217 0 216 0 218 0 180 2 200 2 196 2 208 2 210 2 206 2 188 1 212 1 213 1 180 1 215 1 214 1 182 1 216 1 217 1 192 1 219 1 218 1 1 3 56 3 52 3 26 3 66 3 64 3 18 3 60 3 76 3 62 3 104 3 120 3 106 3 148 3 164 3 150 3 192 3 208 3 45 3 100 3 96 3 89 3 144 3 140 3 133 3 188 3 184 3 70 3 110 3 108 3 114 3 154 3 152 3 158 3 198 3 196 3 10 1 220 1 221 1 15 1 223 1 222 1 33 1 228 1 230 1 13 1 222 1 220 1 11 1 221 1 224 1 22 1 226 1 227 1 17 1 224 1 228 1 23 1 227 1 225 1 35 1 230 1 229 1 21 1 225 1 223 1 222 4 233 4 231 4 220 4 231 4 232 4 233 4 236 4 234 4 231 4 234 4 235 4 224 4 240 4 238 4 240 4 248 4 247 4 228 4 238 4 237 4 227 4 243 4 242 4 225 4 242 4 241 4 243 4 246 4 245 4 242 4 245 4 244 4 241 4 244 4 236 4 238 4 247 4 239 4 248 4 240 4 232 4 30 5 34 5 250 5 249 5 250 5 252 5 252 5 250 5 237 5 31 0 255 0 254 0 29 0 254 0 253 0 255 0 258 0 257 0 254 0 257 0 256 0 258 5 255 5 249 5 7 0 261 0 259 0 2 0 259 0 260 0 261 0 264 0 262 0 259 0 262 0 263 0 264 0 261 0 253 0 25 0 266 0 267 0 5 0 265 0 266 0 266 0 269 0 270 0 265 0 268 0 269 0 268 0 265 0 260 0 66 6 26 6 271 6 272 6 271 6 273 6 273 6 271 6 267 6 20 0 275 0 276 0 275 0 277 0 278 0 276 6 278 6 246 6 67 4 281 4 280 4 65 4 280 4 279 4 281 4 284 4 283 4 280 4 283 4 282 4 284 6 281 6 272 6 57 4 287 4 285 4 54 4 285 4 286 4 287 4 290 4 288 4 285 4 288 4 289 4 101 4 293 4 291 4 98 4 291 4 292 4 293 4 296 4 294 4 291 4 294 4 295 4 145 4 299 4 297 4 142 4 297 4 298 4 299 4 302 4 300 4 297 4 300 4 301 4 189 4 305 4 303 4 186 4 303 4 304 4 305 4 308 4 306 4 303 4 306 4 307 4 77 4 310 4 311 4 61 4 309 4 310 4 310 4 313 4 314 4 309 4 312 4 313 4 121 4 316 4 317 4 105 4 315 4 316 4 316 4 319 4 320 4 315 4 318 4 319 4 165 4 322 4 323 4 149 4 321 4 322 4 322 4 325 4 326 4 321 4 324 4 325 4 193 1 327 1 328 1 327 4 331 4 332 4 209 4 329 4 330 4 331 4 335 4 336 4 329 4 333 4 334 4 75 0 339 0 338 0 73 0 338 0 337 0 339 0 342 0 341 0 338 0 341 0 340 0 119 0 345 0 344 0 117 0 344 0 343 0 345 0 348 0 347 0 344 0 347 0 346 0 163 0 351 0 350 0 161 0 350 0 349 0 351 0 354 0 353 0 350 0 353 0 352 0 207 0 357 0 356 0 205 0 356 0 355 0 357 0 360 0 359 0 356 0 359 0 358 0 51 0 363 0 361 0 46 0 361 0 362 0 363 0 366 0 364 0 361 0 364 0 365 0 95 0 369 0 367 0 90 0 367 0 368 0 369 0 372 0 370 0 367 0 370 0 371 0 139 0 375 0 373 0 134 0 373 0 374 0 375 0 378 0 376 0 373 0 376 0 377 0 183 0 381 0 379 0 178 0 379 0 380 0 381 0 384 0 382 0 379 0 382 0 383 0 69 0 386 0 387 0 49 0 385 0 386 0 386 0 389 0 390 0 385 0 388 0 389 0 113 0 392 0 393 0 93 0 391 0 392 0 392 0 395 0 396 0 391 0 394 0 395 0 157 0 398 0 399 0 137 0 397 0 398 0 398 0 401 0 402 0 397 0 400 0 401 0 201 0 404 0 405 0 181 0 403 0 404 0 404 0 407 0 408 0 403 0 406 0 407 0 111 4 411 4 410 4 109 4 410 4 409 4 411 4 414 4 413 4 410 4 413 4 412 4 155 4 417 4 416 4 153 4 416 4 415 4 417 4 420 4 419 4 416 4 419 4 418 4 199 4 423 4 422 4 197 4 422 4 421 4 423 4 426 4 425 4 422 4 425 4 424 4 76 1 428 1 427 1 74 5 78 5 430 5 429 5 430 5 432 5 432 5 430 5 311 5 429 5 431 5 342 5 118 5 122 5 434 5 433 5 434 5 436 5 162 5 166 5 438 5 437 5 438 5 440 5 206 5 210 5 442 5 441 5 442 5 444 5 110 6 70 6 445 6 446 6 445 6 447 6 154 6 114 6 449 6 450 6 449 6 451 6 198 6 158 6 453 6 454 6 453 6 455 6 388 0 385 0 362 0 394 0 391 0 368 0 400 0 397 0 374 0 406 0 403 0 380 0 384 0 381 0 355 0 378 0 375 0 349 0 372 0 369 0 343 0 366 0 363 0 337 0 447 6 445 6 387 6 451 6 449 6 393 6 455 6 453 6 399 6 454 6 456 6 426 6 450 6 452 6 420 6 446 6 448 6 414 6 421 4 424 4 308 4 415 4 418 4 302 4 409 4 412 4 296 4 290 4 287 4 279 4 312 4 309 4 286 4 318 4 315 4 292 4 324 4 321 4 298 4 335 4 331 4 304 4 436 5 434 5 317 5 440 5 438 5 323 5 444 5 442 5 330 5 441 5 443 5 360 5 437 5 439 5 354 5 433 5 435 5 348 5 202 4 458 4 457 4 458 4 460 4 459 4 460 6 458 6 405 6
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 | 4.37114e-8 -1 -1.50996e-7 0 1 4.37114e-8 1.50996e-7 0 -1.50996e-7 -1.50996e-7 1 0 0 0 0 1
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/parking_garage/meshes/parking_garage_flipped.dae:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | Blender User
6 | Blender 3.0.1
7 |
8 | 2024-06-21T16:30:02
9 | 2024-06-21T16:30:02
10 |
11 | Z_UP
12 |
13 |
14 |
15 |
16 |
17 |
18 | 39.59775
19 | 1.777778
20 | 0.1
21 | 100
22 |
23 |
24 |
25 |
26 |
27 | 0
28 | 0
29 | 10
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 | 1000 1000 1000
39 | 1
40 | 0
41 | 0.00111109
42 |
43 |
44 |
45 |
46 | 0
47 | 0
48 | 1
49 | 1
50 | 1
51 | 1
52 | 1
53 | 0
54 | 0
55 | 0
56 | 1000
57 | 29.99998
58 | 75
59 | 0.15
60 | 0
61 | 1
62 | 2
63 | 0.04999995
64 | 30.002
65 | 1
66 | 3
67 | 2880
68 | 3
69 | 1
70 | 1
71 | 0.1
72 | 0.1
73 | 1
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 | 15 20 2 15 23 2 25 20 2 25 23 2 15 53 2 25 53 2 15 17 2 25 17 2 5 20 0 5 17 0 -5 20 0 -5 17 0 5 23 0 -5 23 0 5 53 0 -5 53 0 5 -13 0 -5 -13 0 15 -13 2 25 -13 2 5 56 0 -5 56 0 5 59 0 -5 59 0 15 56 2 25 56 2 15 59 2 25 59 2 15 -16 2 25 -16 2 15 -19 2 25 -19 2 5 -16 0 -5 -16 0 5 -19 0 -5 -19 0 10 23 0 10 53 0 10 23 2 10 53 2 10 17 2 10 -13 2 10 17 0 10 -13 0 15 20 6 15 23 6 25 20 6 25 23 6 15 53 6 25 53 6 15 17 6 25 17 6 5 20 4 5 17 4 -5 20 4 -5 17 4 5 23 4 -5 23 4 5 53 4 -5 53 4 5 -13 4 -5 -13 4 15 -13 6 25 -13 6 5 56 4 -5 56 4 5 59 4 -5 59 4 15 56 6 25 56 6 15 59 6 25 59 6 15 -16 6 25 -16 6 15 -19 6 25 -19 6 5 -16 4 -5 -16 4 5 -19 4 -5 -19 4 10 23 4 10 53 4 10 23 6 10 53 6 10 17 6 10 -13 6 10 17 4 10 -13 4 15 20 10 15 23 10 25 20 10 25 23 10 15 53 10 25 53 10 15 17 10 25 17 10 5 20 8 5 17 8 -5 20 8 -5 17 8 5 23 8 -5 23 8 5 53 8 -5 53 8 5 -13 8 -5 -13 8 15 -13 10 25 -13 10 5 56 8 -5 56 8 5 59 8 -5 59 8 15 56 10 25 56 10 15 59 10 25 59 10 15 -16 10 25 -16 10 15 -19 10 25 -19 10 5 -16 8 -5 -16 8 5 -19 8 -5 -19 8 10 23 8 10 53 8 10 23 10 10 53 10 10 17 10 10 -13 10 10 17 8 10 -13 8 15 20 14 15 23 14 25 20 14 25 23 14 15 53 14 25 53 14 15 17 14 25 17 14 5 20 12 5 17 12 -5 20 12 -5 17 12 5 23 12 -5 23 12 5 53 12 -5 53 12 5 -13 12 -5 -13 12 15 -13 14 25 -13 14 5 56 12 -5 56 12 5 59 12 -5 59 12 15 56 14 25 56 14 15 59 14 25 59 14 15 -16 14 25 -16 14 15 -19 14 25 -19 14 5 -16 12 -5 -16 12 5 -19 12 -5 -19 12 10 23 12 10 53 12 10 23 14 10 53 14 10 17 14 10 -13 14 10 17 12 10 -13 12 15 20 18 15 23 18 25 20 18 25 23 18 15 53 18 25 53 18 15 17 18 25 17 18 5 20 16 5 17 16 -5 20 16 -5 17 16 5 23 16 -5 23 16 5 53 16 -5 53 16 5 -13 16 -5 -13 16 15 -13 18 25 -13 18 5 56 16 -5 56 16 5 59 16 -5 59 16 15 56 18 25 56 18 15 59 18 25 59 18 15 -16 18 25 -16 18 15 -19 18 25 -19 18 5 -16 16 -5 -16 16 5 -19 16 -5 -19 16 10 23 16 10 53 16 10 23 18 10 53 18 10 17 18 10 -13 18 10 17 16 10 -13 16 -5 20 0 -5 17 0 -5 23 0 -5 53 0 -5 -13 0 -5 56 0 5 59 0 -5 59 0 -5 -16 0 5 -19 0 -5 -19 0 -5 20 0.5 -5 17 0.5 -5 23 0.5 -5 20 1.5 -5 17 1.5 -5 23 1.5 -5 -19 0.5 -5 -16 0.5 -5 -19 1.5 -5 -13 0.5 -5 53 0.5 -5 56 0.5 -5 59 0.5 -5 53 1.5 -5 56 1.5 -5 59 1.5 -5 -16 1.5 -5 -13 1.5 15 -19 2.5 5 -19 0.5 15 -19 3.5 5 -19 1.5 25 -13 2.5 25 -16 2.5 25 -19 2.5 25 -13 3.5 25 -16 3.5 25 -19 3.5 25 20 2.5 25 23 2.5 25 17 2.5 25 20 3.5 25 23 3.5 25 17 3.5 25 53 2.5 25 56 2.5 25 59 2.5 25 53 3.5 25 56 3.5 25 59 3.5 15 59 2.5 5 59 4.5 15 59 3.5 5 59 5.5 5 56 0.5 5 59 0.5 5 56 1.5 5 59 1.5 -5 53 4.5 -5 56 4.5 -5 59 4.5 -5 53 5.5 -5 56 5.5 -5 59 5.5 -5 20 4.5 -5 17 4.5 -5 23 4.5 -5 20 5.5 -5 17 5.5 -5 23 5.5 -5 20 8.5 -5 17 8.5 -5 23 8.5 -5 20 9.5 -5 17 9.5 -5 23 9.5 -5 20 12.5 -5 17 12.5 -5 23 12.5 -5 20 13.5 -5 17 13.5 -5 23 13.5 -5 20 16.5 -5 17 16.5 -5 23 16.5 -5 20 17.5 -5 17 17.5 -5 23 17.5 -5 -13 4.5 -5 -16 4.5 -5 -19 4.5 -5 -13 5.5 -5 -16 5.5 -5 -19 5.5 -5 -13 8.5 -5 -16 8.5 -5 -19 8.5 -5 -13 9.5 -5 -16 9.5 -5 -19 9.5 -5 -13 12.5 -5 -16 12.5 -5 -19 12.5 -5 -13 13.5 -5 -16 13.5 -5 -19 13.5 -5 -13 16 -5 -16 16 -5 -16 16.5 -5 -19 16.5 -5 -13 16.5 -5 -16 16.5 -5 -16 17.5 -5 -19 17.5 -5 -13 17.5 -5 -16 17.5 25 -13 6.5 25 -16 6.5 25 -19 6.5 25 -13 7.5 25 -16 7.5 25 -19 7.5 25 -13 10.5 25 -16 10.5 25 -19 10.5 25 -13 11.5 25 -16 11.5 25 -19 11.5 25 -13 14.5 25 -16 14.5 25 -19 14.5 25 -13 15.5 25 -16 15.5 25 -19 15.5 25 -13 18.5 25 -16 18.5 25 -19 18.5 25 -13 19.5 25 -16 19.5 25 -19 19.5 25 20 6.5 25 23 6.5 25 17 6.5 25 20 7.5 25 23 7.5 25 17 7.5 25 20 10.5 25 23 10.5 25 17 10.5 25 20 11.5 25 23 11.5 25 17 11.5 25 20 14.5 25 23 14.5 25 17 14.5 25 20 15.5 25 23 15.5 25 17 15.5 25 20 18.5 25 23 18.5 25 17 18.5 25 20 19.5 25 23 19.5 25 17 19.5 25 53 6.5 25 56 6.5 25 59 6.5 25 53 7.5 25 56 7.5 25 59 7.5 25 53 10.5 25 56 10.5 25 59 10.5 25 53 11.5 25 56 11.5 25 59 11.5 25 53 14.5 25 56 14.5 25 59 14.5 25 53 15.5 25 56 15.5 25 59 15.5 25 53 18.5 25 56 18.5 25 59 18.5 25 53 19.5 25 56 19.5 25 59 19.5 -5 53 8.5 -5 56 8.5 -5 59 8.5 -5 53 9.5 -5 56 9.5 -5 59 9.5 -5 53 12.5 -5 56 12.5 -5 59 12.5 -5 53 13.5 -5 56 13.5 -5 59 13.5 -5 53 16.5 -5 56 16.5 -5 59 16.5 -5 53 17.5 -5 56 17.5 -5 59 17.5 15 -16 2 5 -16 4 15 -19 6.5 5 -19 4.5 15 -19 7.5 5 -19 5.5 15 -19 10.5 5 -19 8.5 15 -19 11.5 5 -19 9.5 15 -19 14.5 5 -19 12.5 15 -19 15.5 5 -19 13.5 15 -19 18.5 5 -19 16.5 15 -19 19.5 5 -19 17.5 15 59 6.5 5 59 8.5 15 59 7.5 5 59 9.5 15 59 10.5 5 59 12.5 15 59 11.5 5 59 13.5 15 59 14.5 5 59 16.5 15 59 15.5 5 59 17.5 15 56 18.5 15 59 18.5 15 56 19.5 15 59 19.5
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 | 1 0 0 0 0 -1 0.1961161 0 -0.9805808 -0.1961161 0 -0.9805808 0 0 1 -1 0 0 0 -1 0 0 1 0
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 | 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 0 1 1 1 0 1 0 1 0 1 1 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 | 38 0 0 37 0 1 39 0 2 3 1 3 0 1 4 1 1 5 4 1 6 3 1 7 1 1 8 7 1 9 0 1 10 2 1 11 9 2 12 0 2 13 6 2 14 11 1 15 8 1 16 9 1 17 13 1 18 8 1 19 10 1 20 15 1 21 12 1 22 13 1 23 16 1 24 11 1 25 9 1 26 19 1 27 6 1 28 7 1 29 21 1 30 14 1 31 15 1 32 23 1 33 20 1 34 21 1 35 24 1 36 5 1 37 4 1 38 26 1 39 25 1 40 24 1 41 29 1 42 18 1 43 19 1 44 31 1 45 28 1 46 29 1 47 32 1 48 17 1 49 16 1 50 34 1 51 33 1 52 32 1 53 42 0 54 41 0 55 43 0 56 20 2 57 4 2 58 14 2 59 30 2 60 32 2 61 28 2 62 37 1 63 12 1 64 14 1 65 38 1 66 4 1 67 1 1 68 41 1 69 6 1 70 18 1 71 42 1 72 16 1 73 9 1 74 82 0 75 81 0 76 83 0 77 47 1 78 44 1 79 45 1 80 48 1 81 47 1 82 45 1 83 51 1 84 44 1 85 46 1 86 53 2 87 44 2 88 50 2 89 55 1 90 52 1 91 53 1 92 57 1 93 52 1 94 54 1 95 59 1 96 56 1 97 57 1 98 60 1 99 55 1 100 53 1 101 63 1 102 50 1 103 51 1 104 65 1 105 58 1 106 59 1 107 67 1 108 64 1 109 65 1 110 68 1 111 49 1 112 48 1 113 70 1 114 69 1 115 68 1 116 73 1 117 62 1 118 63 1 119 75 1 120 72 1 121 73 1 122 76 1 123 61 1 124 60 1 125 78 1 126 77 1 127 76 1 128 86 0 129 85 0 130 87 0 131 64 2 132 48 2 133 58 2 134 74 2 135 76 2 136 72 2 137 81 1 138 56 1 139 58 1 140 82 1 141 48 1 142 45 1 143 85 1 144 50 1 145 62 1 146 86 1 147 60 1 148 53 1 149 126 0 150 125 0 151 127 0 152 91 1 153 88 1 154 89 1 155 92 1 156 91 1 157 89 1 158 95 1 159 88 1 160 90 1 161 97 2 162 88 2 163 94 2 164 99 1 165 96 1 166 97 1 167 101 1 168 96 1 169 98 1 170 103 1 171 100 1 172 101 1 173 104 1 174 99 1 175 97 1 176 107 1 177 94 1 178 95 1 179 109 1 180 102 1 181 103 1 182 111 1 183 108 1 184 109 1 185 112 1 186 93 1 187 92 1 188 114 1 189 113 1 190 112 1 191 117 1 192 106 1 193 107 1 194 119 1 195 116 1 196 117 1 197 120 1 198 105 1 199 104 1 200 122 1 201 121 1 202 120 1 203 130 0 204 129 0 205 131 0 206 108 2 207 92 2 208 102 2 209 118 2 210 120 2 211 116 2 212 125 1 213 100 1 214 102 1 215 126 1 216 92 1 217 89 1 218 129 1 219 94 1 220 106 1 221 130 1 222 104 1 223 97 1 224 170 0 225 169 0 226 171 0 227 135 1 228 132 1 229 133 1 230 136 1 231 135 1 232 133 1 233 139 1 234 132 1 235 134 1 236 141 2 237 132 2 238 138 2 239 143 1 240 140 1 241 141 1 242 145 1 243 140 1 244 142 1 245 147 1 246 144 1 247 145 1 248 148 1 249 143 1 250 141 1 251 151 1 252 138 1 253 139 1 254 153 1 255 146 1 256 147 1 257 155 1 258 152 1 259 153 1 260 156 1 261 137 1 262 136 1 263 158 1 264 157 1 265 156 1 266 161 1 267 150 1 268 151 1 269 163 1 270 160 1 271 161 1 272 164 1 273 149 1 274 148 1 275 166 1 276 165 1 277 164 1 278 174 0 279 173 0 280 175 0 281 152 2 282 136 2 283 146 2 284 162 2 285 164 2 286 160 2 287 169 1 288 144 1 289 146 1 290 170 1 291 136 1 292 133 1 293 173 1 294 138 1 295 150 1 296 174 1 297 148 1 298 141 1 299 214 0 300 213 0 301 215 0 302 179 1 303 176 1 304 177 1 305 180 1 306 179 1 307 177 1 308 183 1 309 176 1 310 178 1 311 185 2 312 176 2 313 182 2 314 187 1 315 184 1 316 185 1 317 189 1 318 184 1 319 186 1 320 191 1 321 188 1 322 189 1 323 192 1 324 187 1 325 185 1 326 195 1 327 182 1 328 183 1 329 197 1 330 190 1 331 191 1 332 199 1 333 196 1 334 197 1 335 200 1 336 181 1 337 180 1 338 202 1 339 201 1 340 200 1 341 205 1 342 194 1 343 195 1 344 207 1 345 204 1 346 205 1 347 208 1 348 193 1 349 192 1 350 210 1 351 209 1 352 208 1 353 218 0 354 217 0 355 219 0 356 196 2 357 180 2 358 190 2 359 206 2 360 208 2 361 204 2 362 213 1 363 188 1 364 190 1 365 214 1 366 180 1 367 177 1 368 217 1 369 182 1 370 194 1 371 218 1 372 192 1 373 185 1 374 52 3 375 1 3 376 0 3 377 64 3 378 26 3 379 24 3 380 76 3 381 18 3 382 28 3 383 120 3 384 62 3 385 72 3 386 164 3 387 106 3 388 116 3 389 208 3 390 150 3 391 160 3 392 96 3 393 45 3 394 44 3 395 140 3 396 89 3 397 88 3 398 184 3 399 133 3 400 132 3 401 108 3 402 70 3 403 68 3 404 152 3 405 114 3 406 112 3 407 196 3 408 158 3 409 156 3 410 221 4 411 10 4 412 11 4 413 222 4 414 15 4 415 13 4 416 230 4 417 33 4 418 35 4 419 220 4 420 13 4 421 10 4 422 224 4 423 11 4 424 17 4 425 227 4 426 22 4 427 23 4 428 228 4 429 17 4 430 33 4 431 225 4 432 23 4 433 21 4 434 229 4 435 35 4 436 34 4 437 223 4 438 21 4 439 15 4 440 231 5 441 222 5 442 220 5 443 232 5 444 220 5 445 221 5 446 234 5 447 233 5 448 231 5 449 235 5 450 231 5 451 232 5 452 238 5 453 224 5 454 228 5 455 247 5 456 240 5 457 238 5 458 237 5 459 228 5 460 230 5 461 242 5 462 227 5 463 225 5 464 241 5 465 225 5 466 223 5 467 245 5 468 243 5 469 242 5 470 244 5 471 242 5 472 241 5 473 236 5 474 241 5 475 233 5 476 239 5 477 238 5 478 237 5 479 232 5 480 248 5 481 235 5 482 30 6 483 250 6 484 34 6 485 249 6 486 252 6 487 250 6 488 237 6 489 252 6 490 239 6 491 254 0 492 31 0 493 29 0 494 253 0 495 29 0 496 19 0 497 257 0 498 255 0 499 254 0 500 256 0 501 254 0 502 253 0 503 249 6 504 258 6 505 251 6 506 259 0 507 7 0 508 2 0 509 260 0 510 2 0 511 3 0 512 262 0 513 261 0 514 259 0 515 263 0 516 259 0 517 260 0 518 253 0 519 264 0 520 256 0 521 267 0 522 25 0 523 27 0 524 266 0 525 5 0 526 25 0 527 270 0 528 266 0 529 267 0 530 269 0 531 265 0 532 266 0 533 260 0 534 268 0 535 263 0 536 66 7 537 271 7 538 26 7 539 272 7 540 273 7 541 271 7 542 267 7 543 273 7 544 270 7 545 276 0 546 20 0 547 22 0 548 278 0 549 275 0 550 276 0 551 246 7 552 276 7 553 243 7 554 280 5 555 67 5 556 65 5 557 279 5 558 65 5 559 59 5 560 283 5 561 281 5 562 280 5 563 282 5 564 280 5 565 279 5 566 272 7 567 284 7 568 274 7 569 285 5 570 57 5 571 54 5 572 286 5 573 54 5 574 55 5 575 288 5 576 287 5 577 285 5 578 289 5 579 285 5 580 286 5 581 291 5 582 101 5 583 98 5 584 292 5 585 98 5 586 99 5 587 294 5 588 293 5 589 291 5 590 295 5 591 291 5 592 292 5 593 297 5 594 145 5 595 142 5 596 298 5 597 142 5 598 143 5 599 300 5 600 299 5 601 297 5 602 301 5 603 297 5 604 298 5 605 303 5 606 189 5 607 186 5 608 304 5 609 186 5 610 187 5 611 306 5 612 305 5 613 303 5 614 307 5 615 303 5 616 304 5 617 311 5 618 77 5 619 79 5 620 310 5 621 61 5 622 77 5 623 314 5 624 310 5 625 311 5 626 313 5 627 309 5 628 310 5 629 317 5 630 121 5 631 123 5 632 316 5 633 105 5 634 121 5 635 320 5 636 316 5 637 317 5 638 319 5 639 315 5 640 316 5 641 323 5 642 165 5 643 167 5 644 322 5 645 149 5 646 165 5 647 326 5 648 322 5 649 323 5 650 325 5 651 321 5 652 322 5 653 328 4 654 193 4 655 209 4 656 332 5 657 327 5 658 328 5 659 330 5 660 209 5 661 211 5 662 336 5 663 331 5 664 332 5 665 334 5 666 329 5 667 330 5 668 338 0 669 75 0 670 73 0 671 337 0 672 73 0 673 63 0 674 341 0 675 339 0 676 338 0 677 340 0 678 338 0 679 337 0 680 344 0 681 119 0 682 117 0 683 343 0 684 117 0 685 107 0 686 347 0 687 345 0 688 344 0 689 346 0 690 344 0 691 343 0 692 350 0 693 163 0 694 161 0 695 349 0 696 161 0 697 151 0 698 353 0 699 351 0 700 350 0 701 352 0 702 350 0 703 349 0 704 356 0 705 207 0 706 205 0 707 355 0 708 205 0 709 195 0 710 359 0 711 357 0 712 356 0 713 358 0 714 356 0 715 355 0 716 361 0 717 51 0 718 46 0 719 362 0 720 46 0 721 47 0 722 364 0 723 363 0 724 361 0 725 365 0 726 361 0 727 362 0 728 367 0 729 95 0 730 90 0 731 368 0 732 90 0 733 91 0 734 370 0 735 369 0 736 367 0 737 371 0 738 367 0 739 368 0 740 373 0 741 139 0 742 134 0 743 374 0 744 134 0 745 135 0 746 376 0 747 375 0 748 373 0 749 377 0 750 373 0 751 374 0 752 379 0 753 183 0 754 178 0 755 380 0 756 178 0 757 179 0 758 382 0 759 381 0 760 379 0 761 383 0 762 379 0 763 380 0 764 387 0 765 69 0 766 71 0 767 386 0 768 49 0 769 69 0 770 390 0 771 386 0 772 387 0 773 389 0 774 385 0 775 386 0 776 393 0 777 113 0 778 115 0 779 392 0 780 93 0 781 113 0 782 396 0 783 392 0 784 393 0 785 395 0 786 391 0 787 392 0 788 399 0 789 157 0 790 159 0 791 398 0 792 137 0 793 157 0 794 402 0 795 398 0 796 399 0 797 401 0 798 397 0 799 398 0 800 405 0 801 201 0 802 203 0 803 404 0 804 181 0 805 201 0 806 408 0 807 404 0 808 405 0 809 407 0 810 403 0 811 404 0 812 410 5 813 111 5 814 109 5 815 409 5 816 109 5 817 103 5 818 413 5 819 411 5 820 410 5 821 412 5 822 410 5 823 409 5 824 416 5 825 155 5 826 153 5 827 415 5 828 153 5 829 147 5 830 419 5 831 417 5 832 416 5 833 418 5 834 416 5 835 415 5 836 422 5 837 199 5 838 197 5 839 421 5 840 197 5 841 191 5 842 425 5 843 423 5 844 422 5 845 424 5 846 422 5 847 421 5 848 427 4 849 76 4 850 28 4 851 74 6 852 430 6 853 78 6 854 429 6 855 432 6 856 430 6 857 311 6 858 432 6 859 314 6 860 342 6 861 429 6 862 339 6 863 118 6 864 434 6 865 122 6 866 433 6 867 436 6 868 434 6 869 162 6 870 438 6 871 166 6 872 437 6 873 440 6 874 438 6 875 206 6 876 442 6 877 210 6 878 441 6 879 444 6 880 442 6 881 110 7 882 445 7 883 70 7 884 446 7 885 447 7 886 445 7 887 154 7 888 449 7 889 114 7 890 450 7 891 451 7 892 449 7 893 198 7 894 453 7 895 158 7 896 454 7 897 455 7 898 453 7 899 362 0 900 388 0 901 365 0 902 368 0 903 394 0 904 371 0 905 374 0 906 400 0 907 377 0 908 380 0 909 406 0 910 383 0 911 355 0 912 384 0 913 358 0 914 349 0 915 378 0 916 352 0 917 343 0 918 372 0 919 346 0 920 337 0 921 366 0 922 340 0 923 387 7 924 447 7 925 390 7 926 393 7 927 451 7 928 396 7 929 399 7 930 455 7 931 402 7 932 426 7 933 454 7 934 423 7 935 420 7 936 450 7 937 417 7 938 414 7 939 446 7 940 411 7 941 308 5 942 421 5 943 305 5 944 302 5 945 415 5 946 299 5 947 296 5 948 409 5 949 293 5 950 279 5 951 290 5 952 282 5 953 286 5 954 312 5 955 289 5 956 292 5 957 318 5 958 295 5 959 298 5 960 324 5 961 301 5 962 304 5 963 335 5 964 307 5 965 317 6 966 436 6 967 320 6 968 323 6 969 440 6 970 326 6 971 330 6 972 444 6 973 334 6 974 360 6 975 441 6 976 357 6 977 354 6 978 437 6 979 351 6 980 348 6 981 433 6 982 345 6 983 457 5 984 202 5 985 200 5 986 459 5 987 458 5 988 457 5 989 405 7 990 460 7 991 408 7 992 38 0 993 36 0 994 37 0 995 3 1 996 2 1 997 0 1 998 4 1 999 5 1 1000 3 1 1001 7 1 1002 6 1 1003 0 1 1004 9 2 1005 8 2 1006 0 2 1007 11 1 1008 10 1 1009 8 1 1010 13 1 1011 12 1 1012 8 1 1013 15 1 1014 14 1 1015 12 1 1016 16 1 1017 17 1 1018 11 1 1019 19 1 1020 18 1 1021 6 1 1022 21 1 1023 20 1 1024 14 1 1025 23 1 1026 22 1 1027 20 1 1028 24 1 1029 25 1 1030 5 1 1031 26 1 1032 27 1 1033 25 1 1034 29 1 1035 28 1 1036 18 1 1037 31 1 1038 30 1 1039 28 1 1040 32 1 1041 33 1 1042 17 1 1043 34 1 1044 35 1 1045 33 1 1046 42 0 1047 40 0 1048 41 0 1049 20 2 1050 24 2 1051 4 2 1052 30 2 1053 34 2 1054 32 2 1055 37 1 1056 36 1 1057 12 1 1058 38 1 1059 39 1 1060 4 1 1061 41 1 1062 40 1 1063 6 1 1064 42 1 1065 43 1 1066 16 1 1067 82 0 1068 80 0 1069 81 0 1070 47 1 1071 46 1 1072 44 1 1073 48 1 1074 49 1 1075 47 1 1076 51 1 1077 50 1 1078 44 1 1079 53 2 1080 52 2 1081 44 2 1082 55 1 1083 54 1 1084 52 1 1085 57 1 1086 56 1 1087 52 1 1088 59 1 1089 58 1 1090 56 1 1091 60 1 1092 61 1 1093 55 1 1094 63 1 1095 62 1 1096 50 1 1097 65 1 1098 64 1 1099 58 1 1100 67 1 1101 66 1 1102 64 1 1103 68 1 1104 69 1 1105 49 1 1106 70 1 1107 71 1 1108 69 1 1109 73 1 1110 72 1 1111 62 1 1112 75 1 1113 74 1 1114 72 1 1115 76 1 1116 77 1 1117 61 1 1118 78 1 1119 79 1 1120 77 1 1121 86 0 1122 84 0 1123 85 0 1124 64 2 1125 68 2 1126 48 2 1127 74 2 1128 78 2 1129 76 2 1130 81 1 1131 80 1 1132 56 1 1133 82 1 1134 83 1 1135 48 1 1136 85 1 1137 84 1 1138 50 1 1139 86 1 1140 87 1 1141 60 1 1142 126 0 1143 124 0 1144 125 0 1145 91 1 1146 90 1 1147 88 1 1148 92 1 1149 93 1 1150 91 1 1151 95 1 1152 94 1 1153 88 1 1154 97 2 1155 96 2 1156 88 2 1157 99 1 1158 98 1 1159 96 1 1160 101 1 1161 100 1 1162 96 1 1163 103 1 1164 102 1 1165 100 1 1166 104 1 1167 105 1 1168 99 1 1169 107 1 1170 106 1 1171 94 1 1172 109 1 1173 108 1 1174 102 1 1175 111 1 1176 110 1 1177 108 1 1178 112 1 1179 113 1 1180 93 1 1181 114 1 1182 115 1 1183 113 1 1184 117 1 1185 116 1 1186 106 1 1187 119 1 1188 118 1 1189 116 1 1190 120 1 1191 121 1 1192 105 1 1193 122 1 1194 123 1 1195 121 1 1196 130 0 1197 128 0 1198 129 0 1199 108 2 1200 112 2 1201 92 2 1202 118 2 1203 122 2 1204 120 2 1205 125 1 1206 124 1 1207 100 1 1208 126 1 1209 127 1 1210 92 1 1211 129 1 1212 128 1 1213 94 1 1214 130 1 1215 131 1 1216 104 1 1217 170 0 1218 168 0 1219 169 0 1220 135 1 1221 134 1 1222 132 1 1223 136 1 1224 137 1 1225 135 1 1226 139 1 1227 138 1 1228 132 1 1229 141 2 1230 140 2 1231 132 2 1232 143 1 1233 142 1 1234 140 1 1235 145 1 1236 144 1 1237 140 1 1238 147 1 1239 146 1 1240 144 1 1241 148 1 1242 149 1 1243 143 1 1244 151 1 1245 150 1 1246 138 1 1247 153 1 1248 152 1 1249 146 1 1250 155 1 1251 154 1 1252 152 1 1253 156 1 1254 157 1 1255 137 1 1256 158 1 1257 159 1 1258 157 1 1259 161 1 1260 160 1 1261 150 1 1262 163 1 1263 162 1 1264 160 1 1265 164 1 1266 165 1 1267 149 1 1268 166 1 1269 167 1 1270 165 1 1271 174 0 1272 172 0 1273 173 0 1274 152 2 1275 156 2 1276 136 2 1277 162 2 1278 166 2 1279 164 2 1280 169 1 1281 168 1 1282 144 1 1283 170 1 1284 171 1 1285 136 1 1286 173 1 1287 172 1 1288 138 1 1289 174 1 1290 175 1 1291 148 1 1292 214 0 1293 212 0 1294 213 0 1295 179 1 1296 178 1 1297 176 1 1298 180 1 1299 181 1 1300 179 1 1301 183 1 1302 182 1 1303 176 1 1304 185 2 1305 184 2 1306 176 2 1307 187 1 1308 186 1 1309 184 1 1310 189 1 1311 188 1 1312 184 1 1313 191 1 1314 190 1 1315 188 1 1316 192 1 1317 193 1 1318 187 1 1319 195 1 1320 194 1 1321 182 1 1322 197 1 1323 196 1 1324 190 1 1325 199 1 1326 198 1 1327 196 1 1328 200 1 1329 201 1 1330 181 1 1331 202 1 1332 203 1 1333 201 1 1334 205 1 1335 204 1 1336 194 1 1337 207 1 1338 206 1 1339 204 1 1340 208 1 1341 209 1 1342 193 1 1343 210 1 1344 211 1 1345 209 1 1346 218 0 1347 216 0 1348 217 0 1349 196 2 1350 200 2 1351 180 2 1352 206 2 1353 210 2 1354 208 2 1355 213 1 1356 212 1 1357 188 1 1358 214 1 1359 215 1 1360 180 1 1361 217 1 1362 216 1 1363 182 1 1364 218 1 1365 219 1 1366 192 1 1367 52 3 1368 56 3 1369 1 3 1370 64 3 1371 66 3 1372 26 3 1373 76 3 1374 60 3 1375 18 3 1376 120 3 1377 104 3 1378 62 3 1379 164 3 1380 148 3 1381 106 3 1382 208 3 1383 192 3 1384 150 3 1385 96 3 1386 100 3 1387 45 3 1388 140 3 1389 144 3 1390 89 3 1391 184 3 1392 188 3 1393 133 3 1394 108 3 1395 110 3 1396 70 3 1397 152 3 1398 154 3 1399 114 3 1400 196 3 1401 198 3 1402 158 3 1403 221 4 1404 220 4 1405 10 4 1406 222 4 1407 223 4 1408 15 4 1409 230 4 1410 228 4 1411 33 4 1412 220 4 1413 222 4 1414 13 4 1415 224 4 1416 221 4 1417 11 4 1418 227 4 1419 226 4 1420 22 4 1421 228 4 1422 224 4 1423 17 4 1424 225 4 1425 227 4 1426 23 4 1427 229 4 1428 230 4 1429 35 4 1430 223 4 1431 225 4 1432 21 4 1433 231 5 1434 233 5 1435 222 5 1436 232 5 1437 231 5 1438 220 5 1439 234 5 1440 236 5 1441 233 5 1442 235 5 1443 234 5 1444 231 5 1445 238 5 1446 240 5 1447 224 5 1448 247 5 1449 248 5 1450 240 5 1451 237 5 1452 238 5 1453 228 5 1454 242 5 1455 243 5 1456 227 5 1457 241 5 1458 242 5 1459 225 5 1460 245 5 1461 246 5 1462 243 5 1463 244 5 1464 245 5 1465 242 5 1466 236 5 1467 244 5 1468 241 5 1469 239 5 1470 247 5 1471 238 5 1472 232 5 1473 240 5 1474 248 5 1475 30 6 1476 249 6 1477 250 6 1478 249 6 1479 251 6 1480 252 6 1481 237 6 1482 250 6 1483 252 6 1484 254 0 1485 255 0 1486 31 0 1487 253 0 1488 254 0 1489 29 0 1490 257 0 1491 258 0 1492 255 0 1493 256 0 1494 257 0 1495 254 0 1496 249 6 1497 255 6 1498 258 6 1499 259 0 1500 261 0 1501 7 0 1502 260 0 1503 259 0 1504 2 0 1505 262 0 1506 264 0 1507 261 0 1508 263 0 1509 262 0 1510 259 0 1511 253 0 1512 261 0 1513 264 0 1514 267 0 1515 266 0 1516 25 0 1517 266 0 1518 265 0 1519 5 0 1520 270 0 1521 269 0 1522 266 0 1523 269 0 1524 268 0 1525 265 0 1526 260 0 1527 265 0 1528 268 0 1529 66 7 1530 272 7 1531 271 7 1532 272 7 1533 274 7 1534 273 7 1535 267 7 1536 271 7 1537 273 7 1538 276 0 1539 275 0 1540 20 0 1541 278 0 1542 277 0 1543 275 0 1544 246 7 1545 278 7 1546 276 7 1547 280 5 1548 281 5 1549 67 5 1550 279 5 1551 280 5 1552 65 5 1553 283 5 1554 284 5 1555 281 5 1556 282 5 1557 283 5 1558 280 5 1559 272 7 1560 281 7 1561 284 7 1562 285 5 1563 287 5 1564 57 5 1565 286 5 1566 285 5 1567 54 5 1568 288 5 1569 290 5 1570 287 5 1571 289 5 1572 288 5 1573 285 5 1574 291 5 1575 293 5 1576 101 5 1577 292 5 1578 291 5 1579 98 5 1580 294 5 1581 296 5 1582 293 5 1583 295 5 1584 294 5 1585 291 5 1586 297 5 1587 299 5 1588 145 5 1589 298 5 1590 297 5 1591 142 5 1592 300 5 1593 302 5 1594 299 5 1595 301 5 1596 300 5 1597 297 5 1598 303 5 1599 305 5 1600 189 5 1601 304 5 1602 303 5 1603 186 5 1604 306 5 1605 308 5 1606 305 5 1607 307 5 1608 306 5 1609 303 5 1610 311 5 1611 310 5 1612 77 5 1613 310 5 1614 309 5 1615 61 5 1616 314 5 1617 313 5 1618 310 5 1619 313 5 1620 312 5 1621 309 5 1622 317 5 1623 316 5 1624 121 5 1625 316 5 1626 315 5 1627 105 5 1628 320 5 1629 319 5 1630 316 5 1631 319 5 1632 318 5 1633 315 5 1634 323 5 1635 322 5 1636 165 5 1637 322 5 1638 321 5 1639 149 5 1640 326 5 1641 325 5 1642 322 5 1643 325 5 1644 324 5 1645 321 5 1646 328 4 1647 327 4 1648 193 4 1649 332 5 1650 331 5 1651 327 5 1652 330 5 1653 329 5 1654 209 5 1655 336 5 1656 335 5 1657 331 5 1658 334 5 1659 333 5 1660 329 5 1661 338 0 1662 339 0 1663 75 0 1664 337 0 1665 338 0 1666 73 0 1667 341 0 1668 342 0 1669 339 0 1670 340 0 1671 341 0 1672 338 0 1673 344 0 1674 345 0 1675 119 0 1676 343 0 1677 344 0 1678 117 0 1679 347 0 1680 348 0 1681 345 0 1682 346 0 1683 347 0 1684 344 0 1685 350 0 1686 351 0 1687 163 0 1688 349 0 1689 350 0 1690 161 0 1691 353 0 1692 354 0 1693 351 0 1694 352 0 1695 353 0 1696 350 0 1697 356 0 1698 357 0 1699 207 0 1700 355 0 1701 356 0 1702 205 0 1703 359 0 1704 360 0 1705 357 0 1706 358 0 1707 359 0 1708 356 0 1709 361 0 1710 363 0 1711 51 0 1712 362 0 1713 361 0 1714 46 0 1715 364 0 1716 366 0 1717 363 0 1718 365 0 1719 364 0 1720 361 0 1721 367 0 1722 369 0 1723 95 0 1724 368 0 1725 367 0 1726 90 0 1727 370 0 1728 372 0 1729 369 0 1730 371 0 1731 370 0 1732 367 0 1733 373 0 1734 375 0 1735 139 0 1736 374 0 1737 373 0 1738 134 0 1739 376 0 1740 378 0 1741 375 0 1742 377 0 1743 376 0 1744 373 0 1745 379 0 1746 381 0 1747 183 0 1748 380 0 1749 379 0 1750 178 0 1751 382 0 1752 384 0 1753 381 0 1754 383 0 1755 382 0 1756 379 0 1757 387 0 1758 386 0 1759 69 0 1760 386 0 1761 385 0 1762 49 0 1763 390 0 1764 389 0 1765 386 0 1766 389 0 1767 388 0 1768 385 0 1769 393 0 1770 392 0 1771 113 0 1772 392 0 1773 391 0 1774 93 0 1775 396 0 1776 395 0 1777 392 0 1778 395 0 1779 394 0 1780 391 0 1781 399 0 1782 398 0 1783 157 0 1784 398 0 1785 397 0 1786 137 0 1787 402 0 1788 401 0 1789 398 0 1790 401 0 1791 400 0 1792 397 0 1793 405 0 1794 404 0 1795 201 0 1796 404 0 1797 403 0 1798 181 0 1799 408 0 1800 407 0 1801 404 0 1802 407 0 1803 406 0 1804 403 0 1805 410 5 1806 411 5 1807 111 5 1808 409 5 1809 410 5 1810 109 5 1811 413 5 1812 414 5 1813 411 5 1814 412 5 1815 413 5 1816 410 5 1817 416 5 1818 417 5 1819 155 5 1820 415 5 1821 416 5 1822 153 5 1823 419 5 1824 420 5 1825 417 5 1826 418 5 1827 419 5 1828 416 5 1829 422 5 1830 423 5 1831 199 5 1832 421 5 1833 422 5 1834 197 5 1835 425 5 1836 426 5 1837 423 5 1838 424 5 1839 425 5 1840 422 5 1841 427 4 1842 428 4 1843 76 4 1844 74 6 1845 429 6 1846 430 6 1847 429 6 1848 431 6 1849 432 6 1850 311 6 1851 430 6 1852 432 6 1853 342 6 1854 431 6 1855 429 6 1856 118 6 1857 433 6 1858 434 6 1859 433 6 1860 435 6 1861 436 6 1862 162 6 1863 437 6 1864 438 6 1865 437 6 1866 439 6 1867 440 6 1868 206 6 1869 441 6 1870 442 6 1871 441 6 1872 443 6 1873 444 6 1874 110 7 1875 446 7 1876 445 7 1877 446 7 1878 448 7 1879 447 7 1880 154 7 1881 450 7 1882 449 7 1883 450 7 1884 452 7 1885 451 7 1886 198 7 1887 454 7 1888 453 7 1889 454 7 1890 456 7 1891 455 7 1892 362 0 1893 385 0 1894 388 0 1895 368 0 1896 391 0 1897 394 0 1898 374 0 1899 397 0 1900 400 0 1901 380 0 1902 403 0 1903 406 0 1904 355 0 1905 381 0 1906 384 0 1907 349 0 1908 375 0 1909 378 0 1910 343 0 1911 369 0 1912 372 0 1913 337 0 1914 363 0 1915 366 0 1916 387 7 1917 445 7 1918 447 7 1919 393 7 1920 449 7 1921 451 7 1922 399 7 1923 453 7 1924 455 7 1925 426 7 1926 456 7 1927 454 7 1928 420 7 1929 452 7 1930 450 7 1931 414 7 1932 448 7 1933 446 7 1934 308 5 1935 424 5 1936 421 5 1937 302 5 1938 418 5 1939 415 5 1940 296 5 1941 412 5 1942 409 5 1943 279 5 1944 287 5 1945 290 5 1946 286 5 1947 309 5 1948 312 5 1949 292 5 1950 315 5 1951 318 5 1952 298 5 1953 321 5 1954 324 5 1955 304 5 1956 331 5 1957 335 5 1958 317 6 1959 434 6 1960 436 6 1961 323 6 1962 438 6 1963 440 6 1964 330 6 1965 442 6 1966 444 6 1967 360 6 1968 443 6 1969 441 6 1970 354 6 1971 439 6 1972 437 6 1973 348 6 1974 435 6 1975 433 6 1976 457 5 1977 458 5 1978 202 5 1979 459 5 1980 460 5 1981 458 5 1982 405 7 1983 458 7 1984 460 7 1985
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 | 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1
127 |
128 |
129 |
130 | 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1
131 |
132 |
133 |
134 | -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/parking_garage/model.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | Parking Garage
5 | 1.0
6 | model.sdf
7 |
8 |
9 | Alexander Mock
10 | amock@uos.de
11 |
12 |
13 |
14 | Parking Garage
15 |
16 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/parking_garage/model.sdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | true
5 |
6 |
7 |
8 |
9 | 1 1 1
10 | meshes/parking_garage.dae
11 |
12 |
13 |
14 |
15 |
16 |
17 | 1 1 1
18 | meshes/parking_garage.dae
19 |
20 |
21 |
22 |
23 |
24 |
25 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/tray/meshes/tray.dae:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | Blender User
6 | Blender 3.3.1 commit date:2022-10-04, commit time:18:35, hash:b292cfe5a936
7 |
8 | 2022-10-20T21:46:39
9 | 2022-10-20T21:46:39
10 |
11 | Z_UP
12 |
13 |
14 |
15 |
16 |
17 |
18 | 39.59775
19 | 1.777778
20 | 0.1
21 | 100
22 |
23 |
24 |
25 |
26 |
27 | 0
28 | 0
29 | 10
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 | 1000 1000 1000
39 | 1
40 | 0
41 | 0.00111109
42 |
43 |
44 |
45 |
46 | 0
47 | 0
48 | 1
49 | 1
50 | 1
51 | 1
52 | 1
53 | 0
54 | 0
55 | 0
56 | 1000
57 | 29.99998
58 | 75
59 | 0.15
60 | 0
61 | 1
62 | 2
63 | 0.04999995
64 | 30.002
65 | 1
66 | 3
67 | 2880
68 | 3
69 | 1
70 | 1
71 | 0.1
72 | 0.1
73 | 1
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 | 0 0 0 1
85 |
86 |
87 | 0.8 0.8 0.8 1
88 |
89 |
90 | 1.45
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 | 1 1 1 1 1 -1 1 -1 1 1 -1 -1 -1 1 1 -1 1 -1 -1 -1 1 -1 -1 -1
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 | 0 1 0 1 0 0 0 0 1 -1 0 0 0 -1 0
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 | 0.375 1 0.625 0.75 0.375 0.75 0.375 0.25 0.625 0 0.375 0 0.125 0.75 0.375 0.5 0.125 0.5 0.375 0.75 0.625 0.5 0.375 0.5 0.375 0.5 0.625 0.25 0.375 0.25 0.375 1 0.625 1 0.625 0.75 0.375 0.25 0.625 0.25 0.625 0 0.125 0.75 0.375 0.75 0.375 0.5 0.375 0.75 0.625 0.75 0.625 0.5 0.375 0.5 0.625 0.5 0.625 0.25
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 | 7 0 0 2 0 1 3 0 2 5 1 3 6 1 4 7 1 5 7 2 6 1 2 7 5 2 8 3 3 9 0 3 10 1 3 11 1 4 12 4 4 13 5 4 14 7 0 15 6 0 16 2 0 17 5 1 18 4 1 19 6 1 20 7 2 21 3 2 22 1 2 23 3 3 24 2 3 25 0 3 26 1 4 27 0 4 28 4 4 29
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 | 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1
151 |
152 |
153 |
154 | -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1
155 |
156 |
157 |
158 | 10 0 0 0 0 5 0 0 0 0 0.5000001 0.5 0 0 0 1
159 |
160 |
161 |
162 |
163 |
164 |
165 |
166 |
167 |
168 |
169 |
170 |
171 |
172 |
173 |
174 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/tray/meshes/tray.ply:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/naturerobots/mesh_navigation_tutorials/81d9c97468f9db5027fbbd0db75307da1cd8679e/mesh_navigation_tutorials_sim/models/tray/meshes/tray.ply
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/tray/model.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | Tray
5 | 1.0
6 | model.sdf
7 |
8 |
9 | Alexander Mock
10 | amock@uos.de
11 |
12 |
13 |
14 | Tray
15 |
16 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/models/tray/model.sdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | true
5 |
6 |
7 |
8 |
9 | 1 1 1
10 | meshes/tray.dae
11 |
12 |
13 |
14 |
15 |
16 |
17 | 1 1 1
18 | meshes/tray.dae
19 |
20 |
21 |
22 |
23 |
24 |
25 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | mesh_navigation_tutorials_sim
5 | 0.0.1
6 | Tutorials for mobile robot navigation in 3D, using mesh maps.
7 |
8 | Matthias Holoch
9 | Alexander Mock
10 |
11 | BSD-3-Clause
12 |
13 | ament_cmake
14 |
15 | rclcpp
16 | geometry_msgs
17 | tf2_ros
18 | tf2_geometry_msgs
19 |
20 | ros_gz_bridge
21 | ros_gz_sim
22 | xacro
23 |
24 | ament_lint_auto
25 | ament_cmake_copyright
26 | ament_cmake_cppcheck
27 | ament_cmake_pep257
28 | ament_cmake_uncrustify
29 |
30 |
31 | ament_cmake
32 |
33 |
34 |
35 |
36 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/src/ground_truth_localization.cpp:
--------------------------------------------------------------------------------
1 | // Copyright 2024 Nature Robots GmbH
2 | //
3 | // Redistribution and use in source and binary forms, with or without
4 | // modification, are permitted provided that the following conditions are met:
5 | //
6 | // * Redistributions of source code must retain the above copyright
7 | // notice, this list of conditions and the following disclaimer.
8 | //
9 | // * Redistributions in binary form must reproduce the above copyright
10 | // notice, this list of conditions and the following disclaimer in the
11 | // documentation and/or other materials provided with the distribution.
12 | //
13 | // * Neither the name of the Nature Robots GmbH nor the names of its
14 | // contributors may be used to endorse or promote products derived from
15 | // this software without specific prior written permission.
16 | //
17 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 | // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 | // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 | // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21 | // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22 | // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23 | // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24 | // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25 | // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26 | // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27 | // POSSIBILITY OF SUCH DAMAGE.
28 |
29 |
30 | #include
31 | #include
32 |
33 | #include
34 |
35 |
36 | #include "tf2/exceptions.h"
37 | #include "tf2_ros/transform_listener.h"
38 | #include "tf2_ros/buffer.h"
39 | #include "tf2/convert.h"
40 | #include "tf2_eigen/tf2_eigen.hpp"
41 |
42 | #include "tf2/LinearMath/Quaternion.h"
43 | #include "tf2_ros/transform_broadcaster.h"
44 |
45 | #include
46 |
47 |
48 | #include
49 |
50 |
51 | namespace mesh_navigation_tutorials_sim
52 | {
53 |
54 | class GroundTruthLocalizationNode : public rclcpp::Node
55 | {
56 | public:
57 | explicit GroundTruthLocalizationNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions())
58 | : rclcpp::Node("ground_truth_localization_node", options)
59 | {
60 | std::cout << "GroundTruthLocalizationNode" << std::endl;
61 |
62 | this->declare_parameter("gz_parent_frame", "tray");
63 | this->declare_parameter("gz_child_frame", "robot");
64 | this->declare_parameter("ros_parent_frame", "map");
65 | this->declare_parameter("ros_child_frame", "base_footprint");
66 | this->declare_parameter("ros_odom_frame", "odom");
67 |
68 | gz_parent_frame_ = this->get_parameter("gz_parent_frame").as_string();
69 | gz_child_frame_ = this->get_parameter("gz_child_frame").as_string();
70 | ros_parent_frame_ = this->get_parameter("ros_parent_frame").as_string();
71 | ros_child_frame_ = this->get_parameter("ros_child_frame").as_string();
72 | ros_odom_frame_ = this->get_parameter("ros_odom_frame").as_string();
73 | skip_odom_frame_ = (ros_odom_frame_ != "");
74 |
75 | // Initialize the transform broadcaster
76 | tf_broadcaster_ =
77 | std::make_unique(*this);
78 | tf_buffer_ =
79 | std::make_unique(this->get_clock());
80 | tf_listener_ =
81 | std::make_shared(*tf_buffer_);
82 |
83 | // subscribe to tf messages coming from gazebo
84 | sub_tf_ = this->create_subscription(
85 | "/tf_gt", 10,
86 | [ = ](const tf2_msgs::msg::TFMessage::ConstSharedPtr & msgs) -> void
87 | {
88 | tf_cb(msgs);
89 | });
90 |
91 | std::cout << "Searching for Gazebo Transform " << gz_child_frame_ << " -> " <<
92 | gz_parent_frame_ << std::endl;
93 | }
94 |
95 | void tf_cb(const tf2_msgs::msg::TFMessage::ConstSharedPtr & msgs)
96 | {
97 | for (geometry_msgs::msg::TransformStamped Tbm : msgs->transforms) {
98 | if (Tbm.header.frame_id == gz_parent_frame_) {
99 | if (Tbm.child_frame_id == gz_child_frame_) {
100 | if (skip_odom_frame_) {
101 | // plan:
102 | // get last tf from base_footprint -> odom
103 | geometry_msgs::msg::TransformStamped Tbo;
104 |
105 | // Look up for the transformation between target_frame and turtle2 frames
106 | // and send velocity commands for turtle2 to reach target_frame
107 | try {
108 | Tbo = tf_buffer_->lookupTransform(
109 | ros_odom_frame_, ros_child_frame_,
110 | tf2::TimePointZero);
111 | } catch (const tf2::TransformException & ex) {
112 | RCLCPP_INFO(
113 | this->get_logger(), "Could not transform %s to %s: %s",
114 | ros_child_frame_.c_str(), ros_odom_frame_.c_str(), ex.what());
115 | return;
116 | }
117 |
118 | geometry_msgs::msg::TransformStamped Tom;
119 | // Tom = Tbm * ~Tbo;
120 | Tom.header.frame_id = ros_parent_frame_;
121 | Tom.header.stamp = Tbo.header.stamp; // what time to use? I think it should be the odom time since we are correcting it
122 | Tom.child_frame_id = ros_odom_frame_;
123 |
124 | tf2::Transform Tbm_tf;
125 | tf2::fromMsg(Tbm.transform, Tbm_tf);
126 |
127 | tf2::Transform Tbo_tf;
128 | tf2::fromMsg(Tbo.transform, Tbo_tf);
129 |
130 | tf2::Transform Tom_tf = Tbm_tf * Tbo_tf.inverse();
131 | tf2::toMsg(Tom_tf, Tom.transform);
132 |
133 | // send T odom -> map as correction of odom only
134 |
135 | tf_broadcaster_->sendTransform(Tom);
136 | } else {
137 | // if odom doesnt exist, send T base -> map
138 | Tbm.header.frame_id = ros_parent_frame_;
139 | Tbm.child_frame_id = ros_child_frame_;
140 | tf_broadcaster_->sendTransform(Tbm);
141 | }
142 | }
143 | }
144 | }
145 | }
146 |
147 |
148 | std::string gz_parent_frame_;
149 | std::string gz_child_frame_;
150 | std::string ros_parent_frame_;
151 | std::string ros_child_frame_;
152 |
153 | // frame to skip
154 | std::string ros_odom_frame_;
155 | bool skip_odom_frame_;
156 |
157 | // TF stuff
158 | std::unique_ptr tf_broadcaster_;
159 | std::shared_ptr tf_listener_{nullptr};
160 | std::unique_ptr tf_buffer_;
161 |
162 | rclcpp::Subscription::SharedPtr sub_tf_;
163 |
164 | };
165 |
166 | } // namespace mesh_navigation_tutorials_sim
167 |
168 | #include "rclcpp_components/register_node_macro.hpp"
169 | RCLCPP_COMPONENTS_REGISTER_NODE(mesh_navigation_tutorials_sim::GroundTruthLocalizationNode)
170 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/urdf/ceres.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
153 |
154 |
155 |
156 |
157 |
158 |
159 |
164 |
165 |
166 |
167 |
168 |
169 |
170 |
171 |
172 |
173 |
174 |
175 |
176 |
177 | 1
178 | 100
179 | false
180 | /model/robot/imu
181 | imu
182 | imu
183 | imu
184 |
185 |
186 |
187 |
188 | "
189 | 0 0 0 0 0 0
190 | /model/robot/scan
191 | 10
192 |
193 |
194 |
195 | 270
196 | 1
197 | -2.356194
198 | 2.356194
199 |
200 |
201 | 1
202 | 0.01
203 | 0
204 | 0
205 |
206 |
207 |
208 | 0.08
209 | 15.0
210 | 0.01
211 |
212 |
213 | 1
214 | true
215 | laser2d
216 | laser2d
217 | laser2d
218 |
219 |
220 |
221 |
222 | "
223 | 0 0 0 0 0 0
224 | /model/robot/cloud
225 | 10
226 |
227 |
228 |
229 | 128
230 | 0.01
231 | ${-M_PI}
232 | ${M_PI}
233 |
234 |
235 | 32
236 | 0.01
237 | ${-M_PI / 16.0}
238 | ${M_PI / 4.0}
239 |
240 |
241 |
242 | 0.2
243 | 100.0
244 | 0.01
245 |
246 |
247 | 1
248 | true
249 | laser3d
250 | laser3d
251 | laser3d
252 |
253 |
254 |
255 |
256 |
259 |
260 | 2
261 |
262 | left_front_wheel
263 | right_front_wheel
264 | ${axis_length}
265 | ${wheel_radius}
266 |
267 |
268 | left_rear_wheel
269 | right_rear_wheel
270 | ${axis_length}
271 | ${wheel_radius}
272 |
273 | 50
274 | odom
275 | base_footprint
276 | /model/robot/tf_odom
277 |
278 |
279 |
280 |
281 |
284 | right_front_wheel
285 | /model/robot/joint_states
286 |
287 |
288 |
291 | left_front_wheel
292 | /model/robot/joint_states
293 |
294 |
295 |
298 | right_rear_wheel
299 | /model/robot/joint_states
300 |
301 |
302 |
305 | left_rear_wheel
306 | /model/robot/joint_states
307 |
308 |
309 |
310 |
311 |
312 |
315 | true
316 | true
317 | true
318 |
319 |
320 |
321 |
322 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/urdf/common.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
67 |
68 |
69 |
70 |
71 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/urdf/wheel.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
33 |
34 | Gazebo/DarkGrey
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/worlds/floor_is_lava.sdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | 0.001
6 | 1.0
7 |
8 |
9 |
12 |
13 |
16 | ogre2
17 |
18 |
21 |
22 |
25 |
26 |
29 |
30 |
31 |
32 | true
33 | 0 0 10 0 0 0
34 | 1 1 1 1
35 | 0.5 0.5 0.5 1
36 |
37 | 1000
38 | 0.9
39 | 0.01
40 | 0.001
41 |
42 | -0.5 0.1 -0.9
43 |
44 |
45 |
46 | model://floor_is_lava
47 |
48 |
49 |
50 | false
51 |
52 |
53 |
54 |
55 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/worlds/parking_garage.sdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | 0.001
6 | 1.0
7 |
8 |
9 |
12 |
13 |
16 | ogre2
17 |
18 |
21 |
22 |
25 |
26 |
29 |
30 |
31 |
32 | true
33 | 0 0 10 0 0 0
34 | 1 1 1 1
35 | 0.5 0.5 0.5 1
36 |
37 | 1000
38 | 0.9
39 | 0.01
40 | 0.001
41 |
42 | -0.5 0.1 -0.9
43 |
44 |
45 |
46 | model://parking_garage
47 |
48 |
49 |
50 | false
51 |
52 |
53 |
54 |
55 |
--------------------------------------------------------------------------------
/mesh_navigation_tutorials_sim/worlds/tray.sdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | 0.001
6 | 1.0
7 |
8 |
9 |
12 |
13 |
16 | ogre2
17 |
18 |
21 |
22 |
25 |
26 |
29 |
30 |
31 |
32 | true
33 | 0 0 10 0 0 0
34 | 1 1 1 1
35 | 0.5 0.5 0.5 1
36 |
37 | 1000
38 | 0.9
39 | 0.01
40 | 0.001
41 |
42 | -0.5 0.1 -0.9
43 |
44 |
45 |
46 | model://tray
47 |
48 |
49 |
50 | false
51 |
52 |
53 |
54 |
55 |
--------------------------------------------------------------------------------
/pyproject.toml:
--------------------------------------------------------------------------------
1 | [tool.ruff]
2 | line-length = 99
3 |
4 | target-version = "py310"
5 |
6 | [tool.ruff.lint]
7 | select = ["E", "W", "F"]
8 | ignore = []
9 |
--------------------------------------------------------------------------------
/source_dependencies.yaml:
--------------------------------------------------------------------------------
1 | # Every repository listed here will get cloned and built during CI runs.
2 | # Use this for repositories that cannot be installed via rosdep.
3 | repositories:
4 | lvr2:
5 | type: git
6 | url: https://github.com/uos/lvr2.git
7 | version: main
8 | mesh_tools:
9 | type: git
10 | url: https://github.com/naturerobots/mesh_tools.git
11 | version: main
12 | mesh_navigation:
13 | type: git
14 | url: https://github.com/naturerobots/mesh_navigation.git
15 | version: main
16 | move_base_flex:
17 | type: git
18 | url: https://github.com/naturerobots/move_base_flex.git
19 | version: humble
20 |
--------------------------------------------------------------------------------