├── resource
└── vacuumcleaner
├── vacuumcleaner
├── __init__.py
└── spawn_entity.py
├── setup.cfg
├── package.xml
├── README.md
├── launch
├── launch_slam.py
├── launch_main.py
└── launch_nav2.py
├── setup.py
├── config
├── slam.yaml
├── nav2.yaml
└── rviz.rviz
└── models
├── robot.xacro
└── worlds
├── square_2m
└── square
/resource/vacuumcleaner:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/vacuumcleaner/__init__.py:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/setup.cfg:
--------------------------------------------------------------------------------
1 | [develop]
2 | script-dir=$base/lib/vacuumcleaner
3 | [install]
4 | install-scripts=$base/lib/vacuumcleaner
5 |
--------------------------------------------------------------------------------
/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | vacuumcleaner
5 | 0.0.0
6 | TODO: Package description
7 | william
8 | TODO: License declaration
9 |
10 | ament_copyright
11 | ament_flake8
12 | ament_pep257
13 | python3-pytest
14 |
15 |
16 | ament_python
17 |
18 | joint_state_publisher
19 |
20 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # Vacuum cleaner robot
2 |
3 |
4 |
5 | ## Brief
6 |
7 | Scan data of a LIDAR is combined with odometry provided by the differential drive to implement a SLAM capable platform.
8 |
9 | The resulting map is used by an online coverage algorithm to plan a route.
10 |
11 |
12 |
13 | ## How to build
14 |
15 | ## How to run
16 |
17 | * Start default planning algorithm in default room: roslaunch vacuumcleaner simulation.launch robot_radius:=X spiral_delta_denominator:=Y
18 |
19 |
20 |
21 | ### launch file parameters
22 |
23 | robot_radius: mandatory -> radius of body disk and unit is meters
24 |
25 | spiral_delta_denominator: mandatory -> cfr planning algorithm. Subsequent goal points for stage 1 spiral planning lay
26 |
radians apart.
--------------------------------------------------------------------------------
/launch/launch_slam.py:
--------------------------------------------------------------------------------
1 | from launch import LaunchDescription
2 | from launch.actions import DeclareLaunchArgument
3 | from launch.substitutions import LaunchConfiguration
4 | from launch_ros.actions import Node
5 | from ament_index_python.packages import get_package_share_directory
6 |
7 |
8 | def generate_launch_description():
9 | use_sim_time = LaunchConfiguration('use_sim_time')
10 |
11 | declare_use_sim_time_argument = DeclareLaunchArgument(
12 | 'use_sim_time',
13 | default_value='true',
14 | description='Use simulation/Gazebo clock')
15 |
16 | start_async_slam_toolbox_node = Node(
17 | parameters=[
18 | get_package_share_directory("vacuumcleaner") + '/slam.yaml',
19 | {'use_sim_time': use_sim_time}
20 | ],
21 | package='slam_toolbox',
22 | node_executable='async_slam_toolbox_node',
23 | name='slam_toolbox',
24 | output='screen')
25 |
26 | ld = LaunchDescription()
27 |
28 | ld.add_action(declare_use_sim_time_argument)
29 | ld.add_action(start_async_slam_toolbox_node)
30 |
31 | return ld
32 |
--------------------------------------------------------------------------------
/setup.py:
--------------------------------------------------------------------------------
1 | from setuptools import setup
2 | from glob import glob
3 | package_name = 'vacuumcleaner'
4 |
5 | setup(
6 | name=package_name,
7 | version='0.0.0',
8 | packages=[package_name],
9 | data_files=[
10 | ('share/ament_index/resource_index/packages',
11 | ['resource/' + package_name]),
12 | ('share/' + package_name, ['package.xml']),
13 | ('share/' + package_name, glob('launch/launch_main.py')),
14 | ('share/' + package_name, glob('launch/launch_slam.py')),
15 | ('share/' + package_name, glob('launch/launch_nav2.py')),
16 | ('share/' + package_name, glob('config/slam.yaml')),
17 | ('share/' + package_name, glob('config/nav2.yaml')),
18 | ('share/' + package_name, glob('config/rviz.rviz')),
19 | ('share/' + package_name, glob('models/robot.xacro')),
20 | ('share/' + package_name, glob('models/worlds/square_2m'))
21 | ],
22 | install_requires=['setuptools'],
23 | zip_safe=True,
24 | maintainer='william',
25 | maintainer_email='william@todo.todo',
26 | description='TODO: Package description',
27 | license='TODO: License declaration',
28 | tests_require=['pytest'],
29 | entry_points={
30 | 'console_scripts': [
31 | 'spawn_entity = vacuumcleaner.spawn_entity:main'
32 | ],
33 | },
34 | )
35 |
--------------------------------------------------------------------------------
/vacuumcleaner/spawn_entity.py:
--------------------------------------------------------------------------------
1 | # https://answers.ros.org/question/314607/spawn-model-with-ros2-gazebo/
2 | import os
3 | import sys
4 | import rclpy
5 | from ament_index_python.packages import get_package_share_directory
6 | from gazebo_msgs.srv import SpawnEntity
7 |
8 | # arg O = x
9 | # arg 1 = y
10 | # arg 2 = z
11 | def main():
12 |
13 | argv = sys.argv[1:]
14 |
15 | # Start node
16 | rclpy.init()
17 | node = rclpy.create_node("entity_spawner")
18 | node.get_logger().info('Creating Service client to connect to `/spawn_entity`')
19 |
20 | client = node.create_client(SpawnEntity, "/spawn_entity")
21 | node.get_logger().info("Connecting to `/spawn_entity` service...")
22 |
23 | if not client.service_is_ready():
24 | client.wait_for_service()
25 | node.get_logger().info("...connected!")
26 |
27 | sdf_file_path = os.path.join(get_package_share_directory("vacuumcleaner"), "robot.urdf")
28 |
29 | # Set data for request
30 | request = SpawnEntity.Request()
31 | request.name = "spawn entity"
32 | request.xml = open(sdf_file_path, 'r').read()
33 | request.initial_pose.position.x = float(argv[0])
34 | request.initial_pose.position.y = float(argv[1])
35 | request.initial_pose.position.z = float(argv[2])
36 |
37 | node.get_logger().info("Sending service request to `/spawn_entity`")
38 | future = client.call_async(request)
39 | rclpy.spin_until_future_complete(node, future)
40 | if future.result() is not None:
41 | print('response: %r' % future.result())
42 | else:
43 | raise RuntimeError('exception while calling service: %r' % future.exception())
44 |
45 | node.get_logger().info("Done! Shutting down node.")
46 | node.destroy_node()
47 | rclpy.shutdown()
48 |
49 |
50 | if __name__ == "__main__":
51 | main()
--------------------------------------------------------------------------------
/config/slam.yaml:
--------------------------------------------------------------------------------
1 | slam_toolbox:
2 | ros__parameters:
3 |
4 | # Plugin params
5 | solver_plugin: solver_plugins::CeresSolver
6 | ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
7 | ceres_preconditioner: SCHUR_JACOBI
8 | ceres_trust_strategy: LEVENBERG_MARQUARDT
9 | ceres_dogleg_type: TRADITIONAL_DOGLEG
10 | ceres_loss_function: None
11 |
12 | # ROS Parameters
13 | odom_frame: odom
14 | map_frame: map
15 | base_frame: scan_link
16 | scan_topic: /scan
17 | mode: mapping #localization
18 |
19 | # if you'd like to immediately start continuing a map at a given pose
20 | # or at the dock, but they are mutually exclusive, if pose is given
21 | # will use pose
22 | #map_file_name: test_steve
23 | # map_start_pose: [0.0, 0.0, 0.0]
24 | #map_start_at_dock: true
25 |
26 | debug_logging: false
27 | throttle_scans: 1
28 | transform_publish_period: 0.02 #if 0 never publishes odometry
29 | map_update_interval: 5.0
30 | resolution: 0.05
31 | max_laser_range: 4.0 #for rastering images
32 | minimum_time_interval: 0.5
33 | transform_timeout: 0.2
34 | tf_buffer_duration: 30.
35 | stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
36 | enable_interactive_mode: false
37 |
38 | # General Parameters
39 | use_scan_matching: true
40 | use_scan_barycenter: true
41 | minimum_travel_distance: 0.5
42 | minimum_travel_heading: 0.5
43 | scan_buffer_size: 10
44 | scan_buffer_maximum_scan_distance: 10.0
45 | link_match_minimum_response_fine: 0.1
46 | link_scan_maximum_distance: 1.5
47 | loop_search_maximum_distance: 3.0
48 | do_loop_closing: true
49 | loop_match_minimum_chain_size: 10
50 | loop_match_maximum_variance_coarse: 3.0
51 | loop_match_minimum_response_coarse: 0.35
52 | loop_match_minimum_response_fine: 0.45
53 |
54 | # Correlation Parameters - Correlation Parameters
55 | correlation_search_space_dimension: 0.5
56 | correlation_search_space_resolution: 0.01
57 | correlation_search_space_smear_deviation: 0.1
58 |
59 | # Correlation Parameters - Loop Closure Parameters
60 | loop_search_space_dimension: 8.0
61 | loop_search_space_resolution: 0.05
62 | loop_search_space_smear_deviation: 0.03
63 |
64 | # Scan Matcher Parameters
65 | distance_variance_penalty: 0.5
66 | angle_variance_penalty: 1.0
67 |
68 | fine_search_angle_offset: 0.00349
69 | coarse_search_angle_offset: 0.349
70 | coarse_angle_resolution: 0.0349
71 | minimum_angle_penalty: 0.9
72 | minimum_distance_penalty: 0.5
73 | use_response_expansion: true
74 |
--------------------------------------------------------------------------------
/launch/launch_main.py:
--------------------------------------------------------------------------------
1 | from launch import LaunchDescription
2 | from launch.actions import DeclareLaunchArgument
3 | from launch.actions import IncludeLaunchDescription
4 | from launch.conditions import IfCondition
5 | from launch.launch_description_sources import PythonLaunchDescriptionSource
6 | from launch.substitutions import LaunchConfiguration
7 | from ament_index_python.packages import get_package_share_directory
8 | from launch_ros.actions import Node
9 |
10 |
11 | # https://github.com/bponsler/xacro
12 | def xacro_to_urdf(xacro_name, urdf_name):
13 | from xacro import process_file, open_output
14 | doc = process_file(get_package_share_directory("vacuumcleaner")+'/'+xacro_name)
15 | out = open_output(get_package_share_directory("vacuumcleaner")+'/'+urdf_name)
16 | out.write(doc.toprettyxml(indent=' '))
17 |
18 |
19 | def file_get_contents(filename):
20 | with open(filename) as f:
21 | return f.read()
22 |
23 |
24 | def generate_launch_description():
25 | xacro_to_urdf("robot.xacro", "robot.urdf")
26 | nav2_launchfile = IncludeLaunchDescription(
27 | PythonLaunchDescriptionSource([get_package_share_directory("vacuumcleaner"), '/launch_nav2.py']),
28 | launch_arguments={'use_sim_time': 'True'}.items()
29 | )
30 | slam_launchfile = IncludeLaunchDescription(
31 | PythonLaunchDescriptionSource([get_package_share_directory("vacuumcleaner"), '/launch_slam.py']),
32 | )
33 | model_path = file_get_contents(get_package_share_directory("vacuumcleaner")+"/robot.urdf")
34 | rviz_path = get_package_share_directory("vacuumcleaner") + "/rviz.rviz"
35 | print("using rviz file: "+ rviz_path)
36 | state_publisher_node = Node(
37 | package='robot_state_publisher',
38 | executable='robot_state_publisher',
39 | name='robot_state_publisher',
40 | output='screen',
41 | parameters=[{'use_tf_static': False,
42 | 'use_sim_time': True,
43 | 'robot_description': model_path}],
44 | remappings=[('/joint_states', '/vacuumcleaner/joint_states')])
45 |
46 | return LaunchDescription([
47 | DeclareLaunchArgument('simulation',
48 | default_value="false",
49 | description='Use gazebo to simulate robot i.s.o. physical robot. Requires "gazebo_ros" '
50 | 'ros package to be installed. Supply world file using "world:="'),
51 | nav2_launchfile,
52 | state_publisher_node,
53 | IncludeLaunchDescription(
54 | PythonLaunchDescriptionSource([get_package_share_directory("gazebo_ros"), '/launch/gazebo.launch.py']),
55 | condition=IfCondition(LaunchConfiguration('simulation')),
56 | launch_arguments=[("world",[get_package_share_directory("vacuumcleaner"), '/', LaunchConfiguration('world')])] #"/home/william/ros_ws/src/vacuumcleaner/models/worlds/square_2m"
57 | ),
58 | Node(executable='rviz2', package='rviz2', arguments=['-d'+rviz_path]),
59 | Node(package="vacuumcleaner", executable="spawn_entity", arguments=["0.0", "0.0", "0.0"]),
60 | slam_launchfile,
61 | ])
--------------------------------------------------------------------------------
/launch/launch_nav2.py:
--------------------------------------------------------------------------------
1 | # Copyright (c) 2018 Intel Corporation
2 | #
3 | # Licensed under the Apache License, Version 2.0 (the "License");
4 | # you may not use this file except in compliance with the License.
5 | # You may obtain a copy of the License at
6 | #
7 | # http://www.apache.org/licenses/LICENSE-2.0
8 | #
9 | # Unless required by applicable law or agreed to in writing, software
10 | # distributed under the License is distributed on an "AS IS" BASIS,
11 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | # See the License for the specific language governing permissions and
13 | # limitations under the License.
14 |
15 | import os
16 |
17 | from ament_index_python.packages import get_package_share_directory
18 |
19 | from launch import LaunchDescription
20 | from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
21 | from launch.substitutions import LaunchConfiguration
22 | from launch_ros.actions import Node
23 | from nav2_common.launch import RewrittenYaml
24 |
25 |
26 | def generate_launch_description():
27 | # Get the launch directory
28 | bringup_dir = get_package_share_directory('vacuumcleaner')
29 |
30 | namespace = LaunchConfiguration('namespace')
31 | use_sim_time = LaunchConfiguration('use_sim_time')
32 | autostart = LaunchConfiguration('autostart')
33 | params_file = LaunchConfiguration('params_file')
34 | default_bt_xml_filename = LaunchConfiguration('default_bt_xml_filename')
35 | map_subscribe_transient_local = LaunchConfiguration('map_subscribe_transient_local')
36 |
37 | lifecycle_nodes = ['controller_server',
38 | 'planner_server',
39 | 'recoveries_server',
40 | 'bt_navigator',
41 | 'waypoint_follower']
42 |
43 | # Map fully qualified names to relative ones so the node's namespace can be prepended.
44 | # In case of the transforms (tf), currently, there doesn't seem to be a better alternative
45 | # https://github.com/ros/geometry2/issues/32
46 | # https://github.com/ros/robot_state_publisher/pull/30
47 | # TODO(orduno) Substitute with `PushNodeRemapping`
48 | # https://github.com/ros2/launch_ros/issues/56
49 | remappings = [('/tf', 'tf'),
50 | ('/tf_static', 'tf_static')]
51 |
52 | # Create our own temporary YAML files that include substitutions
53 | param_substitutions = {
54 | 'use_sim_time': use_sim_time,
55 | 'default_bt_xml_filename': default_bt_xml_filename,
56 | 'autostart': autostart,
57 | 'map_subscribe_transient_local': map_subscribe_transient_local}
58 |
59 | configured_params = RewrittenYaml(
60 | source_file=params_file,
61 | root_key=namespace,
62 | param_rewrites=param_substitutions,
63 | convert_types=True)
64 |
65 | return LaunchDescription([
66 | # Set env var to print messages to stdout immediately
67 | SetEnvironmentVariable('RCUTILS_LOGGING_BUFFERED_STREAM', '1'),
68 |
69 | DeclareLaunchArgument(
70 | 'namespace', default_value='',
71 | description='Top-level namespace'),
72 |
73 | DeclareLaunchArgument(
74 | 'use_sim_time', default_value='false',
75 | description='Use simulation (Gazebo) clock if true'),
76 |
77 | DeclareLaunchArgument(
78 | 'autostart', default_value='true',
79 | description='Automatically startup the nav2 stack'),
80 |
81 | DeclareLaunchArgument(
82 | 'params_file',
83 | default_value=os.path.join(bringup_dir, 'nav2.yaml'),
84 | description='Full path to the ROS2 parameters file to use'),
85 |
86 | DeclareLaunchArgument(
87 | 'default_bt_xml_filename',
88 | default_value=os.path.join(
89 | get_package_share_directory('nav2_bt_navigator'),
90 | 'behavior_trees', 'navigate_w_replanning_and_recovery.xml'),
91 | description='Full path to the behavior tree xml file to use'),
92 |
93 | DeclareLaunchArgument(
94 | 'map_subscribe_transient_local', default_value='false',
95 | description='Whether to set the map subscriber QoS to transient local'),
96 |
97 | Node(
98 | package='nav2_controller',
99 | executable='controller_server',
100 | output='screen',
101 | parameters=[configured_params],
102 | remappings=remappings),
103 |
104 | Node(
105 | package='nav2_planner',
106 | executable='planner_server',
107 | name='planner_server',
108 | output='screen',
109 | parameters=[configured_params],
110 | remappings=remappings),
111 |
112 | Node(
113 | package='nav2_recoveries',
114 | executable='recoveries_server',
115 | name='recoveries_server',
116 | output='screen',
117 | parameters=[configured_params],
118 | remappings=remappings),
119 |
120 | Node(
121 | package='nav2_bt_navigator',
122 | executable='bt_navigator',
123 | name='bt_navigator',
124 | output='screen',
125 | parameters=[configured_params],
126 | remappings=remappings),
127 |
128 | Node(
129 | package='nav2_waypoint_follower',
130 | executable='waypoint_follower',
131 | name='waypoint_follower',
132 | output='screen',
133 | parameters=[configured_params],
134 | remappings=remappings),
135 |
136 | Node(
137 | package='nav2_lifecycle_manager',
138 | executable='lifecycle_manager',
139 | name='lifecycle_manager_navigation',
140 | output='screen',
141 | parameters=[{'use_sim_time': use_sim_time},
142 | {'autostart': autostart},
143 | {'node_names': lifecycle_nodes}]),
144 |
145 | ])
146 |
--------------------------------------------------------------------------------
/models/robot.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 | 1000000.0
47 | 100.0
48 | 1.0
49 | 1.0
50 | 1 0 0
51 | 1.0
52 | 0.00
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 | 1000000.0
120 | 100.0
121 | 0
122 | 0
123 | 1 0 0
124 | 1.0
125 | 0.00
126 | Gazebo/ZincYellow
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 | na
138 | 30
139 | joint_left_wheel
140 | joint_right_wheel
141 | ${2*$(arg body_radius)}
142 | 0.066
143 | 5
144 | /cmd_vel
145 | true
146 | true
147 | false
148 | odom
149 | 1.0
150 | odom
151 | virtual_base_link
152 |
153 |
154 |
155 |
156 |
157 | --remap ~/out:=joint_states
158 |
159 | 30
160 | joint_left_wheel
161 | joint_right_wheel
162 |
163 |
164 |
165 |
166 |
167 |
168 |
169 |
170 |
171 |
172 |
173 |
174 |
175 |
176 |
177 |
178 |
179 |
182 |
183 |
184 |
185 |
186 |
187 |
188 |
189 |
190 |
191 |
192 | true
193 | true
194 | 5
195 |
196 |
197 |
198 | 180
199 | 0.000000
200 | 6.28318530718
201 |
202 |
203 |
204 | 0.120000
205 | 4
206 |
207 |
208 | gaussian
209 | 0.0
210 | 0.0
211 |
212 |
213 |
214 |
215 | ~/out:=/scan
216 |
217 | sensor_msgs/LaserScan
218 | scan_link
219 |
220 |
221 |
222 |
--------------------------------------------------------------------------------
/config/nav2.yaml:
--------------------------------------------------------------------------------
1 | amcl:
2 | ros__parameters:
3 | use_sim_time: True
4 | alpha1: 0.2
5 | alpha2: 0.2
6 | alpha3: 0.2
7 | alpha4: 0.2
8 | alpha5: 0.2
9 | base_frame_id: "base_link"
10 | beam_skip_distance: 0.5
11 | beam_skip_error_threshold: 0.9
12 | beam_skip_threshold: 0.3
13 | do_beamskip: false
14 | global_frame_id: "map"
15 | lambda_short: 0.1
16 | laser_likelihood_max_dist: 2.0
17 | laser_max_range: 100.0
18 | laser_min_range: -1.0
19 | laser_model_type: "likelihood_field"
20 | max_beams: 60
21 | max_particles: 2000
22 | min_particles: 500
23 | odom_frame_id: "odom"
24 | pf_err: 0.05
25 | pf_z: 0.99
26 | recovery_alpha_fast: 0.0
27 | recovery_alpha_slow: 0.0
28 | resample_interval: 1
29 | robot_model_type: "differential"
30 | save_pose_rate: 0.5
31 | sigma_hit: 0.2
32 | tf_broadcast: true
33 | transform_tolerance: 1.0
34 | update_min_a: 0.2
35 | update_min_d: 0.25
36 | z_hit: 0.5
37 | z_max: 0.05
38 | z_rand: 0.5
39 | z_short: 0.05
40 | scan_topic: scan
41 |
42 | amcl_map_client:
43 | ros__parameters:
44 | use_sim_time: True
45 |
46 | amcl_rclcpp_node:
47 | ros__parameters:
48 | use_sim_time: True
49 |
50 | bt_navigator:
51 | ros__parameters:
52 | use_sim_time: True
53 | global_frame: map
54 | robot_base_frame: base_link
55 | odom_topic: /odom
56 | enable_groot_monitoring: True
57 | groot_zmq_publisher_port: 1666
58 | groot_zmq_server_port: 1667
59 | default_bt_xml_filename: "navigate_w_replanning_and_recovery.xml"
60 | plugin_lib_names:
61 | - nav2_compute_path_to_pose_action_bt_node
62 | - nav2_follow_path_action_bt_node
63 | - nav2_back_up_action_bt_node
64 | - nav2_spin_action_bt_node
65 | - nav2_wait_action_bt_node
66 | - nav2_clear_costmap_service_bt_node
67 | - nav2_is_stuck_condition_bt_node
68 | - nav2_goal_reached_condition_bt_node
69 | - nav2_goal_updated_condition_bt_node
70 | - nav2_initial_pose_received_condition_bt_node
71 | - nav2_reinitialize_global_localization_service_bt_node
72 | - nav2_rate_controller_bt_node
73 | - nav2_distance_controller_bt_node
74 | - nav2_speed_controller_bt_node
75 | - nav2_truncate_path_action_bt_node
76 | - nav2_goal_updater_node_bt_node
77 | - nav2_recovery_node_bt_node
78 | - nav2_pipeline_sequence_bt_node
79 | - nav2_round_robin_node_bt_node
80 | - nav2_transform_available_condition_bt_node
81 | - nav2_time_expired_condition_bt_node
82 | - nav2_distance_traveled_condition_bt_node
83 |
84 | bt_navigator_rclcpp_node:
85 | ros__parameters:
86 | use_sim_time: True
87 |
88 | controller_server:
89 | ros__parameters:
90 | use_sim_time: True
91 | controller_frequency: 20.0
92 | min_x_velocity_threshold: 0.001
93 | min_y_velocity_threshold: 0.5
94 | min_theta_velocity_threshold: 0.001
95 | progress_checker_plugin: "progress_checker"
96 | goal_checker_plugin: "goal_checker"
97 | controller_plugins: ["FollowPath"]
98 |
99 | # Progress checker parameters
100 | progress_checker:
101 | plugin: "nav2_controller::SimpleProgressChecker"
102 | required_movement_radius: 0.5
103 | movement_time_allowance: 10.0
104 | # Goal checker parameters
105 | goal_checker:
106 | plugin: "nav2_controller::SimpleGoalChecker"
107 | xy_goal_tolerance: 0.05
108 | yaw_goal_tolerance: 6.28
109 | stateful: True
110 | # DWB parameters
111 | FollowPath:
112 | plugin: "dwb_core::DWBLocalPlanner"
113 | debug_trajectory_details: True
114 | min_vel_x: -0.26
115 | min_vel_y: 0.0
116 | max_vel_x: 0.26
117 | max_vel_y: 0.0
118 | max_vel_theta: 1.0
119 | min_speed_xy: -0.26
120 | max_speed_xy: 0.26
121 | min_speed_theta: 0.0
122 | # Add high threshold velocity for turtlebot 3 issue.
123 | # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
124 | acc_lim_x: 1.0
125 | acc_lim_y: 0.0
126 | acc_lim_theta: 1.0
127 | decel_lim_x: -1.0
128 | decel_lim_y: 0.0
129 | decel_lim_theta: -1.0
130 | vx_samples: 20
131 | vy_samples: 5
132 | vtheta_samples: 20
133 | sim_time: 1.7
134 | linear_granularity: 0.05
135 | angular_granularity: 0.025
136 | transform_tolerance: 0.2
137 | xy_goal_tolerance: 0.05
138 | yaw_goal_tolerance: 6.28
139 | trans_stopped_velocity: 0.25
140 | short_circuit_trajectory_evaluation: True
141 | stateful: True
142 | critics: ["RotateToGoal", "Oscillation", "BaseObstacle", "GoalAlign", "PathAlign", "PathDist", "GoalDist"]
143 | BaseObstacle.scale: 0.02
144 | PathAlign.scale: 32.0
145 | PathAlign.forward_point_distance: 0.1
146 | GoalAlign.scale: 24.0
147 | GoalAlign.forward_point_distance: 0.1
148 | PathDist.scale: 32.0
149 | GoalDist.scale: 24.0
150 | RotateToGoal.scale: 32.0
151 | RotateToGoal.slowing_factor: 5.0
152 | RotateToGoal.lookahead_time: -1.0
153 |
154 | controller_server_rclcpp_node:
155 | ros__parameters:
156 | use_sim_time: True
157 |
158 | local_costmap:
159 | local_costmap:
160 | ros__parameters:
161 | update_frequency: 5.0
162 | publish_frequency: 2.0
163 | global_frame: map
164 | robot_base_frame: base_link
165 | use_sim_time: True
166 | rolling_window: true
167 | width: 3
168 | height: 3
169 | resolution: 0.05
170 | robot_radius: 0.1
171 | plugins: ["voxel_layer", "inflation_layer"]
172 | inflation_layer:
173 | plugin: "nav2_costmap_2d::InflationLayer"
174 | cost_scaling_factor: 3.0
175 | inflation_radius: 0.0
176 | voxel_layer:
177 | plugin: "nav2_costmap_2d::VoxelLayer"
178 | enabled: True
179 | publish_voxel_map: True
180 | origin_z: 0.0
181 | z_resolution: 0.05
182 | z_voxels: 16
183 | max_obstacle_height: 2.0
184 | mark_threshold: 0
185 | observation_sources: scan
186 | scan:
187 | topic: /scan
188 | max_obstacle_height: 2.0
189 | clearing: True
190 | marking: True
191 | data_type: "LaserScan"
192 | static_layer:
193 | map_subscribe_transient_local: True
194 | always_send_full_costmap: True
195 | local_costmap_client:
196 | ros__parameters:
197 | use_sim_time: True
198 | local_costmap_rclcpp_node:
199 | ros__parameters:
200 | use_sim_time: True
201 |
202 | global_costmap:
203 | global_costmap:
204 | ros__parameters:
205 | update_frequency: 1.0
206 | publish_frequency: 1.0
207 | global_frame: map
208 | robot_base_frame: base_link
209 | use_sim_time: True
210 | robot_radius: 0.1
211 | resolution: 0.05
212 | track_unknown_space: true
213 | plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
214 | obstacle_layer:
215 | plugin: "nav2_costmap_2d::ObstacleLayer"
216 | enabled: True
217 | observation_sources: scan
218 | scan:
219 | topic: /scan
220 | max_obstacle_height: 2.0
221 | clearing: True
222 | marking: True
223 | data_type: "LaserScan"
224 | static_layer:
225 | plugin: "nav2_costmap_2d::StaticLayer"
226 | map_subscribe_transient_local: True
227 | inflation_layer:
228 | plugin: "nav2_costmap_2d::InflationLayer"
229 | cost_scaling_factor: 3.0
230 | inflation_radius: 0.0
231 | always_send_full_costmap: True
232 | global_costmap_client:
233 | ros__parameters:
234 | use_sim_time: True
235 | global_costmap_rclcpp_node:
236 | ros__parameters:
237 | use_sim_time: True
238 |
239 | map_server:
240 | ros__parameters:
241 | use_sim_time: True
242 | yaml_filename: "turtlebot3_world.yaml"
243 |
244 | map_saver:
245 | ros__parameters:
246 | use_sim_time: True
247 | save_map_timeout: 5000
248 | free_thresh_default: 0.25
249 | occupied_thresh_default: 0.65
250 | map_subscribe_transient_local: False
251 |
252 | planner_server:
253 | ros__parameters:
254 | expected_planner_frequency: 20.0
255 | use_sim_time: True
256 | planner_plugins: ["GridBased"]
257 | GridBased:
258 | plugin: "nav2_navfn_planner/NavfnPlanner"
259 | tolerance: 0.5
260 | use_astar: false
261 | allow_unknown: true
262 |
263 | planner_server_rclcpp_node:
264 | ros__parameters:
265 | use_sim_time: True
266 |
267 | recoveries_server:
268 | ros__parameters:
269 | costmap_topic: local_costmap/costmap_raw
270 | footprint_topic: local_costmap/published_footprint
271 | cycle_frequency: 10.0
272 | recovery_plugins: ["spin", "back_up", "wait"]
273 | spin:
274 | plugin: "nav2_recoveries/Spin"
275 | back_up:
276 | plugin: "nav2_recoveries/BackUp"
277 | wait:
278 | plugin: "nav2_recoveries/Wait"
279 | global_frame: odom
280 | robot_base_frame: base_link
281 | transform_timeout: 0.1
282 | use_sim_time: true
283 | simulate_ahead_time: 2.0
284 | max_rotational_vel: 1.0
285 | min_rotational_vel: 0.4
286 | rotational_acc_lim: 3.2
287 |
288 | robot_state_publisher:
289 | ros__parameters:
290 | use_sim_time: True
--------------------------------------------------------------------------------
/config/rviz.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz_common/Displays
3 | Help Height: 78
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Global Options1
8 | - /Status1
9 | - /TF1/Frames1
10 | - /TF1/Tree1
11 | - /LaserScan1
12 | - /LaserScan1/Topic1
13 | - /Costmaps1
14 | - /Costmaps1/local1
15 | Splitter Ratio: 0.5264706015586853
16 | Tree Height: 784
17 | - Class: rviz_common/Selection
18 | Name: Selection
19 | - Class: rviz_common/Tool Properties
20 | Expanded:
21 | - /2D Goal Pose1
22 | - /Publish Point1
23 | Name: Tool Properties
24 | Splitter Ratio: 0.5886790156364441
25 | - Class: rviz_common/Views
26 | Expanded:
27 | - /Current View1
28 | Name: Views
29 | Splitter Ratio: 0.5
30 | Visualization Manager:
31 | Class: ""
32 | Displays:
33 | - Alpha: 0.5
34 | Cell Size: 1
35 | Class: rviz_default_plugins/Grid
36 | Color: 160; 160; 164
37 | Enabled: true
38 | Line Style:
39 | Line Width: 0.029999999329447746
40 | Value: Lines
41 | Name: Grid
42 | Normal Cell Count: 0
43 | Offset:
44 | X: 0
45 | Y: 0
46 | Z: 0
47 | Plane: XY
48 | Plane Cell Count: 10
49 | Reference Frame:
50 | Value: true
51 | - Class: rviz_default_plugins/TF
52 | Enabled: true
53 | Frame Timeout: 15
54 | Frames:
55 | All Enabled: false
56 | base_link:
57 | Value: true
58 | caster_wheel:
59 | Value: false
60 | map:
61 | Value: true
62 | odom:
63 | Value: true
64 | scan_link:
65 | Value: true
66 | virtual_base_link:
67 | Value: true
68 | Marker Scale: 1
69 | Name: TF
70 | Show Arrows: true
71 | Show Axes: true
72 | Show Names: false
73 | Tree:
74 | map:
75 | odom:
76 | virtual_base_link:
77 | base_link:
78 | caster_wheel:
79 | {}
80 | scan_link:
81 | {}
82 | Update Interval: 0
83 | Value: true
84 | - Alpha: 0.699999988079071
85 | Class: rviz_default_plugins/Map
86 | Color Scheme: map
87 | Draw Behind: false
88 | Enabled: false
89 | Name: Map
90 | Topic:
91 | Depth: 5
92 | Durability Policy: Volatile
93 | History Policy: Keep Last
94 | Reliability Policy: Reliable
95 | Value: /map
96 | Update Topic:
97 | Depth: 5
98 | Durability Policy: Volatile
99 | History Policy: Keep Last
100 | Reliability Policy: Reliable
101 | Value: /map_updates
102 | Use Timestamp: false
103 | Value: false
104 | - Alpha: 0.5
105 | Autocompute Intensity Bounds: true
106 | Autocompute Value Bounds:
107 | Max Value: -0.050999999046325684
108 | Min Value: -0.050999999046325684
109 | Value: true
110 | Axis: Z
111 | Channel Name: intensity
112 | Class: rviz_default_plugins/LaserScan
113 | Color: 255; 255; 255
114 | Color Transformer: Intensity
115 | Decay Time: 0
116 | Enabled: true
117 | Invert Rainbow: false
118 | Max Color: 255; 255; 255
119 | Max Intensity: 0
120 | Min Color: 0; 0; 0
121 | Min Intensity: 0
122 | Name: LaserScan
123 | Position Transformer: XYZ
124 | Selectable: true
125 | Size (Pixels): 3
126 | Size (m): 0.009999999776482582
127 | Style: Flat Squares
128 | Topic:
129 | Depth: 5
130 | Durability Policy: Volatile
131 | History Policy: Keep Last
132 | Reliability Policy: Best Effort
133 | Value: /scan
134 | Use Fixed Frame: true
135 | Use rainbow: true
136 | Value: true
137 | - Alpha: 1
138 | Class: rviz_default_plugins/Polygon
139 | Color: 25; 255; 0
140 | Enabled: true
141 | Name: Polygon
142 | Topic:
143 | Depth: 5
144 | Durability Policy: Volatile
145 | History Policy: Keep Last
146 | Reliability Policy: Reliable
147 | Value: /global_costmap/published_footprint
148 | Value: true
149 | - Alpha: 1
150 | Axes Length: 1
151 | Axes Radius: 0.10000000149011612
152 | Class: rviz_default_plugins/Pose
153 | Color: 255; 25; 0
154 | Enabled: true
155 | Head Length: 0.30000001192092896
156 | Head Radius: 0.10000000149011612
157 | Name: Pose
158 | Shaft Length: 1
159 | Shaft Radius: 0.05000000074505806
160 | Shape: Arrow
161 | Topic:
162 | Depth: 5
163 | Durability Policy: Volatile
164 | History Policy: Keep Last
165 | Reliability Policy: Reliable
166 | Value: /goal_pose
167 | Value: true
168 | - Class: rviz_common/Group
169 | Displays:
170 | - Alpha: 0.699999988079071
171 | Class: rviz_default_plugins/Map
172 | Color Scheme: costmap
173 | Draw Behind: false
174 | Enabled: true
175 | Name: local
176 | Topic:
177 | Depth: 5
178 | Durability Policy: Volatile
179 | History Policy: Keep Last
180 | Reliability Policy: Reliable
181 | Value: /local_costmap/costmap
182 | Update Topic:
183 | Depth: 5
184 | Durability Policy: Volatile
185 | History Policy: Keep Last
186 | Reliability Policy: Reliable
187 | Value: /local_costmap/costmap_updates
188 | Use Timestamp: false
189 | Value: true
190 | - Alpha: 0.699999988079071
191 | Class: rviz_default_plugins/Map
192 | Color Scheme: costmap
193 | Draw Behind: false
194 | Enabled: false
195 | Name: global
196 | Topic:
197 | Depth: 5
198 | Durability Policy: Volatile
199 | History Policy: Keep Last
200 | Reliability Policy: Reliable
201 | Value: /global_costmap/costmap
202 | Update Topic:
203 | Depth: 5
204 | Durability Policy: Volatile
205 | History Policy: Keep Last
206 | Reliability Policy: Reliable
207 | Value: /global_costmap/costmap_updates
208 | Use Timestamp: false
209 | Value: false
210 | Enabled: true
211 | Name: Costmaps
212 | - Alpha: 1
213 | Buffer Length: 1
214 | Class: rviz_default_plugins/Path
215 | Color: 25; 255; 0
216 | Enabled: true
217 | Head Diameter: 0.30000001192092896
218 | Head Length: 0.20000000298023224
219 | Length: 0.30000001192092896
220 | Line Style: Lines
221 | Line Width: 0.029999999329447746
222 | Name: local_plan
223 | Offset:
224 | X: 0
225 | Y: 0
226 | Z: 0
227 | Pose Color: 255; 85; 255
228 | Pose Style: None
229 | Radius: 0.029999999329447746
230 | Shaft Diameter: 0.10000000149011612
231 | Shaft Length: 0.10000000149011612
232 | Topic:
233 | Depth: 5
234 | Durability Policy: Volatile
235 | History Policy: Keep Last
236 | Reliability Policy: Reliable
237 | Value: /local_plan
238 | Value: true
239 | - Alpha: 1
240 | Buffer Length: 1
241 | Class: rviz_default_plugins/Path
242 | Color: 25; 255; 0
243 | Enabled: true
244 | Head Diameter: 0.30000001192092896
245 | Head Length: 0.20000000298023224
246 | Length: 0.30000001192092896
247 | Line Style: Lines
248 | Line Width: 0.029999999329447746
249 | Name: Global Plan
250 | Offset:
251 | X: 0
252 | Y: 0
253 | Z: 0
254 | Pose Color: 255; 85; 255
255 | Pose Style: None
256 | Radius: 0.029999999329447746
257 | Shaft Diameter: 0.10000000149011612
258 | Shaft Length: 0.10000000149011612
259 | Topic:
260 | Depth: 5
261 | Durability Policy: Volatile
262 | History Policy: Keep Last
263 | Reliability Policy: Reliable
264 | Value: /received_global_plan
265 | Value: true
266 | Enabled: true
267 | Global Options:
268 | Background Color: 48; 48; 48
269 | Fixed Frame: map
270 | Frame Rate: 30
271 | Name: root
272 | Tools:
273 | - Class: rviz_default_plugins/Interact
274 | Hide Inactive Objects: true
275 | - Class: rviz_default_plugins/MoveCamera
276 | - Class: rviz_default_plugins/Select
277 | - Class: rviz_default_plugins/FocusCamera
278 | - Class: rviz_default_plugins/Measure
279 | Line color: 128; 128; 0
280 | - Class: rviz_default_plugins/SetInitialPose
281 | Topic:
282 | Depth: 5
283 | Durability Policy: Volatile
284 | History Policy: Keep Last
285 | Reliability Policy: Reliable
286 | Value: /initialpose
287 | - Class: rviz_default_plugins/SetGoal
288 | Topic:
289 | Depth: 5
290 | Durability Policy: Volatile
291 | History Policy: Keep Last
292 | Reliability Policy: Reliable
293 | Value: /goal_pose
294 | - Class: rviz_default_plugins/PublishPoint
295 | Single click: true
296 | Topic:
297 | Depth: 5
298 | Durability Policy: Volatile
299 | History Policy: Keep Last
300 | Reliability Policy: Reliable
301 | Value: /clicked_point
302 | Transformation:
303 | Current:
304 | Class: rviz_default_plugins/TF
305 | Value: true
306 | Views:
307 | Current:
308 | Class: rviz_default_plugins/Orbit
309 | Distance: 6.522454261779785
310 | Enable Stereo Rendering:
311 | Stereo Eye Separation: 0.05999999865889549
312 | Stereo Focal Distance: 1
313 | Swap Stereo Eyes: false
314 | Value: false
315 | Focal Point:
316 | X: -0.03556397557258606
317 | Y: 0.5177552103996277
318 | Z: -0.08830908685922623
319 | Focal Shape Fixed Size: true
320 | Focal Shape Size: 0.05000000074505806
321 | Invert Z Axis: false
322 | Name: Current View
323 | Near Clip Distance: 0.009999999776482582
324 | Pitch: 1.2247960567474365
325 | Target Frame:
326 | Value: Orbit (rviz)
327 | Yaw: 5.045467376708984
328 | Saved: ~
329 | Window Geometry:
330 | Displays:
331 | collapsed: true
332 | Height: 1016
333 | Hide Left Dock: true
334 | Hide Right Dock: false
335 | QMainWindow State: 000000ff00000000fd0000000400000000000001fe0000039cfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073000000003e0000039c000000ca00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f0000039cfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003e0000039c000000a600fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000002ab0000039c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
336 | Selection:
337 | collapsed: false
338 | Tool Properties:
339 | collapsed: false
340 | Views:
341 | collapsed: false
342 | Width: 960
343 | X: 960
344 | Y: 27
345 |
--------------------------------------------------------------------------------
/models/worlds/square_2m:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | 1
5 | 0 0 10 0 -0 0
6 | 0.8 0.8 0.8 1
7 | 0.2 0.2 0.2 1
8 |
9 | 1000
10 | 0.9
11 | 0.01
12 | 0.001
13 |
14 | -0.5 0.1 -0.9
15 |
16 |
17 | 1
18 |
19 |
20 |
21 |
22 | 0 0 1
23 | 100 100
24 |
25 |
26 |
27 |
28 |
29 | 100
30 | 50
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 | 10
42 |
43 |
44 | 0
45 |
46 |
47 | 0 0 1
48 | 100 100
49 |
50 |
51 |
52 |
56 |
57 |
58 | 0
59 | 0
60 | 0
61 |
62 |
63 | 0 0 -9.8
64 | 6e-06 2.3e-05 -4.2e-05
65 |
66 |
67 | 0.001
68 | 1
69 | 1000
70 |
71 |
72 | 0.4 0.4 0.4 1
73 | 0.7 0.7 0.7 1
74 | 1
75 |
76 |
79 |
80 |
81 | EARTH_WGS84
82 | 0
83 | 0
84 | 0
85 | 0
86 |
87 |
88 | 391 649000000
89 | 277 111704651
90 | 1593217321 104096233
91 | 274377
92 |
93 | 1.43108 0 0.477249 -0.004218 7e-06 0.001724
94 | 1 0.402019 1
95 |
96 | 1.43108 0 0.477249 -0.004218 7e-06 0.001724
97 | 0 0 0 0 -0 0
98 | 0 0 0 0 -0 0
99 | 0 0 0 0 -0 0
100 |
101 |
102 |
103 | 0.003557 1.49246 0.469184 -7e-06 -0.004218 -1.56907
104 | 1 0.48103 1
105 |
106 | 0.003557 1.49246 0.469184 -7e-06 -0.004218 -1.56907
107 | 0 0 0 0 -0 0
108 | 0 0 0 0 -0 0
109 | 0 0 0 0 -0 0
110 |
111 |
112 |
113 | -1.486 -0.014482 0.47792 -0.004218 7e-06 0.001724
114 | 1 0.494549 1
115 |
116 | -1.486 -0.014482 0.47792 -0.004218 7e-06 0.001724
117 | 0 0 0 0 -0 0
118 | 0 0 0 0 -0 0
119 | 0 0 0 0 -0 0
120 |
121 |
122 |
123 | 0.081658 -1.49076 0.482964 -7e-06 -0.004218 -1.56907
124 | 1 0.463801 1
125 |
126 | 0.081658 -1.49076 0.482964 -7e-06 -0.004218 -1.56907
127 | 0 0 0 0 -0 0
128 | 0 0 0 0 -0 0
129 | 0 0 0 0 -0 0
130 |
131 |
132 |
133 | 0 0 0 0 -0 0
134 | 1 1 1
135 |
136 | 0 0 0 0 -0 0
137 | 0 0 0 0 -0 0
138 | 0 0 0 0 -0 0
139 | 0 0 0 0 -0 0
140 |
141 |
142 |
143 | 0 0 10 0 -0 0
144 |
145 |
146 |
147 |
148 |
149 | 1
150 |
151 | 0.166667
152 | 0
153 | 0
154 | 0.166667
155 | 0
156 | 0.166667
157 |
158 |
159 | 0
160 | 0
161 | 0
162 | 0 0 0 0 -0 0
163 |
164 |
165 |
166 | 1 8 1
167 |
168 |
169 |
170 |
174 |
175 | 0 0 0 0 -0 0
176 | 0
177 | 1
178 |
179 |
180 | 0
181 | 10
182 | 0 0 0 0 -0 0
183 |
184 |
185 | 1 8 1
186 |
187 |
188 |
189 |
190 |
191 | 1
192 | 1
193 | 0 0 0
194 | 0
195 | 0
196 |
197 |
198 | 1
199 | 0
200 | 0
201 | 1
202 |
203 | 0
204 |
205 |
206 |
207 |
208 | 0
209 | 1e+06
210 |
211 |
212 | 0
213 | 1
214 | 1
215 |
216 | 0
217 | 0.2
218 | 1e+13
219 | 1
220 | 0.01
221 | 0
222 |
223 |
224 | 1
225 | -0.01
226 | 0
227 | 0.2
228 | 1e+13
229 | 1
230 |
231 |
232 |
233 |
234 |
235 | 1
236 | 1
237 | 3 -1.95836 0.48315 -0.004218 7e-06 0.001724
238 |
239 |
240 |
241 |
242 | 1
243 |
244 | 0.166667
245 | 0
246 | 0
247 | 0.166667
248 | 0
249 | 0.166667
250 |
251 |
252 | 0
253 | 0
254 | 0
255 | 0 0 0 0 -0 0
256 |
257 |
258 |
259 | 1 8.00002 1
260 |
261 |
262 |
263 |
267 |
268 | 0 0 0 0 -0 0
269 | 0
270 | 1
271 |
272 |
273 | 0
274 | 10
275 | 0 0 0 0 -0 0
276 |
277 |
278 | 1 8.00002 1
279 |
280 |
281 |
282 |
283 |
284 | 1
285 | 1
286 | 0 0 0
287 | 0
288 | 0
289 |
290 |
291 | 1
292 | 0
293 | 0
294 | 1
295 |
296 | 0
297 |
298 |
299 |
300 |
301 | 0
302 | 1e+06
303 |
304 |
305 | 0
306 | 1
307 | 1
308 |
309 | 0
310 | 0.2
311 | 1e+13
312 | 1
313 | 0.01
314 | 0
315 |
316 |
317 | 1
318 | -0.01
319 | 0
320 | 0.2
321 | 1e+13
322 | 1
323 |
324 |
325 |
326 |
327 |
328 | 1
329 | 1
330 | -6.43616 0.426991 0.477245 -0.004218 7e-06 0.001724
331 |
332 |
333 |
334 |
335 | 1
336 |
337 | 0.166667
338 | 0
339 | 0
340 | 0.166667
341 | 0
342 | 0.166667
343 |
344 |
345 | 0
346 | 0
347 | 0
348 | 0 0 0 0 -0 0
349 |
350 |
351 |
352 | 1 8 1
353 |
354 |
355 |
356 |
360 |
361 | 0 0 0 0 -0 0
362 | 0
363 | 1
364 |
365 |
366 | 0
367 | 10
368 | 0 0 0 0 -0 0
369 |
370 |
371 | 1 8 1
372 |
373 |
374 |
375 |
376 |
377 | 1
378 | 1
379 | 0 0 0
380 | 0
381 | 0
382 |
383 |
384 | 1
385 | 0
386 | 0
387 | 1
388 |
389 | 0
390 |
391 |
392 |
393 |
394 | 0
395 | 1e+06
396 |
397 |
398 | 0
399 | 1
400 | 1
401 |
402 | 0
403 | 0.2
404 | 1e+13
405 | 1
406 | 0.01
407 | 0
408 |
409 |
410 | 1
411 | -0.01
412 | 0
413 | 0.2
414 | 1e+13
415 | 1
416 |
417 |
418 |
419 |
420 |
421 | 1
422 | 1
423 | -2.55182 -4.68915 0.48315 -7e-06 -0.004218 -1.56907
424 |
425 |
426 |
427 |
428 | 1
429 |
430 | 0.166667
431 | 0
432 | 0
433 | 0.166667
434 | 0
435 | 0.166667
436 |
437 |
438 | 0
439 | 0
440 | 0
441 | 0 0 0 0 -0 0
442 |
443 |
444 |
445 | 1 8.00001 1
446 |
447 |
448 |
449 |
453 |
454 | 0 0 0 0 -0 0
455 | 0
456 | 1
457 |
458 |
459 | 0
460 | 10
461 | 0 0 0 0 -0 0
462 |
463 |
464 | 1 8.00001 1
465 |
466 |
467 |
468 |
469 |
470 | 1
471 | 1
472 | 0 0 0
473 | 0
474 | 0
475 |
476 |
477 | 1
478 | 0
479 | 0
480 | 1
481 |
482 | 0
483 |
484 |
485 |
486 |
487 | 0
488 | 1e+06
489 |
490 |
491 | 0
492 | 1
493 | 1
494 |
495 | 0
496 | 0.2
497 | 1e+13
498 | 1
499 | 0.01
500 | 0
501 |
502 |
503 | 1
504 | -0.01
505 | 0
506 | 0.2
507 | 1e+13
508 | 1
509 |
510 |
511 |
512 |
513 |
514 | 1
515 | 1
516 | 2.65497 2.91478 0.477245 -0.004218 7e-06 0.001724
517 |
518 |
519 |
520 | 11.0307 -2.08848 20.6368 0 1.05449 2.77623
521 | orbit
522 | perspective
523 |
524 |
525 |
526 |
527 |
--------------------------------------------------------------------------------
/models/worlds/square:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | 0.319654 -0.235002 9.29441 0 1.5138 0.009599
6 | orbit
7 | perspective
8 |
9 |
10 |
11 |
12 | 1000.0
13 | 0.001
14 | 1
15 |
16 |
17 | quick
18 | 500
19 | 0
20 | 1.400000
21 | 1
22 |
23 |
24 | 0.00001
25 | 0.2
26 | 2000.000000
27 | 0.01000
28 |
29 |
30 |
31 |
32 |
33 |
34 | 1
35 | 0 0 10 0 -0 0
36 | 0.8 0.8 0.8 1
37 | 0.2 0.2 0.2 1
38 |
39 | 1000
40 | 0.9
41 | 0.01
42 | 0.001
43 |
44 | -0.5 0.1 -0.9
45 |
46 |
47 | 1
48 |
49 |
50 |
51 |
52 | 0 0 1
53 | 100 100
54 |
55 |
56 |
57 |
58 |
59 | 100
60 | 50
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 | 10
72 |
73 |
74 | 0
75 |
76 |
77 | 0 0 1
78 | 100 100
79 |
80 |
81 |
82 |
86 |
87 |
88 | 0
89 | 0
90 | 0
91 |
92 |
93 | 0 0 -9.8
94 | 6e-06 2.3e-05 -4.2e-05
95 |
96 |
97 | 0.001
98 | 1
99 | 1000
100 |
101 |
102 | 0.4 0.4 0.4 1
103 | 0.7 0.7 0.7 1
104 | 1
105 |
106 |
109 |
110 |
111 | EARTH_WGS84
112 | 0
113 | 0
114 | 0
115 | 0
116 |
117 |
118 | 117 272000000
119 | 118 427623581
120 | 1585253546 474757598
121 | 117272
122 |
123 | 4 0 0.477245 -0.004218 7e-06 0.001724
124 | 1 1 1
125 |
126 | 4 0 0.477245 -0.004218 7e-06 0.001724
127 | 0 0 0 0 -0 0
128 | 0 0 0 0 -0 0
129 | 0 0 0 0 -0 0
130 |
131 |
132 |
133 | 0.000108 3.49068 0.460755 -7e-06 -0.004218 -1.56907
134 | 1 1 1
135 |
136 | 0.000108 3.49068 0.460755 -7e-06 -0.004218 -1.56907
137 | 0 0 0 0 -0 0
138 | 0 0 0 0 -0 0
139 | 0 0 0 0 -0 0
140 |
141 |
142 |
143 | -3.99956 -0.014482 0.47792 -0.004218 7e-06 0.001724
144 | 1 1 1
145 |
146 | -3.99956 -0.014482 0.47792 -0.004218 7e-06 0.001724
147 | 0 0 0 0 -0 0
148 | 0 0 0 0 -0 0
149 | 0 0 0 0 -0 0
150 |
151 |
152 |
153 | 0.085136 -3.50562 0.491463 -7e-06 -0.004218 -1.56907
154 | 1 1 1
155 |
156 | 0.085136 -3.50562 0.491463 -7e-06 -0.004218 -1.56907
157 | 0 0 0 0 -0 0
158 | 0 0 0 0 -0 0
159 | 0 0 0 0 -0 0
160 |
161 |
162 |
163 | 0 0 0 0 -0 0
164 | 1 1 1
165 |
166 | 0 0 0 0 -0 0
167 | 0 0 0 0 -0 0
168 | 0 0 0 0 -0 0
169 | 0 0 0 0 -0 0
170 |
171 |
172 |
173 | 0 0 10 0 -0 0
174 |
175 |
176 |
177 |
178 |
179 | 1
180 |
181 | 0.166667
182 | 0
183 | 0
184 | 0.166667
185 | 0
186 | 0.166667
187 |
188 |
189 | 0
190 | 0
191 | 0
192 | 0 0 0 0 -0 0
193 |
194 |
195 |
196 | 1 8 1
197 |
198 |
199 |
200 |
204 |
205 | 0 0 0 0 -0 0
206 | 0
207 | 1
208 |
209 |
210 | 0
211 | 10
212 | 0 0 0 0 -0 0
213 |
214 |
215 | 1 8 1
216 |
217 |
218 |
219 |
220 |
221 | 1
222 | 1
223 | 0 0 0
224 | 0
225 | 0
226 |
227 |
228 | 1
229 | 0
230 | 0
231 | 1
232 |
233 | 0
234 |
235 |
236 |
237 |
238 | 0
239 | 1e+06
240 |
241 |
242 | 0
243 | 1
244 | 1
245 |
246 | 0
247 | 0.2
248 | 1e+13
249 | 1
250 | 0.01
251 | 0
252 |
253 |
254 | 1
255 | -0.01
256 | 0
257 | 0.2
258 | 1e+13
259 | 1
260 |
261 |
262 |
263 |
264 |
265 | 1
266 | 1
267 | 3 -1.95836 0.48315 -0.004218 7e-06 0.001724
268 |
269 |
270 |
271 |
272 | 1
273 |
274 | 0.166667
275 | 0
276 | 0
277 | 0.166667
278 | 0
279 | 0.166667
280 |
281 |
282 | 0
283 | 0
284 | 0
285 | 0 0 0 0 -0 0
286 |
287 |
288 |
289 | 1 8 1
290 |
291 |
292 |
293 |
297 |
298 | 0 0 0 0 -0 0
299 | 0
300 | 1
301 |
302 |
303 | 0
304 | 10
305 | 0 0 0 0 -0 0
306 |
307 |
308 | 1 8 1
309 |
310 |
311 |
312 |
313 |
314 | 1
315 | 1
316 | 0 0 0
317 | 0
318 | 0
319 |
320 |
321 | 1
322 | 0
323 | 0
324 | 1
325 |
326 | 0
327 |
328 |
329 |
330 |
331 | 0
332 | 1e+06
333 |
334 |
335 | 0
336 | 1
337 | 1
338 |
339 | 0
340 | 0.2
341 | 1e+13
342 | 1
343 | 0.01
344 | 0
345 |
346 |
347 | 1
348 | -0.01
349 | 0
350 | 0.2
351 | 1e+13
352 | 1
353 |
354 |
355 |
356 |
357 |
358 | 1
359 | 1
360 | -6.43616 0.426991 0.477245 -0.004218 7e-06 0.001724
361 |
362 |
363 |
364 |
365 | 1
366 |
367 | 0.166667
368 | 0
369 | 0
370 | 0.166667
371 | 0
372 | 0.166667
373 |
374 |
375 | 0
376 | 0
377 | 0
378 | 0 0 0 0 -0 0
379 |
380 |
381 |
382 | 1 8 1
383 |
384 |
385 |
386 |
390 |
391 | 0 0 0 0 -0 0
392 | 0
393 | 1
394 |
395 |
396 | 0
397 | 10
398 | 0 0 0 0 -0 0
399 |
400 |
401 | 1 8 1
402 |
403 |
404 |
405 |
406 |
407 | 1
408 | 1
409 | 0 0 0
410 | 0
411 | 0
412 |
413 |
414 | 1
415 | 0
416 | 0
417 | 1
418 |
419 | 0
420 |
421 |
422 |
423 |
424 | 0
425 | 1e+06
426 |
427 |
428 | 0
429 | 1
430 | 1
431 |
432 | 0
433 | 0.2
434 | 1e+13
435 | 1
436 | 0.01
437 | 0
438 |
439 |
440 | 1
441 | -0.01
442 | 0
443 | 0.2
444 | 1e+13
445 | 1
446 |
447 |
448 |
449 |
450 |
451 | 1
452 | 1
453 | -2.55182 -4.68915 0.48315 -7e-06 -0.004218 -1.56907
454 |
455 |
456 |
457 |
458 | 1
459 |
460 | 0.166667
461 | 0
462 | 0
463 | 0.166667
464 | 0
465 | 0.166667
466 |
467 |
468 | 0
469 | 0
470 | 0
471 | 0 0 0 0 -0 0
472 |
473 |
474 |
475 | 1 8 1
476 |
477 |
478 |
479 |
483 |
484 | 0 0 0 0 -0 0
485 | 0
486 | 1
487 |
488 |
489 | 0
490 | 10
491 | 0 0 0 0 -0 0
492 |
493 |
494 | 1 8 1
495 |
496 |
497 |
498 |
499 |
500 | 1
501 | 1
502 | 0 0 0
503 | 0
504 | 0
505 |
506 |
507 | 1
508 | 0
509 | 0
510 | 1
511 |
512 | 0
513 |
514 |
515 |
516 |
517 | 0
518 | 1e+06
519 |
520 |
521 | 0
522 | 1
523 | 1
524 |
525 | 0
526 | 0.2
527 | 1e+13
528 | 1
529 | 0.01
530 | 0
531 |
532 |
533 | 1
534 | -0.01
535 | 0
536 | 0.2
537 | 1e+13
538 | 1
539 |
540 |
541 |
542 |
543 |
544 | 1
545 | 1
546 | 2.65497 2.91478 0.477245 -0.004218 7e-06 0.001724
547 |
548 |
549 |
550 | 25.8482 -2.60256 8.54988 0 0.289795 2.90508
551 | orbit
552 | perspective
553 |
554 |
555 |
556 |
557 |
--------------------------------------------------------------------------------