├── .clang-format
├── .pre-commit-config.yaml
├── .yamllint.yaml
├── LICENSE
├── README.md
├── nav_u_dependencies
├── CMakeLists.txt
└── package.xml
├── nav_u_generic_description
├── CMakeLists.txt
├── package.xml
└── urdf
│ └── macros.urdf.xacro
├── nav_u_robot_generator
├── CMakeLists.txt
├── config
│ └── gen.rviz
├── include
│ └── nav_u_robot_generator
│ │ ├── app_widget.hpp
│ │ ├── robot_gen_widget.hpp
│ │ ├── rviz_panel.hpp
│ │ └── templates.hpp
├── launch
│ └── generator.launch.py
├── package.xml
├── src
│ ├── app_widget.cpp
│ ├── main.cpp
│ ├── robot_gen_widget.cpp
│ ├── rviz_panel.cpp
│ └── templates.cpp
└── templates
│ ├── CMakeLists.txt
│ ├── CMakeLists2.txt
│ ├── amcl.rviz
│ ├── amcl.yaml
│ ├── bt_nav.yaml
│ ├── controller.yaml
│ ├── description.launch.py.template
│ ├── display.launch.py.template
│ ├── gazebo.launch.py.template
│ ├── generator.launch.py.template
│ ├── global.rviz
│ ├── global_plan.launch.py
│ ├── kinematics.yaml
│ ├── local.rviz
│ ├── local_plan.launch.py
│ ├── localization.launch.py
│ ├── mapping.launch.py
│ ├── mapping.rviz
│ ├── package.xml.template
│ ├── package2.xml.template
│ ├── planner.yaml
│ ├── recoveries.yaml
│ ├── robot.urdf.xacro
│ ├── trees.launch.py
│ └── variables.yaml
├── repos.yaml
├── setup.cfg
└── university_world
├── CMakeLists.txt
├── maps
├── willow-2010-02-18-0.10.pgm
├── willow-2010-02-18-0.10.png
└── willow-2010-02-18-0.10.yaml
├── models
└── nowhere
│ ├── meshes
│ └── a_map.stl
│ ├── model.config
│ └── model.sdf
├── package.xml
└── worlds
└── a.world
/.clang-format:
--------------------------------------------------------------------------------
1 | Language: Cpp
2 | Standard: Cpp11
3 | ColumnLimit: 120
4 |
5 | # Braces (Breaks for all, EXCEPT enum)
6 | BreakBeforeBraces: Custom
7 | BraceWrapping:
8 | AfterCaseLabel: true
9 | AfterClass: true
10 | AfterControlStatement: true
11 | AfterEnum: false
12 | AfterFunction: true
13 | AfterNamespace: true
14 | AfterStruct: true
15 | AfterUnion: true
16 | BeforeCatch: true
17 | BeforeElse: true
18 | IndentBraces: false
19 |
20 | # Whitespace
21 | AllowShortBlocksOnASingleLine: false
22 | AllowShortFunctionsOnASingleLine: None
23 | BreakConstructorInitializers: BeforeColon
24 | ConstructorInitializerIndentWidth: 2
25 | SpacesBeforeTrailingComments: 2
26 | UseTab: Never
27 |
28 | # Types
29 | AlwaysBreakTemplateDeclarations: true
30 | PointerBindsToType: true
31 |
32 | # Turn stuff off
33 | FixNamespaceComments: false
34 | IndentPPDirectives: None
35 | KeepEmptyLinesAtTheStartOfBlocks: true
36 | ReflowComments: false
37 | SortIncludes: false
38 | SortUsingDeclarations: false
39 |
--------------------------------------------------------------------------------
/.pre-commit-config.yaml:
--------------------------------------------------------------------------------
1 | repos:
2 | - repo: https://github.com/pre-commit/pre-commit-hooks
3 | hooks:
4 | - id: end-of-file-fixer
5 | - id: trailing-whitespace
6 | - id: check-merge-conflict
7 | - id: mixed-line-ending
8 | - id: check-executables-have-shebangs
9 | - id: check-shebang-scripts-are-executable
10 | - id: detect-private-key
11 | - id: destroyed-symlinks
12 | - id: check-symlinks
13 | - id: check-case-conflict
14 | - id: check-xml
15 | exclude: nav_u_robot_generator/templates/robot.urdf.xacro
16 | - id: check-yaml
17 | - id: check-ast
18 | - id: double-quote-string-fixer
19 | - id: requirements-txt-fixer
20 | rev: v5.0.0
21 | - repo: https://github.com/codespell-project/codespell
22 | hooks:
23 | - id: codespell
24 | args:
25 | - --write-changes
26 | rev: v2.3.0
27 | - repo: https://github.com/adrienverge/yamllint
28 | hooks:
29 | - id: yamllint
30 | args:
31 | - --format
32 | - parsable
33 | - --strict
34 | rev: v1.35.1
35 | - repo: https://github.com/jumanjihouse/pre-commit-hook-yamlfmt
36 | hooks:
37 | - id: yamlfmt
38 | args:
39 | - --width
40 | - '120'
41 | - --implicit_start
42 | - --implicit_end
43 | - --mapping
44 | - '2'
45 | - --sequence
46 | - '2'
47 | - --offset
48 | - '0'
49 | rev: 0.2.3
50 | - repo: https://github.com/hhatto/autopep8
51 | hooks:
52 | - id: autopep8
53 | rev: v2.3.1
54 | - repo: https://github.com/PyCQA/flake8
55 | hooks:
56 | - id: flake8
57 | rev: 7.1.1
58 | - repo: https://github.com/pre-commit/mirrors-clang-format
59 | hooks:
60 | - id: clang-format
61 | rev: v19.1.6
62 | - repo: https://github.com/tier4/pre-commit-hooks-ros
63 | hooks:
64 | - id: prettier-package-xml
65 | - id: prettier-xacro
66 | exclude: nav_u_robot_generator/templates/robot.urdf
67 | rev: v0.10.0
68 | ci:
69 | autoupdate_schedule: quarterly
70 |
--------------------------------------------------------------------------------
/.yamllint.yaml:
--------------------------------------------------------------------------------
1 | yaml-files:
2 | - '*.yaml'
3 | - '*.yml'
4 | rules:
5 | anchors: enable
6 | braces: enable
7 | brackets: enable
8 | colons: enable
9 | commas: enable
10 | comments:
11 | level: warning
12 | comments-indentation:
13 | level: warning
14 | document-end: disable
15 | document-start: disable
16 | empty-lines: enable
17 | empty-values: disable
18 | float-values: disable
19 | hyphens: enable
20 | indentation: disable
21 | key-duplicates: enable
22 | key-ordering: disable
23 | line-length:
24 | max: 120
25 | new-line-at-end-of-file: enable
26 | new-lines: enable
27 | octal-values: disable
28 | quoted-strings: disable
29 | trailing-spaces: enable
30 | truthy:
31 | level: warning
32 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | BSD 3-Clause License
2 |
3 | Copyright (c) 2023, Metro 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 | 
2 |
3 | See [navigationuniversity.com](https://navigationuniversity.com) for more details.
4 |
5 | Code to support the Navigation University workshop.
6 |
7 | # Software Setup Instructions
8 | ## Setup Up Your Folder Structure / Clone Repos
9 | * You can use your own `colcon` workspace, but you may want to create a clean one for this workshop.
10 |
11 | * If you are creating one, run `mkdir ~/ros2_ws/src -p`
12 | * `cd ~/ros2_ws`
13 | * `wget https://raw.githubusercontent.com/MetroRobots/navigation_university/main/repos.yaml`
14 | * `vcs import --recursive < repos.yaml`
15 | * You may also want to create a new empty git repo for the new robot you'll create.
16 | * `mkdir ~/ros2_ws/src/my_new_robot`
17 | * `cd ~/ros2_ws/src/my_new_robot`
18 | * `git init`
19 |
20 | ## Install More Dependencies
21 | * `cd ~/ros2_ws`,
22 | * `rosdep install -r --from-paths src --ignore-src --rosdistro iron -y`
23 |
24 | ## Build the ROS Workspace
25 | * `source /opt/ros/iron/setup.bash`
26 | * `colcon build --symlink-install`
27 |
28 | # Curriculum
29 |
30 | Presentations for the Navigation University workshop.
31 |
32 | 1. [00 - Intro](https://docs.google.com/presentation/d/1Ix0YbG5T3BNs6E0aIlGHWx-LOWcSm6gAooYLkKlC7aA/edit?usp=sharing)
33 | 2. [01 - Teleoperation](https://docs.google.com/presentation/d/1n13MWDcnPihA-IBY9qn0Eyqg2voVTSz69Dk_iipQsgU/edit?usp=sharing)
34 | 3. [02 - Mapping](https://docs.google.com/presentation/d/1ZiZhw7uswBVzEkDrTCOjHh_HMbA6Duw5_YbPt8leqtY/edit?usp=sharing)
35 | 4. [03 - Global Planning](https://docs.google.com/presentation/d/1P86WW4Zh_Xr57MBmwCfGA0vgjo_maeoSe70MJrYjXWM/edit?usp=sharing)
36 | 5. [04 - Localization](https://docs.google.com/presentation/d/18TA7NGiPHXQrzqErOisxQS8GZxMOid9798djV9Hf7fk/edit?usp=sharing)
37 | 6. [05 - Costmaps](https://docs.google.com/presentation/d/1sxIqtTtSlSyvCpn6x0fwloD2D-W_K8swfpHEGsYEBLk/edit?usp=sharing)
38 | 7. [06 - Local Planning](https://docs.google.com/presentation/d/1kXSle8oyF-ooqYNL298knn994adwgV2_cCK4lpZnGho/edit?usp=sharing)
39 | 8. [07 - High Level Coordination](https://docs.google.com/presentation/d/1txxOIOTduF_LYAMh2NWUG2syBrtXM6LIyLhOILcFwIs/edit?usp=sharing)
40 |
--------------------------------------------------------------------------------
/nav_u_dependencies/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.8)
2 | project(nav_u_dependencies)
3 | find_package(ament_cmake REQUIRED)
4 | ament_package()
5 |
--------------------------------------------------------------------------------
/nav_u_dependencies/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | nav_u_dependencies
5 | 0.0.0
6 | A pile of run dependencies for the workshop
7 | David V. Lu!!
8 | BSD 3-clause
9 |
10 | ament_cmake
11 | fuse
12 | gazebo_ros
13 | gazebo_plugins
14 | joint_state_publisher
15 | joint_state_publisher_gui
16 | nav2_bringup
17 | robot_state_publisher
18 | rosbag2
19 | rqt_graph
20 | rqt_robot_steering
21 | rviz2
22 | rviz_common
23 | rviz_default_plugins
24 | slam_toolbox
25 | teleop_twist_joy
26 | teleop_twist_keyboard
27 | urdf_launch
28 |
29 |
30 | ament_cmake
31 |
32 |
33 |
--------------------------------------------------------------------------------
/nav_u_generic_description/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.8)
2 | project(nav_u_generic_description)
3 |
4 | find_package(ament_cmake REQUIRED)
5 | install(DIRECTORY urdf/
6 | DESTINATION share/${PROJECT_NAME}/urdf
7 | )
8 | ament_package()
9 |
--------------------------------------------------------------------------------
/nav_u_generic_description/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | nav_u_generic_description
5 | 0.0.0
6 | Generic Robot Macros for Navigation University Demos
7 | David V. Lu!!
8 | BSD 3-clause
9 |
10 | ament_cmake
11 |
12 |
13 | ament_cmake
14 |
15 |
16 |
--------------------------------------------------------------------------------
/nav_u_generic_description/urdf/macros.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 |
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 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 | ${rate}
83 |
84 |
85 | ~/out:=scan
86 |
87 |
88 | ${type}
89 | sensor
90 |
91 |
92 |
93 |
94 | ${samples}
95 | 1
96 | ${-angular_range/2}
97 | ${angular_range/2}
98 |
99 |
100 |
101 | ${min_dist}
102 | ${max_dist}
103 | 0.015
104 |
105 |
106 | gaussian
107 | 0.0
108 | ${stddev}
109 |
110 |
111 |
112 | Gazebo/DarkGrey
113 |
114 |
115 |
116 |
117 |
118 |
119 | /robot
120 | 5.0
121 |
122 |
123 |
124 |
125 | ${x_covar}
126 | ${y_covar}
127 | ${theta_covar}
128 | ${x_covar*odom_mult}
129 | ${y_covar*odom_mult}
130 | ${theta_covar*odom_mult}
131 |
132 |
133 |
134 |
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 |
160 |
161 |
162 |
163 |
164 |
165 |
166 | Gazebo/${color}
167 |
168 |
169 |
170 |
171 |
172 |
173 |
174 |
175 |
176 |
177 |
178 |
179 |
180 |
181 |
182 |
183 |
184 |
185 |
186 |
187 |
188 |
189 |
190 |
191 |
192 |
193 |
194 |
195 |
196 |
197 |
198 |
199 |
200 | Gazebo/${color}
201 |
202 |
203 |
204 |
205 |
206 |
207 |
208 |
209 | /
210 |
211 | 10
212 | left_front_wheel_joint
213 | right_front_wheel_joint
214 | right_back_wheel_joint
215 | left_back_wheel_joint
216 |
217 |
218 |
219 |
220 |
221 |
222 |
223 |
224 |
225 |
226 |
227 |
228 |
229 |
230 |
231 |
232 |
233 |
234 |
235 |
236 |
237 |
238 |
239 |
240 |
241 |
242 |
243 |
244 |
245 |
246 |
247 |
248 |
249 | Gazebo/${color}
250 |
251 |
252 |
253 |
254 |
255 |
256 |
257 | /
258 |
259 | 10
260 | left_front_wheel_joint
261 | right_front_wheel_joint
262 | back_wheel_joint
263 |
264 |
265 |
266 |
267 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.8)
2 | project(nav_u_robot_generator)
3 |
4 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
5 | add_compile_options(-Wall -Wextra -Wpedantic)
6 | endif()
7 |
8 | find_package(ament_cmake REQUIRED)
9 | find_package(ament_index_cpp REQUIRED)
10 | find_package(Qt5Core REQUIRED)
11 | find_package(Qt5Widgets REQUIRED)
12 | find_package(rcl_interfaces REQUIRED)
13 | find_package(rclcpp REQUIRED)
14 |
15 | set(CMAKE_AUTOMOC ON)
16 |
17 | qt5_wrap_cpp(MOC_FILES
18 | include/nav_u_robot_generator/robot_gen_widget.hpp
19 | include/nav_u_robot_generator/app_widget.hpp
20 | )
21 |
22 | add_executable(${PROJECT_NAME}
23 | src/main.cpp
24 | src/app_widget.cpp
25 | src/robot_gen_widget.cpp
26 | src/templates.cpp
27 | ${MOC_FILES}
28 | )
29 | target_include_directories(${PROJECT_NAME} PUBLIC
30 | $
31 | $
32 | )
33 | ament_target_dependencies(${PROJECT_NAME}
34 | ament_index_cpp
35 | Qt5Core
36 | Qt5Widgets
37 | rclcpp
38 | rcl_interfaces
39 | )
40 | install(DIRECTORY config/
41 | DESTINATION share/${PROJECT_NAME}/config
42 | )
43 | install(DIRECTORY launch/
44 | DESTINATION share/${PROJECT_NAME}/launch
45 | )
46 | install(DIRECTORY templates/
47 | DESTINATION share/${PROJECT_NAME}/templates
48 | )
49 | install(TARGETS ${PROJECT_NAME}
50 | DESTINATION lib/${PROJECT_NAME}
51 | )
52 | install(DIRECTORY include/
53 | DESTINATION include
54 | )
55 |
56 | ament_export_include_directories(include)
57 |
58 | ament_package()
59 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/config/gen.rviz:
--------------------------------------------------------------------------------
1 | Visualization Manager:
2 | Displays:
3 | - Class: rviz_default_plugins/Grid
4 | Name: Grid
5 | Value: true
6 | - Class: rviz_default_plugins/RobotModel
7 | Description Topic:
8 | Value: /robot_description
9 | Name: RobotModel
10 | Value: true
11 | Enabled: true
12 | Global Options:
13 | Fixed Frame: base_footprint
14 | Tools:
15 | - Class: rviz_default_plugins/MoveCamera
16 | Value: true
17 | Views:
18 | Current:
19 | Class: rviz_default_plugins/Orbit
20 | Distance: 1.2
21 | Name: Current View
22 | Pitch: 0.32
23 | Value: Orbit (rviz)
24 | Yaw: 0.6
25 | Window Geometry:
26 | Height: 800
27 | Width: 800
28 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/include/nav_u_robot_generator/app_widget.hpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 |
37 | #pragma once
38 |
39 | // ROS
40 | #include
41 | #include
42 |
43 | // Qt
44 | #include
45 | #include
46 |
47 | namespace nav_u_robot_generator
48 | {
49 | class AppWidget : public QWidget
50 | {
51 | Q_OBJECT
52 | public:
53 | AppWidget(const rclcpp::Node::SharedPtr& node, QWidget* parent);
54 | void closeEvent(QCloseEvent* event) override;
55 | virtual bool notify(QObject* rec, QEvent* ev);
56 |
57 | private:
58 | rclcpp::Node::SharedPtr node_;
59 | RobotGenWidget* robot_gen_widget_;
60 | QSplitter* splitter_;
61 | };
62 | } // namespace nav_u_robot_generator
63 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/include/nav_u_robot_generator/robot_gen_widget.hpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 |
37 | #pragma once
38 | #include
39 | #include
40 | #include
41 | #include
42 | #include
43 | #include
44 | #include
45 | #include
46 | #include
47 | #include
48 | #include
49 | #include
50 |
51 | namespace nav_u_robot_generator
52 | {
53 | class QDoubleSlider : public QSlider
54 | {
55 | public:
56 | QDoubleSlider(QWidget* parent, double min, double max) : QSlider(parent), min_(min), max_(max)
57 | {
58 | }
59 |
60 | double double_value() const
61 | {
62 | double value_i = value();
63 | int min_i = minimum(), max_i = maximum();
64 | double ratio = (value_i - min_i) / (max_i - min_i);
65 | return min_ + ratio * (max_ - min_);
66 | }
67 |
68 | void setDoubleValue(double d)
69 | {
70 | double ratio = (d - min_) / (max_ - min_);
71 | int min_i = minimum(), max_i = maximum();
72 | int value_i = static_cast(min_i + ratio * (max_i - min_i));
73 | setValue(value_i);
74 | }
75 |
76 | protected:
77 | double min_, max_;
78 | };
79 |
80 | class RobotGenWidget : public QWidget
81 | {
82 | Q_OBJECT
83 | public:
84 | void initialize(const rclcpp::Node::SharedPtr& parent_node, QWidget* parent_widget);
85 |
86 | protected Q_SLOTS:
87 | void editedStrings();
88 | void shapeChanged(int);
89 | void changeNoiseLevel(int);
90 | void colorChanged(int);
91 | void geometryChanged(double);
92 | void speedChange(double);
93 | void browse();
94 | void generate();
95 |
96 | protected:
97 | void initializeValue(QLineEdit* widget, const std::string& param_name, const std::string& default_value);
98 | void initializeValue(QComboBox* widget, const std::string& param_name, const std::string& default_value);
99 | void initializeValue(QDoubleSpinBox* widget, const std::string& param_name, double default_value);
100 | void initializeValue(QSpinBox* widget, const std::string& param_name, int default_value);
101 | void initializeValue(QDoubleSlider* widget, const std::string& param_name, double default_value);
102 |
103 | std::vector getVariables();
104 | void generateURDF();
105 | QHBoxLayout* addRow(const std::string& text, QWidget* widget);
106 |
107 | rclcpp::Node::SharedPtr node_;
108 | int shape_;
109 |
110 | rclcpp::Client::SharedPtr set_params_srv_;
111 |
112 | std::filesystem::path this_package_;
113 | std::string package_name_, config_package_name_;
114 |
115 | QVBoxLayout* main_layout_;
116 | QPushButton *browse_button_, *generate_button_;
117 | QLineEdit *robot_edit_, *name_edit_, *email_edit_, *path_edit_;
118 | QComboBox *shape_edit_, *sensor_edit_, *body_color_edit_, *wheel_color_edit_;
119 | QDoubleSpinBox *width_edit_, *height_edit_, *length_edit_, *wheel_height_edit_, *sensor_range_edit_, *drive_vel_edit_,
120 | *turn_vel_edit_;
121 | QSpinBox* samples_edit_;
122 | QDoubleSlider *noise_edit_, *odom_noise_edit_, *laser_noise_edit_, *sensor_offset_edit_;
123 | };
124 | } // namespace nav_u_robot_generator
125 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/include/nav_u_robot_generator/rviz_panel.hpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 |
37 | #pragma once
38 |
39 | #include
40 | #include
41 | #include
42 | #include
43 | #include
44 | #include
45 | #include
46 | #include
47 | #include
48 | #include
49 | #include
50 |
51 | namespace nav_u_robot_generator
52 | {
53 | class RVizPanel : public QWidget, public rviz_common::WindowManagerInterface
54 | {
55 | Q_OBJECT
56 | public:
57 | RVizPanel(QWidget* parent, const rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr& node_abstraction);
58 | ~RVizPanel() override;
59 |
60 | void initialize();
61 | void updateFixedFrame();
62 |
63 | QWidget* getParentWindow() override
64 | {
65 | return parent_;
66 | }
67 |
68 | rviz_common::PanelDockWidget* addPane(const QString& /*name*/, QWidget* /*pane*/,
69 | Qt::DockWidgetArea /*area*/ = Qt::LeftDockWidgetArea,
70 | bool /*floating*/ = true) override
71 | {
72 | // Stub for now...just to define the WindowManagerInterface methods
73 | return nullptr;
74 | }
75 |
76 | void setStatus(const QString& /*message*/) override
77 | {
78 | // Stub for now...just to define the WindowManagerInterface methods
79 | }
80 |
81 | protected:
82 | QWidget* parent_;
83 | rviz_common::RenderPanel* rviz_render_panel_{nullptr};
84 | rviz_common::VisualizationManager* rviz_manager_{nullptr};
85 | rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr node_abstraction_;
86 | rclcpp::Node::SharedPtr node_;
87 | std::shared_ptr logger_;
88 |
89 | rviz_default_plugins::displays::GridDisplay* grid_display_{nullptr};
90 | rviz_default_plugins::displays::RobotModelDisplay* robot_display_{nullptr};
91 | };
92 | } // namespace nav_u_robot_generator
93 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/include/nav_u_robot_generator/templates.hpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 |
37 | #pragma once
38 |
39 | #include
40 | #include
41 | #include
42 | #include
43 |
44 | namespace nav_u_robot_generator
45 | {
46 | /**
47 | * @brief Simple Key/value pair for templates
48 | */
49 | struct TemplateVariable
50 | {
51 | TemplateVariable(const std::string& key, const std::string& value) : key(key), value(value)
52 | {
53 | }
54 |
55 | std::string key;
56 | std::string value;
57 | };
58 |
59 | template
60 | TemplateVariable TV(const std::string& key, T value)
61 | {
62 | return TemplateVariable(key, std::to_string(value));
63 | }
64 |
65 | std::filesystem::path getSharePath(const std::string& package_name);
66 |
67 | std::string renderTemplate(const std::filesystem::path template_path, const std::vector& variables);
68 |
69 | void renderTemplate(const std::filesystem::path template_path, const std::vector& variables,
70 | const std::filesystem::path output_path, bool overwrite = true);
71 |
72 | } // namespace nav_u_robot_generator
73 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/launch/generator.launch.py:
--------------------------------------------------------------------------------
1 | import launch
2 | from launch_ros.actions import Node
3 | from launch_ros.substitutions import FindPackageShare
4 |
5 | EMPTY_URDF = """
6 |
7 |
8 |
9 | """
10 |
11 |
12 | def generate_launch_description():
13 | ld = launch.LaunchDescription()
14 | ld.add_action(Node(
15 | package='nav_u_robot_generator',
16 | executable='nav_u_robot_generator',
17 | ))
18 | ld.add_action(Node(
19 | package='robot_state_publisher',
20 | executable='robot_state_publisher',
21 | parameters=[{'robot_description': EMPTY_URDF}],
22 | ))
23 | ld.add_action(Node(
24 | package='joint_state_publisher',
25 | executable='joint_state_publisher',
26 | ))
27 | ld.add_action(Node(
28 | package='rviz2',
29 | executable='rviz2',
30 | arguments=['-d', [FindPackageShare('nav_u_robot_generator'), '/config/gen.rviz']],
31 | ))
32 | return ld
33 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | nav_u_robot_generator
5 | 0.0.0
6 | Navigation University Robot Generator
7 | David V. Lu!!
8 | BSD 3-clause
9 |
10 | ament_cmake
11 | ament_index_cpp
12 |
13 |
14 | ament_cmake
15 |
16 |
17 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/src/app_widget.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 |
37 | #include
38 | #include
39 | #include
40 | #include
41 | #include
42 | #include
43 | #include
44 | #include
45 | #include
46 |
47 | namespace nav_u_robot_generator
48 | {
49 | AppWidget::AppWidget(const rclcpp::Node::SharedPtr& node, QWidget* parent) : QWidget(parent), node_(node)
50 | {
51 | QHBoxLayout* layout = new QHBoxLayout();
52 | layout->setAlignment(Qt::AlignTop);
53 |
54 | robot_gen_widget_ = new RobotGenWidget();
55 | robot_gen_widget_->initialize(node_, this);
56 |
57 | splitter_ = new QSplitter(Qt::Horizontal, this);
58 | splitter_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
59 | splitter_->addWidget(robot_gen_widget_);
60 | splitter_->setHandleWidth(6);
61 | layout->addWidget(splitter_);
62 |
63 | setLayout(layout);
64 |
65 | setWindowTitle("Robot Generator");
66 |
67 | QApplication::processEvents();
68 | }
69 |
70 | void AppWidget::closeEvent(QCloseEvent* event)
71 | {
72 |
73 | if (QMessageBox::question(this, "Exit Application", QString("Are you sure you want to exit the Robot Generator?"),
74 | QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
75 | {
76 | event->ignore();
77 | return;
78 | }
79 |
80 | // Shutdown app
81 | event->accept();
82 | }
83 |
84 | bool AppWidget::notify(QObject* /*receiver*/, QEvent* /*event*/)
85 | {
86 | QMessageBox::critical(this, "Error", "An error occurred and was caught by Qt notify event handler.", QMessageBox::Ok);
87 |
88 | return false;
89 | }
90 |
91 | } // namespace nav_u_robot_generator
92 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/src/main.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 | #include
37 | #include
38 | #include
39 | #include
40 |
41 | static void siginthandler(int /*param*/)
42 | {
43 | QApplication::quit();
44 | }
45 |
46 | int main(int argc, char** argv)
47 | {
48 | rclcpp::init(argc, argv);
49 | auto node = std::make_shared(
50 | "nav_u_robot_generator",
51 | rclcpp::NodeOptions().allow_undeclared_parameters(true).automatically_declare_parameters_from_overrides(true));
52 | QApplication qt_app(argc, argv);
53 |
54 | signal(SIGINT, siginthandler);
55 |
56 | nav_u_robot_generator::AppWidget ww(node, nullptr);
57 | ww.setMinimumWidth(1090);
58 | ww.setMinimumHeight(600);
59 |
60 | ww.show();
61 |
62 | // Wait here until Qt App is finished
63 | const int result = qt_app.exec();
64 |
65 | // Shutdown ROS
66 | rclcpp::shutdown();
67 |
68 | return result;
69 | }
70 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/src/robot_gen_widget.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 |
37 | #include
38 | #include
39 | #include
40 | #include
41 | #include
42 | #include
43 |
44 | namespace nav_u_robot_generator
45 | {
46 | QHBoxLayout* RobotGenWidget::addRow(const std::string& text, QWidget* widget)
47 | {
48 | QHBoxLayout* row = new QHBoxLayout();
49 | QLabel* title = new QLabel(this);
50 | title->setText(text.c_str());
51 | row->addWidget(title);
52 | row->addWidget(widget);
53 | return row;
54 | }
55 |
56 | void RobotGenWidget::initialize(const rclcpp::Node::SharedPtr& parent_node, QWidget* parent_widget)
57 | {
58 | setParent(parent_widget);
59 | node_ = parent_node;
60 | this_package_ = getSharePath("nav_u_robot_generator");
61 |
62 | set_params_srv_ = node_->create_client("/robot_state_publisher/set_parameters");
63 | using namespace std::chrono_literals;
64 | while (!set_params_srv_->wait_for_service(1s))
65 | {
66 | if (!rclcpp::ok())
67 | {
68 | RCLCPP_ERROR(node_->get_logger(), "Interrupted while waiting for the service. Exiting.");
69 | return;
70 | }
71 | RCLCPP_INFO(node_->get_logger(), "service not available, waiting again...");
72 | }
73 |
74 | main_layout_ = new QVBoxLayout(this);
75 | main_layout_->setAlignment(Qt::AlignTop);
76 | main_layout_->setContentsMargins(0, 0, 0, 0);
77 |
78 | QLabel* page_title = new QLabel(this);
79 | page_title->setText("Navigation University Robot Generator");
80 | QFont page_title_font(QFont().defaultFamily(), 18, QFont::Bold);
81 | page_title->setFont(page_title_font);
82 | page_title->setWordWrap(true);
83 | page_title->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Maximum);
84 | main_layout_->addWidget(page_title);
85 |
86 | robot_edit_ = new QLineEdit(this);
87 | initializeValue(robot_edit_, "robot_name", "example_bot");
88 | connect(robot_edit_, SIGNAL(editingFinished()), this, SLOT(editedStrings()));
89 | main_layout_->addLayout(addRow("Robot Name (letters/underscores only)", robot_edit_));
90 |
91 | name_edit_ = new QLineEdit(this);
92 | initializeValue(name_edit_, "author_name", "Roberta Universidad");
93 | connect(name_edit_, SIGNAL(editingFinished()), this, SLOT(editedStrings()));
94 | main_layout_->addLayout(addRow("Your Name (for package.xml)", name_edit_));
95 |
96 | email_edit_ = new QLineEdit(this);
97 | initializeValue(email_edit_, "author_email", "tullyfoote@intrinsic.ai");
98 | connect(email_edit_, SIGNAL(editingFinished()), this, SLOT(editedStrings()));
99 | main_layout_->addLayout(addRow("Your Email (for package.xml)", email_edit_));
100 |
101 | shape_edit_ = new QComboBox(this);
102 | shape_edit_->addItem("Circle");
103 | shape_edit_->addItem("Square");
104 | shape_edit_->addItem("Rectangle");
105 | initializeValue(shape_edit_, "shape", "Circle");
106 | shape_ = shape_edit_->currentIndex();
107 | connect(shape_edit_, SIGNAL(currentIndexChanged(int)), this, SLOT(shapeChanged(int)));
108 | main_layout_->addLayout(addRow("Robot Shape", shape_edit_));
109 |
110 | width_edit_ = new QDoubleSpinBox(this);
111 | width_edit_->setRange(0.05, 1.0);
112 | width_edit_->setSingleStep(0.05);
113 | initializeValue(width_edit_, "width", 0.5);
114 | connect(width_edit_, SIGNAL(valueChanged(double)), this, SLOT(geometryChanged(double)));
115 | main_layout_->addLayout(addRow("Robot Width", width_edit_));
116 |
117 | length_edit_ = new QDoubleSpinBox(this);
118 | length_edit_->setRange(0.05, 1.0);
119 | length_edit_->setSingleStep(0.05);
120 | initializeValue(length_edit_, "length", 0.8);
121 | if (shape_ != 2)
122 | {
123 | length_edit_->setEnabled(false);
124 | }
125 | connect(length_edit_, SIGNAL(valueChanged(double)), this, SLOT(geometryChanged(double)));
126 | main_layout_->addLayout(addRow("Robot Length", length_edit_));
127 |
128 | height_edit_ = new QDoubleSpinBox(this);
129 | height_edit_->setRange(0.05, 1.0);
130 | height_edit_->setSingleStep(0.05);
131 | initializeValue(height_edit_, "height", 0.1);
132 | connect(height_edit_, SIGNAL(valueChanged(double)), this, SLOT(geometryChanged(double)));
133 | main_layout_->addLayout(addRow("Robot Height", height_edit_));
134 |
135 | wheel_height_edit_ = new QDoubleSpinBox(this);
136 | wheel_height_edit_->setRange(0.025, 0.5);
137 | wheel_height_edit_->setSingleStep(0.05);
138 | initializeValue(wheel_height_edit_, "wheel_radius", 0.1);
139 | connect(wheel_height_edit_, SIGNAL(valueChanged(double)), this, SLOT(geometryChanged(double)));
140 | main_layout_->addLayout(addRow("Wheel Radius", wheel_height_edit_));
141 |
142 | drive_vel_edit_ = new QDoubleSpinBox(this);
143 | drive_vel_edit_->setRange(0.05, 1.5);
144 | drive_vel_edit_->setSingleStep(0.05);
145 | initializeValue(drive_vel_edit_, "max_vel_x", 0.8);
146 | connect(drive_vel_edit_, SIGNAL(valueChanged(double)), this, SLOT(speedChange(double)));
147 | main_layout_->addLayout(addRow("Max Drive Speed", drive_vel_edit_));
148 |
149 | turn_vel_edit_ = new QDoubleSpinBox(this);
150 | turn_vel_edit_->setRange(0.05, 1.5);
151 | turn_vel_edit_->setSingleStep(0.05);
152 | initializeValue(turn_vel_edit_, "max_vel_theta", 0.8);
153 | connect(turn_vel_edit_, SIGNAL(valueChanged(double)), this, SLOT(speedChange(double)));
154 | main_layout_->addLayout(addRow("Max Turn Speed", turn_vel_edit_));
155 |
156 | /*noise_edit_ = new QDoubleSlider(this, 0.0, 0.00005);
157 | noise_edit_->setOrientation(Qt::Horizontal);
158 | initializeValue(noise_edit_, "base_noise", 0.00001);
159 | connect(noise_edit_, SIGNAL(valueChanged(int)), this, SLOT(changeNoiseLevel(int)));
160 | main_layout_->addLayout(addRow("Base Noise", noise_edit_));
161 |
162 | odom_noise_edit_ = new QDoubleSlider(this, 1.0, 10.0);
163 | odom_noise_edit_->setOrientation(Qt::Horizontal);
164 | initializeValue(odom_noise_edit_, "odom_mult", 1.5);
165 | connect(odom_noise_edit_, SIGNAL(valueChanged(int)), this, SLOT(changeNoiseLevel(int)));
166 | main_layout_->addLayout(addRow("Odometry Noise", odom_noise_edit_));*/
167 |
168 | sensor_edit_ = new QComboBox(this);
169 | sensor_edit_->addItem("LaserScan");
170 | sensor_edit_->addItem("PointCloud2");
171 | initializeValue(sensor_edit_, "sensor_type", "LaserScan");
172 | connect(sensor_edit_, SIGNAL(currentIndexChanged(int)), this, SLOT(changeNoiseLevel(int)));
173 | main_layout_->addLayout(addRow("Sensor Type", sensor_edit_));
174 |
175 | samples_edit_ = new QSpinBox(this);
176 | samples_edit_->setRange(10, 300);
177 | samples_edit_->setSingleStep(10);
178 | initializeValue(samples_edit_, "sensor_samples", 150);
179 | connect(samples_edit_, SIGNAL(valueChanged(int)), this, SLOT(changeNoiseLevel(int)));
180 | main_layout_->addLayout(addRow("Sensor Samples", samples_edit_));
181 |
182 | laser_noise_edit_ = new QDoubleSlider(this, 0.0, 0.3);
183 | laser_noise_edit_->setOrientation(Qt::Horizontal);
184 | initializeValue(laser_noise_edit_, "sensor_noise", 0.1);
185 | connect(laser_noise_edit_, SIGNAL(valueChanged(int)), this, SLOT(changeNoiseLevel(int)));
186 | main_layout_->addLayout(addRow("Sensor Noise", laser_noise_edit_));
187 |
188 | sensor_offset_edit_ = new QDoubleSlider(this, 0.0, 0.9);
189 | sensor_offset_edit_->setOrientation(Qt::Horizontal);
190 | initializeValue(sensor_offset_edit_, "sensor_offset", 0.0);
191 | connect(sensor_offset_edit_, SIGNAL(valueChanged(int)), this, SLOT(colorChanged(int)));
192 | main_layout_->addLayout(addRow("Sensor Offset", sensor_offset_edit_));
193 |
194 | sensor_range_edit_ = new QDoubleSpinBox(this);
195 | sensor_range_edit_->setRange(10.0, 360.0);
196 | sensor_range_edit_->setSingleStep(10.0);
197 | initializeValue(sensor_range_edit_, "sensor_range", 180.0);
198 | connect(sensor_range_edit_, SIGNAL(valueChanged(double)), this, SLOT(geometryChanged(double)));
199 | main_layout_->addLayout(addRow("Sensor Angular Range (deg)", sensor_range_edit_));
200 |
201 | body_color_edit_ = new QComboBox(this);
202 | body_color_edit_->addItem("Grey");
203 | body_color_edit_->addItem("DarkGrey");
204 | body_color_edit_->addItem("White");
205 | body_color_edit_->addItem("FlatBlack");
206 | body_color_edit_->addItem("Black");
207 | body_color_edit_->addItem("Red");
208 | body_color_edit_->addItem("RedBright");
209 | body_color_edit_->addItem("Green");
210 | body_color_edit_->addItem("Blue");
211 | body_color_edit_->addItem("SkyBlue");
212 | body_color_edit_->addItem("Yellow");
213 | body_color_edit_->addItem("ZincYellow");
214 | body_color_edit_->addItem("DarkYellow");
215 | body_color_edit_->addItem("Purple");
216 | body_color_edit_->addItem("Turquoise");
217 | body_color_edit_->addItem("Orange");
218 | body_color_edit_->addItem("Indigo");
219 | body_color_edit_->addItem("Gold");
220 | initializeValue(body_color_edit_, "body_color", "Blue");
221 | connect(body_color_edit_, SIGNAL(currentIndexChanged(int)), this, SLOT(colorChanged(int)));
222 | main_layout_->addLayout(addRow("Body Color", body_color_edit_));
223 |
224 | wheel_color_edit_ = new QComboBox(this);
225 | wheel_color_edit_->addItem("Grey");
226 | wheel_color_edit_->addItem("DarkGrey");
227 | wheel_color_edit_->addItem("White");
228 | wheel_color_edit_->addItem("FlatBlack");
229 | wheel_color_edit_->addItem("Black");
230 | wheel_color_edit_->addItem("Red");
231 | wheel_color_edit_->addItem("RedBright");
232 | wheel_color_edit_->addItem("Green");
233 | wheel_color_edit_->addItem("Blue");
234 | wheel_color_edit_->addItem("SkyBlue");
235 | wheel_color_edit_->addItem("Yellow");
236 | wheel_color_edit_->addItem("ZincYellow");
237 | wheel_color_edit_->addItem("DarkYellow");
238 | wheel_color_edit_->addItem("Purple");
239 | wheel_color_edit_->addItem("Turquoise");
240 | wheel_color_edit_->addItem("Orange");
241 | wheel_color_edit_->addItem("Indigo");
242 | wheel_color_edit_->addItem("Gold");
243 | initializeValue(wheel_color_edit_, "wheel_color", "DarkGrey");
244 | connect(wheel_color_edit_, SIGNAL(currentIndexChanged(int)), this, SLOT(colorChanged(int)));
245 | main_layout_->addLayout(addRow("Wheel Color", wheel_color_edit_));
246 |
247 | QHBoxLayout* last_row = new QHBoxLayout();
248 | QLabel* title = new QLabel(this);
249 | title->setText("Package Parent Directory");
250 | last_row->addWidget(title);
251 |
252 | path_edit_ = new QLineEdit(this);
253 | initializeValue(path_edit_, "parent_path", "");
254 | last_row->addWidget(path_edit_);
255 |
256 | browse_button_ = new QPushButton(this);
257 | browse_button_->setText("Explore");
258 | connect(browse_button_, SIGNAL(clicked()), this, SLOT(browse()));
259 | last_row->addWidget(browse_button_);
260 |
261 | main_layout_->addLayout(last_row);
262 |
263 | QHBoxLayout* really_last_row = new QHBoxLayout();
264 | generate_button_ = new QPushButton(this);
265 | generate_button_->setText("Generate");
266 | connect(generate_button_, SIGNAL(clicked()), this, SLOT(generate()));
267 | really_last_row->addWidget(generate_button_);
268 | main_layout_->addLayout(really_last_row);
269 | generateURDF();
270 | }
271 |
272 | void RobotGenWidget::initializeValue(QLineEdit* widget, const std::string& param_name, const std::string& default_value)
273 | {
274 | std::string value = node_->get_parameter_or(param_name, default_value);
275 | widget->setText(value.c_str());
276 | }
277 | void RobotGenWidget::initializeValue(QComboBox* widget, const std::string& param_name, const std::string& default_value)
278 | {
279 | std::string value = node_->get_parameter_or(param_name, default_value);
280 | int my_index = widget->findText(value.c_str());
281 | if (my_index >= 0)
282 | widget->setCurrentIndex(my_index);
283 | }
284 | void RobotGenWidget::initializeValue(QDoubleSpinBox* widget, const std::string& param_name, double default_value)
285 | {
286 | double value = node_->get_parameter_or(param_name, default_value);
287 | widget->setValue(value);
288 | }
289 | void RobotGenWidget::initializeValue(QSpinBox* widget, const std::string& param_name, int default_value)
290 | {
291 | int value = node_->get_parameter_or(param_name, default_value);
292 | widget->setValue(value);
293 | }
294 | void RobotGenWidget::initializeValue(QDoubleSlider* widget, const std::string& param_name, double default_value)
295 | {
296 | double value = node_->get_parameter_or(param_name, default_value);
297 | widget->setDoubleValue(value);
298 | }
299 |
300 | void RobotGenWidget::editedStrings()
301 | {
302 | generateURDF();
303 | }
304 |
305 | void RobotGenWidget::changeNoiseLevel(int)
306 | {
307 | }
308 |
309 | void RobotGenWidget::geometryChanged(double)
310 | {
311 | generateURDF();
312 | }
313 |
314 | void RobotGenWidget::shapeChanged(int shape)
315 | {
316 | shape_ = shape;
317 | if (shape == 2)
318 | {
319 | length_edit_->setEnabled(true);
320 | }
321 | else
322 | {
323 | length_edit_->setEnabled(false);
324 | }
325 | generateURDF();
326 | }
327 |
328 | void RobotGenWidget::colorChanged(int)
329 | {
330 | generateURDF();
331 | }
332 |
333 | void RobotGenWidget::speedChange(double)
334 | {
335 | }
336 |
337 | void RobotGenWidget::browse()
338 | {
339 | QString path = QFileDialog::getExistingDirectory(this, "Open Parent Directory", path_edit_->text(),
340 | QFileDialog::ShowDirsOnly | QFileDialog::DontResolveSymlinks);
341 |
342 | // check they did not press cancel
343 | if (!path.isNull())
344 | path_edit_->setText(path);
345 | }
346 |
347 | std::vector RobotGenWidget::getVariables()
348 | {
349 | std::vector variables;
350 |
351 | std::string robot_name = robot_edit_->text().toStdString();
352 | variables.push_back(TemplateVariable("ROBOT_NAME", robot_name));
353 | package_name_ = robot_name + "_description";
354 | variables.push_back(TemplateVariable("PACKAGE_NAME", package_name_));
355 |
356 | config_package_name_ = robot_name + "_nav_config";
357 | variables.push_back(TemplateVariable("CONFIG_PACKAGE_NAME", config_package_name_));
358 |
359 | variables.push_back(TemplateVariable("AUTHOR_NAME", name_edit_->text().toStdString()));
360 | variables.push_back(TemplateVariable("AUTHOR_EMAIL", email_edit_->text().toStdString()));
361 |
362 | double width = width_edit_->value();
363 | variables.push_back(TV("WIDTH", width));
364 | variables.push_back(TV("HEIGHT", height_edit_->value()));
365 | double length = length_edit_->value();
366 | variables.push_back(TV("LENGTH", length));
367 | variables.push_back(TV("WHEEL_RADIUS", wheel_height_edit_->value()));
368 |
369 | double sensor_offset_mult = sensor_offset_edit_->double_value();
370 | std::string shape_macro = "";
371 | std::string sensor_offset;
372 | if (shape_ == 0)
373 | {
374 | shape_macro = "circle_robot ";
375 | sensor_offset = std::to_string(width * sensor_offset_mult / 2);
376 | }
377 | else if (shape_ == 1)
378 | {
379 | shape_macro = "box_robot length=\"" + std::to_string(width) + "\"";
380 | sensor_offset = std::to_string(width * sensor_offset_mult / 2);
381 | }
382 | else
383 | {
384 | shape_macro = "box_robot length=\"" + std::to_string(length) + "\"";
385 | sensor_offset = std::to_string(length * sensor_offset_mult / 2);
386 | }
387 | variables.push_back(TemplateVariable("SHAPE_MACRO", shape_macro));
388 | variables.push_back(TemplateVariable("SENSOR_OFFSET", sensor_offset));
389 | variables.push_back(TV("SENSOR_OFFSET_MULT", sensor_offset_mult));
390 | variables.push_back(TemplateVariable("SHAPE", shape_edit_->itemText(shape_).toStdString()));
391 |
392 | // variables.push_back(TV("BASE_NOISE", noise_edit_->double_value()));
393 | // variables.push_back(TV("ODOM_MULT", odom_noise_edit_->double_value()));
394 | variables.push_back(TV("MAX_VEL_X", drive_vel_edit_->value()));
395 | variables.push_back(TV("MAX_VEL_THETA", turn_vel_edit_->value()));
396 |
397 | variables.push_back(TemplateVariable("BODY_COLOR", body_color_edit_->currentText().toStdString()));
398 | variables.push_back(TemplateVariable("WHEEL_COLOR", wheel_color_edit_->currentText().toStdString()));
399 |
400 | variables.push_back(TV("SENSOR_RANGE", sensor_range_edit_->value()));
401 | variables.push_back(TV("SENSOR_SAMPLES", samples_edit_->value()));
402 | variables.push_back(TV("SENSOR_NOISE", laser_noise_edit_->double_value()));
403 | variables.push_back(TemplateVariable("SENSOR_TYPE", sensor_edit_->currentText().toStdString()));
404 |
405 | variables.push_back(TemplateVariable("PARENT_PATH", path_edit_->text().toStdString()));
406 | return variables;
407 | }
408 |
409 | void RobotGenWidget::generateURDF()
410 | {
411 | std::vector variables = getVariables();
412 |
413 | std::filesystem::path temp_path = "/tmp/robot.xacro";
414 | renderTemplate(this_package_ / "templates" / "robot.urdf.xacro", variables, temp_path);
415 | std::string cmd = "ros2 run xacro xacro " + temp_path.string();
416 |
417 | std::string buffer = "";
418 | FILE* pipe = popen(cmd.c_str(), "r");
419 | char pipe_buffer[128];
420 | while (!feof(pipe))
421 | {
422 | if (fgets(pipe_buffer, 128, pipe) != nullptr)
423 | buffer += pipe_buffer;
424 | }
425 | pclose(pipe);
426 |
427 | auto request = std::make_shared();
428 | request->parameters.resize(1);
429 | request->parameters[0].name = "robot_description";
430 | request->parameters[0].value.type = 4; // string
431 | request->parameters[0].value.string_value = buffer;
432 |
433 | auto result = set_params_srv_->async_send_request(request);
434 | }
435 |
436 | void RobotGenWidget::generate()
437 | {
438 | std::filesystem::path parent_path = path_edit_->text().toStdString();
439 | std::vector variables = getVariables();
440 |
441 | std::filesystem::path package = parent_path / package_name_;
442 | std::filesystem::path templates = this_package_ / "templates";
443 |
444 | renderTemplate(templates / "package.xml.template", variables, package / "package.xml");
445 | renderTemplate(templates / "CMakeLists.txt", variables, package / "CMakeLists.txt");
446 | renderTemplate(templates / "description.launch.py.template", variables, package / "launch" / "description.launch.py");
447 | renderTemplate(templates / "display.launch.py.template", variables, package / "launch" / "display.launch.py");
448 | renderTemplate(templates / "gazebo.launch.py.template", variables, package / "launch" / "gazebo.launch.py");
449 | renderTemplate(templates / "generator.launch.py.template", variables, package / "launch" / "generator.launch.py");
450 | renderTemplate(templates / "variables.yaml", variables, package / "config" / "variables.yaml");
451 | renderTemplate(templates / "kinematics.yaml", variables, package / "config" / "kinematics.yaml");
452 | renderTemplate(templates / "robot.urdf.xacro", variables, package / "urdf" / "robot.urdf.xacro");
453 |
454 | std::filesystem::path package2 = parent_path / config_package_name_;
455 |
456 | renderTemplate(templates / "package2.xml.template", variables, package2 / "package.xml");
457 | renderTemplate(templates / "CMakeLists2.txt", variables, package2 / "CMakeLists.txt");
458 | renderTemplate(templates / "amcl.rviz", variables, package2 / "config" / "amcl.rviz", false);
459 | renderTemplate(templates / "amcl.yaml", variables, package2 / "config" / "amcl.yaml", false);
460 | renderTemplate(templates / "bt_nav.yaml", variables, package2 / "config" / "bt_nav.yaml", false);
461 | renderTemplate(templates / "controller.yaml", variables, package2 / "config" / "controller.yaml", false);
462 | renderTemplate(templates / "global.rviz", variables, package2 / "config" / "global.rviz", false);
463 | renderTemplate(templates / "local.rviz", variables, package2 / "config" / "local.rviz", false);
464 | renderTemplate(templates / "mapping.rviz", variables, package2 / "config" / "mapping.rviz", false);
465 | renderTemplate(templates / "recoveries.yaml", variables, package2 / "config" / "recoveries.yaml", false);
466 | renderTemplate(templates / "planner.yaml", variables, package2 / "config" / "planner.yaml", false);
467 | renderTemplate(templates / "global_plan.launch.py", variables, package2 / "launch" / "global_plan.launch.py");
468 | renderTemplate(templates / "localization.launch.py", variables, package2 / "launch" / "localization.launch.py");
469 | renderTemplate(templates / "mapping.launch.py", variables, package2 / "launch" / "mapping.launch.py");
470 | renderTemplate(templates / "local_plan.launch.py", variables, package2 / "launch" / "local_plan.launch.py");
471 | renderTemplate(templates / "trees.launch.py", variables, package2 / "launch" / "trees.launch.py");
472 |
473 | QMessageBox::information(this, package_name_.c_str(), QString("Files generated successfully!"));
474 | }
475 | } // namespace nav_u_robot_generator
476 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/src/rviz_panel.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 |
37 | #include
38 | #include
39 | #include
40 | #include
41 |
42 | namespace nav_u_robot_generator
43 | {
44 | RVizPanel::RVizPanel(QWidget* parent,
45 | const rviz_common::ros_integration::RosNodeAbstractionIface::WeakPtr& node_abstraction)
46 | : QWidget(parent), parent_(parent), node_abstraction_(node_abstraction),
47 | node_(node_abstraction_.lock()->get_raw_node())
48 |
49 | {
50 | logger_ = std::make_shared(node_->get_logger().get_child("RVizPanel"));
51 | }
52 | void RVizPanel::initialize()
53 | {
54 | // Create rviz frame
55 | rviz_render_panel_ = new rviz_common::RenderPanel();
56 | rviz_render_panel_->setMinimumWidth(200);
57 | rviz_render_panel_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
58 |
59 | QApplication::processEvents();
60 | rviz_render_panel_->getRenderWindow()->initialize();
61 |
62 | rviz_manager_ =
63 | new rviz_common::VisualizationManager(rviz_render_panel_, node_abstraction_, this, node_->get_clock());
64 | rviz_render_panel_->initialize(rviz_manager_);
65 | rviz_manager_->initialize();
66 | rviz_manager_->startUpdate();
67 |
68 | auto tm = rviz_manager_->getToolManager();
69 | tm->addTool("rviz_default_plugins/MoveCamera");
70 |
71 | grid_display_ = new rviz_default_plugins::displays::GridDisplay();
72 | rviz_manager_->addDisplay(grid_display_, true);
73 |
74 | robot_display_ = new rviz_default_plugins::displays::RobotModelDisplay();
75 | rviz_manager_->addDisplay(robot_display_, true);
76 |
77 | // Set the fixed and target frame
78 | updateFixedFrame();
79 |
80 | // Set robot description
81 | robot_display_->subProp("Description Topic")->setValue(QString::fromStdString("robot_description"));
82 |
83 | // Zoom into robot
84 | rviz_common::ViewController* view = rviz_manager_->getViewManager()->getCurrent();
85 | view->subProp("Distance")->setValue(4.0f);
86 |
87 | // Add Rviz to Planning Groups Widget
88 | QVBoxLayout* rviz_layout = new QVBoxLayout();
89 | rviz_layout->addWidget(rviz_render_panel_);
90 |
91 | // visual / collision buttons
92 | auto btn_layout = new QHBoxLayout();
93 | rviz_layout->addLayout(btn_layout);
94 |
95 | QCheckBox* btn;
96 | btn_layout->addWidget(btn = new QCheckBox("visual"), 0);
97 | btn->setChecked(true);
98 | connect(btn, &QCheckBox::toggled,
99 | [this](bool checked) { robot_display_->subProp("Visual Enabled")->setValue(checked); });
100 |
101 | btn_layout->addWidget(btn = new QCheckBox("collision"), 1);
102 | btn->setChecked(false);
103 | connect(btn, &QCheckBox::toggled,
104 | [this](bool checked) { robot_display_->subProp("Collision Enabled")->setValue(checked); });
105 | setLayout(rviz_layout);
106 | }
107 | RVizPanel::~RVizPanel()
108 | {
109 | if (rviz_manager_ != nullptr)
110 | rviz_manager_->removeAllDisplays();
111 | if (rviz_render_panel_ != nullptr)
112 | delete rviz_render_panel_;
113 | if (rviz_manager_ != nullptr)
114 | delete rviz_manager_;
115 | }
116 |
117 | void RVizPanel::updateFixedFrame()
118 | {
119 | rviz_manager_->setFixedFrame(QString::fromStdString("base_footprint"));
120 | }
121 | } // namespace nav_u_robot_generator
122 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/src/templates.cpp:
--------------------------------------------------------------------------------
1 | /*********************************************************************
2 | * Software License Agreement (BSD License)
3 | *
4 | * Copyright (c) 2023, Metro Robots
5 | * All rights reserved.
6 | *
7 | * Redistribution and use in source and binary forms, with or without
8 | * modification, are permitted provided that the following conditions
9 | * are met:
10 | *
11 | * * Redistributions of source code must retain the above copyright
12 | * notice, this list of conditions and the following disclaimer.
13 | * * Redistributions in binary form must reproduce the above
14 | * copyright notice, this list of conditions and the following
15 | * disclaimer in the documentation and/or other materials provided
16 | * with the distribution.
17 | * * Neither the name of Metro Robots nor the names of its
18 | * contributors may be used to endorse or promote products derived
19 | * from this software without specific prior written permission.
20 | *
21 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 | * POSSIBILITY OF SUCH DAMAGE.
33 | *********************************************************************/
34 |
35 | /* Author: David V. Lu!! */
36 |
37 | #include
38 | #include // for string find and replace in templates
39 | #include
40 |
41 | namespace nav_u_robot_generator
42 | {
43 | std::filesystem::path getSharePath(const std::string& package_name)
44 | {
45 | return std::filesystem::path(ament_index_cpp::get_package_share_directory(package_name));
46 | }
47 |
48 | std::string renderTemplate(const std::filesystem::path template_path, const std::vector& variables)
49 | {
50 | // Error check file
51 | if (!std::filesystem::is_regular_file(template_path))
52 | {
53 | throw std::runtime_error(std::string("Unable to find template file ") + template_path.string());
54 | }
55 |
56 | // Load file
57 | std::ifstream template_stream(template_path);
58 | if (!template_stream.good()) // File not found
59 | {
60 | throw std::runtime_error(std::string("Unable to load file ") + template_path.string());
61 | }
62 |
63 | // Load the file to a string using an efficient memory allocation technique
64 | std::string template_string;
65 | template_stream.seekg(0, std::ios::end);
66 | template_string.reserve(template_stream.tellg());
67 | template_stream.seekg(0, std::ios::beg);
68 | template_string.assign((std::istreambuf_iterator(template_stream)), std::istreambuf_iterator());
69 | template_stream.close();
70 |
71 | // Replace keywords in string ------------------------------------------------------------
72 | for (const auto& variable : variables)
73 | {
74 | std::string key_with_brackets = "[" + variable.key + "]";
75 | boost::replace_all(template_string, key_with_brackets, variable.value);
76 | }
77 | return template_string;
78 | }
79 |
80 | void renderTemplate(const std::filesystem::path template_path, const std::vector& variables,
81 | const std::filesystem::path output_path, bool overwrite)
82 | {
83 | if (std::filesystem::is_regular_file(output_path) && !overwrite)
84 | {
85 | return;
86 | }
87 |
88 | std::string s = renderTemplate(template_path, variables);
89 |
90 | std::filesystem::path parent = output_path.parent_path();
91 | if (!std::filesystem::is_directory(parent))
92 | {
93 | std::filesystem::create_directories(parent);
94 | }
95 |
96 | std::ofstream output_stream(output_path, std::ios_base::trunc);
97 | if (!output_stream.good())
98 | {
99 | throw std::runtime_error(std::string("Unable to open file for writing ") + output_path.string());
100 | }
101 |
102 | output_stream << s.c_str();
103 | output_stream.close();
104 | }
105 | } // namespace nav_u_robot_generator
106 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project([PACKAGE_NAME])
3 | find_package(ament_cmake REQUIRED)
4 | install(DIRECTORY urdf/
5 | DESTINATION share/${PROJECT_NAME}/urdf
6 | )
7 | install(DIRECTORY config/
8 | DESTINATION share/${PROJECT_NAME}/config
9 | )
10 | install(DIRECTORY launch/
11 | DESTINATION share/${PROJECT_NAME}/launch
12 | )
13 | ament_package()
14 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/CMakeLists2.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project([CONFIG_PACKAGE_NAME])
3 | find_package(ament_cmake REQUIRED)
4 |
5 | install(DIRECTORY config/
6 | DESTINATION share/${PROJECT_NAME}/config
7 | )
8 | install(DIRECTORY launch/
9 | DESTINATION share/${PROJECT_NAME}/launch
10 | )
11 | ament_package()
12 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/amcl.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz_common/Displays
3 | Help Height: 70
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Map1/Topic1
8 | - /ParticleCloud1/Topic1
9 | Tree Height: 552
10 | - Class: rviz_common/Views
11 | Expanded:
12 | - /Current View1
13 | Name: Views
14 | Visualization Manager:
15 | Displays:
16 | - Class: rviz_default_plugins/Grid
17 | Name: Grid
18 | Value: true
19 | - Binary representation: false
20 | Binary threshold: 100
21 | Class: rviz_default_plugins/Map
22 | Name: Map
23 | Topic:
24 | Durability Policy: Transient Local
25 | Filter size: 10
26 | Value: /map
27 | Update Topic:
28 | Value: /map_updates
29 | Value: true
30 | - Class: rviz_default_plugins/PoseWithCovariance
31 | Name: PoseWithCovariance
32 | Topic:
33 | Filter size: 10
34 | Value: /amcl_pose
35 | Value: true
36 | - Class: rviz_default_plugins/LaserScan
37 | Color: 0; 255; 0
38 | Color Transformer: FlatColor
39 | Max Intensity: 0
40 | Name: LaserScan
41 | Position Transformer: XYZ
42 | Size (m): 0.05000000074505806
43 | Topic:
44 | Filter size: 10
45 | Value: /scan
46 | Value: true
47 | - Class: rviz_default_plugins/TF
48 | Name: TF
49 | Value: true
50 | - Alpha: 1
51 | Class: nav2_rviz_plugins/ParticleCloud
52 | Color: 255; 25; 0
53 | Max Arrow Length: 0.30000001192092896
54 | Min Arrow Length: 0.019999999552965164
55 | Name: ParticleCloud
56 | Shape: Arrow (Flat)
57 | Topic:
58 | Filter size: 10
59 | Reliability Policy: Best Effort
60 | Value: /particle_cloud
61 | Value: true
62 | Enabled: true
63 | Global Options:
64 | Fixed Frame: map
65 | Tools:
66 | - Class: rviz_default_plugins/MoveCamera
67 | - Class: rviz_default_plugins/SetInitialPose
68 | Covariance x: 0.25
69 | Covariance y: 0.25
70 | Covariance yaw: 0.06853891909122467
71 | Topic:
72 | Value: initialpose
73 | - Class: rviz_default_plugins/SetGoal
74 | Topic:
75 | Value: goal_pose
76 | Value: true
77 | Views:
78 | Current:
79 | Class: rviz_default_plugins/TopDownOrtho
80 | Name: Current View
81 | Scale: 55.19443130493164
82 | Window Geometry:
83 | Height: 995
84 | QMainWindow State: 000000ff00000000fd0000000100000000000001cb00000389fc0200000002fb000000100044006900730070006c006100790073010000003d000002ab000000c900fffffffb0000000a0056006900650077007301000002ee000000d8000000a400ffffff000005af0000038900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
85 | Width: 1920
86 | X: 0
87 | Y: 24
88 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/amcl.yaml:
--------------------------------------------------------------------------------
1 | /amcl:
2 | ros__parameters:
3 | alpha1: 0.2
4 | alpha2: 0.2
5 | alpha3: 0.2
6 | alpha4: 0.2
7 | alpha5: 0.2
8 | beam_skip_distance: 0.5
9 | beam_skip_error_threshold: 0.9
10 | beam_skip_threshold: 0.3
11 | lambda_short: 0.1
12 | laser_likelihood_max_dist: 2.0
13 | laser_max_range: 100.0
14 | laser_min_range: -1.0
15 | max_beams: 60
16 | max_particles: 2000
17 | min_particles: 500
18 | pf_err: 0.05
19 | pf_z: 0.99
20 | recovery_alpha_fast: 0.0
21 | recovery_alpha_slow: 0.0
22 | resample_interval: 1
23 | sigma_hit: 0.2
24 | update_min_a: 0.2
25 | update_min_d: 0.25
26 | z_hit: 0.5
27 | z_max: 0.05
28 | z_rand: 0.5
29 | z_short: 0.05
30 |
31 | set_initial_pose: true
32 | initial_pose:
33 | x: 0.0
34 | y: 0.0
35 | yaw: 0.0
36 | z: 0.0
37 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/bt_nav.yaml:
--------------------------------------------------------------------------------
1 | bt_navigator:
2 | ros__parameters:
3 | global_frame: odom
4 | robot_base_frame: base_footprint
5 | plugin_lib_names:
6 | - nav2_compute_path_to_pose_action_bt_node
7 | - nav2_compute_path_through_poses_action_bt_node
8 | - nav2_smooth_path_action_bt_node
9 | - nav2_follow_path_action_bt_node
10 | - nav2_spin_action_bt_node
11 | - nav2_wait_action_bt_node
12 | - nav2_assisted_teleop_action_bt_node
13 | - nav2_back_up_action_bt_node
14 | - nav2_drive_on_heading_bt_node
15 | - nav2_clear_costmap_service_bt_node
16 | - nav2_is_stuck_condition_bt_node
17 | - nav2_goal_reached_condition_bt_node
18 | - nav2_goal_updated_condition_bt_node
19 | - nav2_globally_updated_goal_condition_bt_node
20 | - nav2_is_path_valid_condition_bt_node
21 | - nav2_are_error_codes_active_condition_bt_node
22 | - nav2_would_a_controller_recovery_help_condition_bt_node
23 | - nav2_would_a_planner_recovery_help_condition_bt_node
24 | - nav2_would_a_smoother_recovery_help_condition_bt_node
25 | - nav2_initial_pose_received_condition_bt_node
26 | - nav2_reinitialize_global_localization_service_bt_node
27 | - nav2_rate_controller_bt_node
28 | - nav2_distance_controller_bt_node
29 | - nav2_speed_controller_bt_node
30 | - nav2_truncate_path_action_bt_node
31 | - nav2_truncate_path_local_action_bt_node
32 | - nav2_goal_updater_node_bt_node
33 | - nav2_recovery_node_bt_node
34 | - nav2_pipeline_sequence_bt_node
35 | - nav2_round_robin_node_bt_node
36 | - nav2_transform_available_condition_bt_node
37 | - nav2_time_expired_condition_bt_node
38 | - nav2_path_expiring_timer_condition
39 | - nav2_distance_traveled_condition_bt_node
40 | - nav2_single_trigger_bt_node
41 | - nav2_goal_updated_controller_bt_node
42 | - nav2_is_battery_low_condition_bt_node
43 | - nav2_navigate_through_poses_action_bt_node
44 | - nav2_navigate_to_pose_action_bt_node
45 | - nav2_remove_passed_goals_action_bt_node
46 | - nav2_planner_selector_bt_node
47 | - nav2_controller_selector_bt_node
48 | - nav2_goal_checker_selector_bt_node
49 | - nav2_controller_cancel_bt_node
50 | - nav2_path_longer_on_approach_bt_node
51 | - nav2_wait_cancel_bt_node
52 | - nav2_spin_cancel_bt_node
53 | - nav2_back_up_cancel_bt_node
54 | - nav2_assisted_teleop_cancel_bt_node
55 | - nav2_drive_on_heading_cancel_bt_node
56 | - nav2_is_battery_charging_condition_bt_node
57 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/controller.yaml:
--------------------------------------------------------------------------------
1 | controller_server:
2 | ros__parameters:
3 | controller_frequency: 20.0
4 | min_x_velocity_threshold: 0.001
5 | min_y_velocity_threshold: 0.5
6 | min_theta_velocity_threshold: 0.001
7 | failure_tolerance: 0.3
8 | progress_checker_plugin: progress_checker
9 | goal_checker_plugins: [general_goal_checker] # "precise_goal_checker"
10 | controller_plugins: [FollowPath]
11 |
12 | # Progress checker parameters
13 | progress_checker:
14 | plugin: nav2_controller::SimpleProgressChecker
15 | required_movement_radius: 0.5
16 | movement_time_allowance: 10.0
17 | # Goal checker parameters
18 | # precise_goal_checker:
19 | # plugin: "nav2_controller::SimpleGoalChecker"
20 | # xy_goal_tolerance: 0.25
21 | # yaw_goal_tolerance: 0.25
22 | # stateful: True
23 | general_goal_checker:
24 | stateful: true
25 | plugin: nav2_controller::SimpleGoalChecker
26 | xy_goal_tolerance: 0.25
27 | yaw_goal_tolerance: 0.25
28 | # DWB parameters
29 | FollowPath:
30 | plugin: dwb_core::DWBLocalPlanner
31 | debug_trajectory_details: true
32 | min_vel_x: 0.0
33 | min_vel_y: 0.0
34 | max_vel_x: 0.8
35 | max_vel_y: 0.0
36 | max_vel_theta: 0.8
37 | min_speed_xy: 0.01
38 | max_speed_xy: 0.8
39 | min_speed_theta: 0.01
40 | # Add high threshold velocity for turtlebot 3 issue.
41 | # https://github.com/ROBOTIS-GIT/turtlebot3_simulations/issues/75
42 | acc_lim_x: 1.0
43 | acc_lim_y: 0.0
44 | acc_lim_theta: 1.0
45 | decel_lim_x: -1.0
46 | decel_lim_y: 0.0
47 | decel_lim_theta: -1.0
48 | vx_samples: 20
49 | vy_samples: 5
50 | vtheta_samples: 10
51 | sim_time: 1.7
52 | linear_granularity: 0.05
53 | angular_granularity: 0.025
54 | transform_tolerance: 0.2
55 | xy_goal_tolerance: 0.25
56 | trans_stopped_velocity: 0.25
57 | short_circuit_trajectory_evaluation: true
58 | stateful: true
59 | critics: [RotateToGoal, Oscillation, BaseObstacle, GoalAlign, PathAlign, PathDist, GoalDist]
60 | BaseObstacle.scale: 0.02
61 | PathAlign.scale: 32.0
62 | PathAlign.forward_point_distance: 0.1
63 | GoalAlign.scale: 24.0
64 | GoalAlign.forward_point_distance: 0.1
65 | PathDist.scale: 32.0
66 | GoalDist.scale: 24.0
67 | RotateToGoal.scale: 32.0
68 | RotateToGoal.slowing_factor: 5.0
69 | RotateToGoal.lookahead_time: -1.0
70 |
71 | local_costmap:
72 | local_costmap:
73 | ros__parameters:
74 | update_frequency: 5.0
75 | publish_frequency: 2.0
76 | global_frame: odom
77 | robot_base_frame: base_footprint
78 | rolling_window: true
79 | width: 4
80 | height: 4
81 | resolution: 0.05
82 | footprint: '[[-0.32, -0.27], [-0.32, 0.27], [0.32, 0.27], [0.32, -0.27]]'
83 | footprint_padding: 0.1
84 | trinary_costmap: false
85 | robot_radius: 0.4
86 | plugins: [obstacle_layer, inflation_layer]
87 | obstacle_layer:
88 | plugin: nav2_costmap_2d::ObstacleLayer
89 | enabled: true
90 | observation_sources: scan
91 | scan:
92 | topic: /scan
93 | max_obstacle_height: 2.0
94 | clearing: true
95 | marking: true
96 | data_type: LaserScan
97 | raytrace_range: 3.0
98 | obstacle_range: 2.5
99 | inf_is_valid: true
100 | inflation_layer:
101 | plugin: nav2_costmap_2d::InflationLayer
102 | cost_scaling_factor: 1.0
103 | inflation_radius: 0.6
104 | always_send_full_costmap: true
105 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/description.launch.py.template:
--------------------------------------------------------------------------------
1 | from launch import LaunchDescription
2 | from launch.actions import IncludeLaunchDescription
3 | from launch.substitutions import PathJoinSubstitution
4 | from launch_ros.actions import Node
5 | from launch_ros.substitutions import FindPackageShare
6 |
7 |
8 | def generate_launch_description():
9 | ld = LaunchDescription()
10 |
11 | ld.add_action(IncludeLaunchDescription(
12 | PathJoinSubstitution([FindPackageShare('urdf_launch'), 'launch', 'description.launch.py']),
13 | launch_arguments={
14 | 'urdf_package': '[PACKAGE_NAME]',
15 | 'urdf_package_path': PathJoinSubstitution(['urdf', 'robot.urdf.xacro'])}.items()
16 | ))
17 |
18 | ld.add_action(Node(
19 | package='base2d_kinematics',
20 | executable='kinematics_publisher',
21 | parameters=[
22 | [FindPackageShare('[PACKAGE_NAME]'), '/config/kinematics.yaml']
23 | ],
24 | ))
25 |
26 | return ld
27 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/display.launch.py.template:
--------------------------------------------------------------------------------
1 | from launch import LaunchDescription
2 | from launch.actions import IncludeLaunchDescription
3 | from launch.substitutions import PathJoinSubstitution
4 | from launch_ros.substitutions import FindPackageShare
5 |
6 |
7 | def generate_launch_description():
8 | ld = LaunchDescription()
9 |
10 | ld.add_action(IncludeLaunchDescription(
11 | PathJoinSubstitution([FindPackageShare('urdf_launch'), 'launch', 'display.launch.py']),
12 | launch_arguments={
13 | 'urdf_package': '[PACKAGE_NAME]',
14 | 'urdf_package_path': PathJoinSubstitution(['urdf', 'robot.urdf.xacro'])}.items()
15 | ))
16 |
17 | return ld
18 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/gazebo.launch.py.template:
--------------------------------------------------------------------------------
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.substitutions import LaunchConfiguration
6 | from launch_ros.actions import Node
7 | from launch_ros.substitutions import FindPackageShare
8 |
9 |
10 | def generate_launch_description():
11 | # these are the arguments you can pass this launch file, for example paused:=true
12 | gui_arg = DeclareLaunchArgument(
13 | name='gui',
14 | default_value='true',
15 | )
16 | world_launch = IncludeLaunchDescription(
17 | [FindPackageShare('gazebo_ros'), '/launch/gzserver.launch.py'],
18 | launch_arguments={
19 | 'pause': 'true',
20 | 'verbose': 'true',
21 | 'world': [FindPackageShare('university_world'), '/worlds/a.world'],
22 | }.items(),
23 | )
24 |
25 | gzclient_launch = IncludeLaunchDescription(
26 | [FindPackageShare('gazebo_ros'), '/launch/gzclient.launch.py'],
27 | condition=IfCondition(LaunchConfiguration('gui'))
28 | )
29 |
30 | description_launch_py = IncludeLaunchDescription(
31 | [FindPackageShare('[PACKAGE_NAME]'), '/launch/description.launch.py'],
32 | )
33 |
34 | # push robot_description to factory and spawn robot in gazebo
35 | urdf_spawner_node = Node(
36 | package='gazebo_ros',
37 | executable='spawn_entity.py',
38 | name='urdf_spawner',
39 | arguments=['-topic', '/robot_description', '-entity', '[ROBOT_NAME]', '-unpause'],
40 | output='screen',
41 | )
42 |
43 | return LaunchDescription([
44 | gui_arg,
45 | world_launch,
46 | gzclient_launch,
47 | description_launch_py,
48 | urdf_spawner_node,
49 | ])
50 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/generator.launch.py.template:
--------------------------------------------------------------------------------
1 | import launch
2 | from launch_ros.actions import Node
3 | from launch_ros.substitutions import FindPackageShare
4 |
5 | EMPTY_URDF = """
6 |
7 |
8 |
9 | """
10 |
11 |
12 | def generate_launch_description():
13 | ld = launch.LaunchDescription()
14 | ld.add_action(Node(
15 | package='nav_u_robot_generator',
16 | executable='nav_u_robot_generator',
17 | parameters=[[FindPackageShare('[PACKAGE_NAME]'), '/config/variables.yaml']],
18 | ))
19 | ld.add_action(Node(
20 | package='robot_state_publisher',
21 | executable='robot_state_publisher',
22 | parameters=[{'robot_description': EMPTY_URDF}],
23 | ))
24 | ld.add_action(Node(
25 | package='joint_state_publisher',
26 | executable='joint_state_publisher',
27 | ))
28 | ld.add_action(Node(
29 | package='rviz2',
30 | executable='rviz2',
31 | arguments=['-d', [FindPackageShare('nav_u_robot_generator'), '/config/gen.rviz']],
32 | ))
33 | return ld
34 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/global.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz_common/Displays
3 | - Class: rviz_common/Views
4 | - Class: rviz_common/Time
5 | Visualization Manager:
6 | Displays:
7 | - Class: rviz_default_plugins/Grid
8 | Name: Grid
9 | Value: true
10 | - Class: rviz_default_plugins/Map
11 | Name: Map
12 | Topic:
13 | Filter size: 10
14 | Value: /global_costmap/costmap
15 | Update Topic:
16 | Value: /global_costmap/costmap_updates
17 | Value: true
18 | - Class: rviz_default_plugins/PoseWithCovariance
19 | Covariance:
20 | Value: false
21 | Head Radius: 0.2
22 | Name: Start Pose
23 | Shaft Radius: 0.1
24 | Topic:
25 | Filter size: 10
26 | Value: /initialpose
27 | Value: true
28 | - Class: rviz_default_plugins/Pose
29 | Color: 0; 255; 0
30 | Head Radius: 0.2
31 | Name: Goal Pose
32 | Shaft Radius: 0.1
33 | Topic:
34 | Filter size: 10
35 | Value: /goal_pose
36 | Value: true
37 | - Class: rviz_default_plugins/Path
38 | Color: 28; 113; 216
39 | Line Style: Billboards
40 | Line Width: 0.1
41 | Name: Path
42 | Topic:
43 | Filter size: 10
44 | Value: /plan
45 | Value: true
46 | Enabled: true
47 | Global Options:
48 | Fixed Frame: map
49 | Tools:
50 | - Class: rviz_default_plugins/MoveCamera
51 | - Class: rviz_default_plugins/SetInitialPose
52 | - Class: rviz_default_plugins/SetGoal
53 | Value: true
54 | Views:
55 | Current:
56 | Class: rviz_default_plugins/TopDownOrtho
57 | Name: Current View
58 | Scale: 20
59 | X: 30
60 | Y: 30
61 | Window Geometry:
62 | Height: 995
63 | Width: 1920
64 | X: 0
65 | Y: 24
66 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/global_plan.launch.py:
--------------------------------------------------------------------------------
1 | from ament_index_python.packages import get_package_share_path
2 | from launch.actions import DeclareLaunchArgument
3 | from launch import LaunchDescription
4 | from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
5 | from launch_ros.actions import Node
6 | from launch_ros.substitutions import FindPackageShare
7 |
8 |
9 | def generate_launch_description():
10 | nav_path = get_package_share_path('[CONFIG_PACKAGE_NAME]')
11 | ld = LaunchDescription()
12 |
13 | ld.add_action(DeclareLaunchArgument(
14 | 'map_yaml',
15 | default_value=PathJoinSubstitution(
16 | [FindPackageShare('university_world'), 'maps', 'willow-2010-02-18-0.10.yaml'])))
17 |
18 | ld.add_action(Node(
19 | package='nav2_planner',
20 | executable='planner_server',
21 | name='planner_server',
22 | output='screen',
23 | parameters=[str(nav_path / 'config' / 'planner.yaml')],
24 | ))
25 |
26 | ld.add_action(Node(
27 | package='nav2_map_server',
28 | executable='map_server',
29 | name='map_server',
30 | output='screen',
31 | parameters=[{'yaml_filename': LaunchConfiguration('map_yaml')}],
32 | ))
33 |
34 | ld.add_action(Node(
35 | package='metro_nav_demo_utils',
36 | executable='global_planner',
37 | output='screen',
38 | ))
39 |
40 | ld.add_action(Node(
41 | package='nav2_lifecycle_manager',
42 | executable='lifecycle_manager',
43 | output='screen',
44 | parameters=[{'autostart': True},
45 | {'node_names': ['planner_server', 'map_server']}]))
46 |
47 | ld.add_action(Node(
48 | package='rviz2',
49 | executable='rviz2',
50 | arguments=['-d', PathJoinSubstitution([FindPackageShare('[CONFIG_PACKAGE_NAME]'), 'config', 'global.rviz'])],
51 | output='screen'
52 | ))
53 |
54 | return ld
55 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/kinematics.yaml:
--------------------------------------------------------------------------------
1 | kinematics_publisher:
2 | ros__parameters:
3 | min_vel_x: 0.0
4 | max_vel_x: [MAX_VEL_X]
5 | max_vel_theta: [MAX_VEL_THETA]
6 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/local.rviz:
--------------------------------------------------------------------------------
1 | Panels:
2 | - Class: rviz_common/Displays
3 | Help Height: 70
4 | Name: Displays
5 | Property Tree Widget:
6 | Expanded:
7 | - /Map1/Topic1
8 | Splitter Ratio: 0.5
9 | Tree Height: 504
10 | - Class: rviz_common/Views
11 | Expanded:
12 | - /Current View1
13 | Name: Views
14 | Splitter Ratio: 0.5
15 | - Class: rviz_common/Time
16 | Experimental: false
17 | Name: Time
18 | SyncMode: 0
19 | SyncSource: LaserScan
20 | Visualization Manager:
21 | Class: ""
22 | Displays:
23 | - Alpha: 0.5
24 | Cell Size: 1
25 | Class: rviz_default_plugins/Grid
26 | Color: 160; 160; 164
27 | Enabled: true
28 | Line Style:
29 | Line Width: 0.029999999329447746
30 | Value: Lines
31 | Name: Grid
32 | Normal Cell Count: 0
33 | Offset:
34 | X: 0
35 | Y: 0
36 | Z: 0
37 | Plane: XY
38 | Plane Cell Count: 10
39 | Reference Frame:
40 | Value: true
41 | - Alpha: 0.699999988079071
42 | Binary representation: false
43 | Binary threshold: 100
44 | Class: rviz_default_plugins/Map
45 | Color Scheme: map
46 | Draw Behind: false
47 | Enabled: true
48 | Name: Map
49 | Topic:
50 | Depth: 5
51 | Durability Policy: Transient Local
52 | Filter size: 10
53 | History Policy: Keep Last
54 | Reliability Policy: Reliable
55 | Value: /map
56 | Update Topic:
57 | Depth: 5
58 | Durability Policy: Volatile
59 | History Policy: Keep Last
60 | Reliability Policy: Reliable
61 | Value: /map_updates
62 | Use Timestamp: false
63 | Value: true
64 | - Alpha: 1
65 | Class: rviz_default_plugins/RobotModel
66 | Collision Enabled: false
67 | Description File: ""
68 | Description Source: Topic
69 | Description Topic:
70 | Depth: 5
71 | Durability Policy: Volatile
72 | History Policy: Keep Last
73 | Reliability Policy: Reliable
74 | Value: /robot_description
75 | Enabled: true
76 | Links:
77 | All Links Enabled: true
78 | Expand Joint Details: false
79 | Expand Link Details: false
80 | Expand Tree: false
81 | Link Tree Style: Links in Alphabetic Order
82 | back_wheel:
83 | Alpha: 1
84 | Show Axes: false
85 | Show Trail: false
86 | Value: true
87 | base_footprint:
88 | Alpha: 1
89 | Show Axes: false
90 | Show Trail: false
91 | base_link:
92 | Alpha: 1
93 | Show Axes: false
94 | Show Trail: false
95 | Value: true
96 | left_front_wheel:
97 | Alpha: 1
98 | Show Axes: false
99 | Show Trail: false
100 | Value: true
101 | right_front_wheel:
102 | Alpha: 1
103 | Show Axes: false
104 | Show Trail: false
105 | Value: true
106 | sensor:
107 | Alpha: 1
108 | Show Axes: false
109 | Show Trail: false
110 | Value: true
111 | Mass Properties:
112 | Inertia: false
113 | Mass: false
114 | Name: RobotModel
115 | TF Prefix: ""
116 | Update Interval: 0
117 | Value: true
118 | Visual Enabled: true
119 | - Alpha: 1
120 | Autocompute Intensity Bounds: true
121 | Autocompute Value Bounds:
122 | Max Value: 10
123 | Min Value: -10
124 | Value: true
125 | Axis: Z
126 | Channel Name: intensity
127 | Class: rviz_default_plugins/LaserScan
128 | Color: 0; 255; 0
129 | Color Transformer: FlatColor
130 | Decay Time: 0
131 | Enabled: true
132 | Invert Rainbow: false
133 | Max Color: 255; 255; 255
134 | Max Intensity: 0
135 | Min Color: 0; 0; 0
136 | Min Intensity: 0
137 | Name: LaserScan
138 | Position Transformer: XYZ
139 | Selectable: true
140 | Size (Pixels): 3
141 | Size (m): 0.05000000074505806
142 | Style: Flat Squares
143 | Topic:
144 | Depth: 5
145 | Durability Policy: Volatile
146 | Filter size: 10
147 | History Policy: Keep Last
148 | Reliability Policy: Reliable
149 | Value: /scan
150 | Use Fixed Frame: true
151 | Use rainbow: true
152 | Value: true
153 | - Alpha: 0.699999988079071
154 | Binary representation: false
155 | Binary threshold: 100
156 | Class: rviz_default_plugins/Map
157 | Color Scheme: map
158 | Draw Behind: false
159 | Enabled: true
160 | Name: Global Costmap
161 | Topic:
162 | Depth: 5
163 | Durability Policy: Volatile
164 | Filter size: 10
165 | History Policy: Keep Last
166 | Reliability Policy: Reliable
167 | Value: /global_costmap/costmap
168 | Update Topic:
169 | Depth: 5
170 | Durability Policy: Volatile
171 | History Policy: Keep Last
172 | Reliability Policy: Reliable
173 | Value: /global_costmap/costmap_updates
174 | Use Timestamp: false
175 | Value: true
176 | - Alpha: 0.699999988079071
177 | Binary representation: false
178 | Binary threshold: 100
179 | Class: rviz_default_plugins/Map
180 | Color Scheme: costmap
181 | Draw Behind: false
182 | Enabled: true
183 | Name: Local Costmap
184 | Topic:
185 | Depth: 5
186 | Durability Policy: Volatile
187 | Filter size: 10
188 | History Policy: Keep Last
189 | Reliability Policy: Reliable
190 | Value: /local_costmap/costmap
191 | Update Topic:
192 | Depth: 5
193 | Durability Policy: Volatile
194 | History Policy: Keep Last
195 | Reliability Policy: Reliable
196 | Value: /local_costmap/costmap_updates
197 | Use Timestamp: false
198 | Value: true
199 | - Alpha: 1
200 | Buffer Length: 1
201 | Class: rviz_default_plugins/Path
202 | Color: 53; 132; 228
203 | Enabled: true
204 | Head Diameter: 0.30000001192092896
205 | Head Length: 0.20000000298023224
206 | Length: 0.30000001192092896
207 | Line Style: Billboards
208 | Line Width: 0.029999999329447746
209 | Name: Global Path
210 | Offset:
211 | X: 0
212 | Y: 0
213 | Z: 0
214 | Pose Color: 255; 85; 255
215 | Pose Style: None
216 | Radius: 0.029999999329447746
217 | Shaft Diameter: 0.10000000149011612
218 | Shaft Length: 0.10000000149011612
219 | Topic:
220 | Depth: 5
221 | Durability Policy: Volatile
222 | Filter size: 10
223 | History Policy: Keep Last
224 | Reliability Policy: Reliable
225 | Value: /plan
226 | Value: true
227 | - Alpha: 1
228 | Buffer Length: 1
229 | Class: rviz_default_plugins/Path
230 | Color: 25; 255; 0
231 | Enabled: true
232 | Head Diameter: 0.30000001192092896
233 | Head Length: 0.20000000298023224
234 | Length: 0.30000001192092896
235 | Line Style: Lines
236 | Line Width: 0.029999999329447746
237 | Name: Local Path
238 | Offset:
239 | X: 0
240 | Y: 0
241 | Z: 0
242 | Pose Color: 255; 85; 255
243 | Pose Style: None
244 | Radius: 0.029999999329447746
245 | Shaft Diameter: 0.10000000149011612
246 | Shaft Length: 0.10000000149011612
247 | Topic:
248 | Depth: 5
249 | Durability Policy: Volatile
250 | Filter size: 10
251 | History Policy: Keep Last
252 | Reliability Policy: Reliable
253 | Value: /local_plan
254 | Value: true
255 | - Alpha: 1
256 | Axes Length: 1
257 | Axes Radius: 0.10000000149011612
258 | Class: rviz_default_plugins/Pose
259 | Color: 255; 25; 0
260 | Enabled: true
261 | Head Length: 0.30000001192092896
262 | Head Radius: 0.10000000149011612
263 | Name: Goal Pose
264 | Shaft Length: 1
265 | Shaft Radius: 0.05000000074505806
266 | Shape: Arrow
267 | Topic:
268 | Depth: 5
269 | Durability Policy: Volatile
270 | Filter size: 10
271 | History Policy: Keep Last
272 | Reliability Policy: Reliable
273 | Value: /goal_pose
274 | Value: true
275 | Enabled: true
276 | Global Options:
277 | Background Color: 48; 48; 48
278 | Fixed Frame: map
279 | Frame Rate: 30
280 | Name: root
281 | Tools:
282 | - Class: rviz_default_plugins/MoveCamera
283 | - Class: rviz_default_plugins/SetInitialPose
284 | Covariance x: 0.25
285 | Covariance y: 0.25
286 | Covariance yaw: 0.06853891909122467
287 | Topic:
288 | Depth: 5
289 | Durability Policy: Volatile
290 | History Policy: Keep Last
291 | Reliability Policy: Reliable
292 | Value: initialpose
293 | - Class: rviz_default_plugins/SetGoal
294 | Topic:
295 | Depth: 5
296 | Durability Policy: Volatile
297 | History Policy: Keep Last
298 | Reliability Policy: Reliable
299 | Value: goal_pose
300 | Transformation:
301 | Current:
302 | Class: rviz_default_plugins/TF
303 | Value: true
304 | Views:
305 | Current:
306 | Angle: 0
307 | Class: rviz_default_plugins/TopDownOrtho
308 | Enable Stereo Rendering:
309 | Stereo Eye Separation: 0.05999999865889549
310 | Stereo Focal Distance: 1
311 | Swap Stereo Eyes: false
312 | Value: false
313 | Invert Z Axis: false
314 | Name: Current View
315 | Near Clip Distance: 0.009999999776482582
316 | Scale: 55.19443130493164
317 | Target Frame:
318 | Value: TopDownOrtho (rviz_default_plugins)
319 | X: 0
320 | Y: 0
321 | Saved: ~
322 | Window Geometry:
323 | Displays:
324 | collapsed: false
325 | Height: 995
326 | Hide Left Dock: false
327 | Hide Right Dock: false
328 | QMainWindow State: 000000ff00000000fd0000000100000000000002fb00000389fc0200000003fb000000100044006900730070006c006100790073010000003d0000027b000000c900fffffffb0000000a0056006900650077007301000002be000000c9000000a400fffffffb0000000800540069006d0065010000038d000000390000003900ffffff0000047f0000038900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
329 | Time:
330 | collapsed: false
331 | Views:
332 | collapsed: false
333 | Width: 1920
334 | X: 0
335 | Y: 24
336 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/local_plan.launch.py:
--------------------------------------------------------------------------------
1 | from ament_index_python.packages import get_package_share_path
2 | from launch.actions import DeclareLaunchArgument
3 | from launch.actions import IncludeLaunchDescription
4 | from launch import LaunchDescription
5 | from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
6 | from launch_ros.actions import Node
7 | from launch_ros.substitutions import FindPackageShare
8 |
9 |
10 | def generate_launch_description():
11 | nav_path = get_package_share_path('[CONFIG_PACKAGE_NAME]')
12 | ld = LaunchDescription()
13 |
14 | ld.add_action(IncludeLaunchDescription(
15 | [FindPackageShare('[PACKAGE_NAME]'), '/launch/gazebo.launch.py'],
16 |
17 | ))
18 |
19 | ld.add_action(DeclareLaunchArgument(
20 | 'map_yaml',
21 | default_value=PathJoinSubstitution(
22 | [FindPackageShare('university_world'), 'maps', 'willow-2010-02-18-0.10.yaml'])))
23 |
24 | ld.add_action(Node(
25 | package='nav2_planner',
26 | executable='planner_server',
27 | name='planner_server',
28 | output='screen',
29 | parameters=[str(nav_path / 'config' / 'planner.yaml')],
30 | ))
31 |
32 | ld.add_action(Node(
33 | package='nav2_map_server',
34 | executable='map_server',
35 | name='map_server',
36 | output='screen',
37 | parameters=[{'yaml_filename': LaunchConfiguration('map_yaml')}],
38 | ))
39 |
40 | ld.add_action(Node(
41 | package='nav2_controller',
42 | executable='controller_server',
43 | output='screen',
44 | parameters=[str(nav_path / 'config' / 'controller.yaml')],
45 | ))
46 |
47 | ld.add_action(Node(
48 | package='tf2_ros',
49 | executable='static_transform_publisher',
50 | arguments=['--frame-id', '/map', '--child-frame-id', '/odom'],
51 | ))
52 |
53 | ld.add_action(Node(
54 | package='nav2_lifecycle_manager',
55 | executable='lifecycle_manager',
56 | output='screen',
57 | parameters=[{'autostart': True},
58 | {'node_names': ['map_server', 'planner_server', 'controller_server']}]))
59 |
60 | ld.add_action(Node(
61 | package='rviz2',
62 | executable='rviz2',
63 | arguments=['-d', PathJoinSubstitution([FindPackageShare('[CONFIG_PACKAGE_NAME]'), 'config', 'local.rviz'])],
64 | output='screen'
65 | ))
66 |
67 | ld.add_action(Node(
68 | package='metro_nav_demo_utils',
69 | executable='simple_exec',
70 | output='screen',
71 | ))
72 |
73 | return ld
74 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/localization.launch.py:
--------------------------------------------------------------------------------
1 | from launch.actions import DeclareLaunchArgument
2 | from launch import LaunchDescription
3 | from launch.conditions import IfCondition, UnlessCondition
4 | from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
5 | from launch_ros.actions import Node, SetParameter
6 | from launch_ros.substitutions import FindPackageShare
7 | from launch.actions import IncludeLaunchDescription
8 |
9 |
10 | def generate_launch_description():
11 | ld = LaunchDescription()
12 | ld.add_action(SetParameter(name='use_sim_time', value=True))
13 |
14 | ld.add_action(DeclareLaunchArgument('amcl', default_value='false'))
15 |
16 | ld.add_action(DeclareLaunchArgument(
17 | 'map_yaml',
18 | default_value=PathJoinSubstitution(
19 | [FindPackageShare('university_world'), 'maps', 'willow-2010-02-18-0.10.yaml'])))
20 |
21 | ld.add_action(Node(
22 | package='nav2_map_server',
23 | executable='map_server',
24 | name='map_server',
25 | output='screen',
26 | parameters=[{'yaml_filename': LaunchConfiguration('map_yaml')}],
27 | ))
28 |
29 | ld.add_action(Node(
30 | package='metro_nav_demo_utils',
31 | executable='odom_to_tf',
32 | output='screen',
33 | ))
34 |
35 | ld.add_action(Node(
36 | package='nav2_amcl',
37 | executable='amcl',
38 | name='amcl',
39 | output='screen',
40 | condition=IfCondition(LaunchConfiguration('amcl')),
41 | parameters=[PathJoinSubstitution([FindPackageShare('[CONFIG_PACKAGE_NAME]'), 'config', 'amcl.yaml'])],
42 | ))
43 |
44 | ld.add_action(Node(
45 | package='nav2_lifecycle_manager',
46 | executable='lifecycle_manager',
47 | output='screen',
48 | condition=IfCondition(LaunchConfiguration('amcl')),
49 | parameters=[{'autostart': True},
50 | {'node_names': ['map_server', 'amcl']}]))
51 |
52 | ld.add_action(Node(
53 | package='nav2_lifecycle_manager',
54 | executable='lifecycle_manager',
55 | output='screen',
56 | condition=UnlessCondition(LaunchConfiguration('amcl')),
57 | parameters=[{'autostart': True},
58 | {'node_names': ['map_server']}]))
59 |
60 | ld.add_action(Node(
61 | package='tf2_ros',
62 | executable='static_transform_publisher',
63 | arguments=['--frame-id', '/map', '--child-frame-id', '/odom'],
64 | ))
65 |
66 | ld.add_action(Node(
67 | package='rviz2',
68 | executable='rviz2',
69 | arguments=['-d', PathJoinSubstitution([FindPackageShare('[CONFIG_PACKAGE_NAME]'), 'config', 'amcl.rviz'])],
70 | output='screen'
71 | ))
72 |
73 | ld.add_action(IncludeLaunchDescription(
74 | [FindPackageShare('[PACKAGE_NAME]'), '/launch/description.launch.py'],
75 | ))
76 |
77 | return ld
78 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/mapping.launch.py:
--------------------------------------------------------------------------------
1 | from launch import LaunchDescription
2 | from launch.actions import DeclareLaunchArgument
3 | from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
4 | from launch_ros.actions import Node
5 | from launch.actions import IncludeLaunchDescription
6 | from launch_ros.substitutions import FindPackageShare
7 |
8 |
9 | def generate_launch_description():
10 | ld = LaunchDescription()
11 |
12 | ld.add_action(DeclareLaunchArgument(
13 | 'use_sim_time',
14 | default_value='true',
15 | description='Use simulation/Gazebo clock'))
16 |
17 | default_rviz_config_path = PathJoinSubstitution(
18 | [FindPackageShare('[CONFIG_PACKAGE_NAME]'), 'config', 'mapping.rviz'])
19 | ld.add_action(DeclareLaunchArgument(name='rviz_config', default_value=default_rviz_config_path,
20 | description='Absolute path to rviz config file'))
21 |
22 | ld.add_action(Node(
23 | package='rviz2',
24 | executable='rviz2',
25 | parameters=[
26 | {'use_sim_time': LaunchConfiguration('use_sim_time')}
27 | ],
28 | arguments=['-d', LaunchConfiguration('rviz_config')],
29 | output='screen'
30 | ))
31 |
32 | slam_launch = IncludeLaunchDescription(
33 | PathJoinSubstitution([FindPackageShare('slam_toolbox'), 'launch', 'offline_launch.py'])
34 | )
35 | ld.add_action(slam_launch)
36 |
37 | return ld
38 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/mapping.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 | - /LaserScan1
10 | - /MarkerArray1
11 | Tree Height: 154
12 | - Class: rviz_common/Selection
13 | Name: Selection
14 | - Class: rviz_common/Tool Properties
15 | Expanded:
16 | - /2D Goal Pose1
17 | - /Publish Point1
18 | Name: Tool Properties
19 | Splitter Ratio: 0.5886790156364441
20 | - Class: rviz_common/Views
21 | Expanded:
22 | - /Current View1
23 | Name: Views
24 | - Class: rviz_common/Time
25 | Name: Time
26 | - Class: slam_toolbox::SlamToolboxPlugin
27 | Name: SlamToolboxPlugin
28 | Visualization Manager:
29 | Displays:
30 | - Class: rviz_default_plugins/Grid
31 | Name: Grid
32 | Value: true
33 | - Class: rviz_default_plugins/LaserScan
34 | Color Transformer: Intensity
35 | Max Intensity: 0
36 | Name: LaserScan
37 | Position Transformer: XYZ
38 | Selectable: false
39 | Size (m): 0.05000000074505806
40 | Style: Spheres
41 | Topic:
42 | Filter size: 10
43 | Value: /scan
44 | Value: true
45 | - Class: rviz_default_plugins/MarkerArray
46 | Name: MarkerArray
47 | Topic:
48 | Value: /slam_toolbox/graph_visualization
49 | Value: true
50 | - Binary representation: false
51 | Binary threshold: 100
52 | Class: rviz_default_plugins/Map
53 | Name: Map
54 | Topic:
55 | Filter size: 10
56 | Value: /map
57 | Update Topic:
58 | Value: /map_updates
59 | Value: true
60 | Enabled: true
61 | Global Options:
62 | Fixed Frame: map
63 | Tools:
64 | - Class: rviz_default_plugins/Interact
65 | - Class: rviz_default_plugins/MoveCamera
66 | - Class: rviz_default_plugins/Select
67 | - Class: rviz_default_plugins/FocusCamera
68 | - Class: rviz_default_plugins/Measure
69 | - Class: rviz_default_plugins/SetInitialPose
70 | Covariance x: 0.25
71 | Covariance y: 0.25
72 | Covariance yaw: 0.06853891909122467
73 | - Class: rviz_default_plugins/SetGoal
74 | - Class: rviz_default_plugins/PublishPoint
75 | Value: true
76 | Views:
77 | Current:
78 | Class: rviz_default_plugins/TopDownOrtho
79 | Name: Current View
80 | Scale: 20
81 | Window Geometry:
82 | Height: 846
83 | QMainWindow State: 000000ff00000000fd000000040000000000000217000002b0fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000125000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb000000220053006c0061006d0054006f006f006c0062006f00780050006c007500670069006e0100000168000001850000018500ffffff000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002fb00fffffffb0000000800540069006d006501000000000000045000000000000000000000017e000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
84 | SlamToolboxPlugin:
85 | collapsed: false
86 | Width: 1200
87 | X: 60
88 | Y: 61
89 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/package.xml.template:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | [PACKAGE_NAME]
5 | 0.1.0
6 |
7 | An automatically generated robot description package for [ROBOT_NAME]
8 |
9 | [AUTHOR_NAME]
10 |
11 | BSD-3-Clause
12 |
13 | [AUTHOR_NAME]
14 |
15 | ament_cmake
16 |
17 | base2d_kinematics
18 | gazebo_ros
19 | nav_u_generic_description
20 | nav_u_robot_generator
21 | rviz2
22 | rviz_common
23 | rviz_default_plugins
24 |
25 |
26 | ament_cmake
27 |
28 |
29 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/package2.xml.template:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | [CONFIG_PACKAGE_NAME]
5 | 0.1.0
6 | Nav config for [ROBOT_NAME]
7 | [AUTHOR_NAME]
8 |
9 | BSD-3-Clause
10 |
11 | [AUTHOR_NAME]
12 |
13 | ament_cmake
14 | metro_nav_demo_utils
15 | nav2_amcl
16 | nav2_lifecycle_manager
17 | nav2_map_server
18 | nav2_planner
19 | nav2_rviz_plugins
20 | rviz2
21 | rviz_common
22 | rviz_default_plugins
23 |
24 |
25 | ament_cmake
26 |
27 |
28 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/planner.yaml:
--------------------------------------------------------------------------------
1 | planner_server:
2 | ros__parameters:
3 | planner_plugins: [GridBased]
4 | GridBased:
5 | plugin: nav2_navfn_planner/NavfnPlanner
6 | allow_unknown: true
7 | Smac2D:
8 | plugin: nav2_smac_planner/SmacPlanner2D
9 | SmacHybrid:
10 | plugin: nav2_smac_planner/SmacPlannerHybrid
11 | SmacLattice:
12 | plugin: nav2_smac_planner/SmacPlannerLattice
13 | Theta:
14 | plugin: nav2_theta_star_planner/ThetaStarPlanner
15 |
16 |
17 | global_costmap:
18 | global_costmap:
19 | ros__parameters:
20 | publish_frequency: 1.0
21 | robot_base_frame: base_footprint
22 | track_unknown_space: true
23 | # track_unknown_space: false
24 | transform_tolerance: 0.5
25 | plugins: [static_layer]
26 | # plugins: [static_layer, inflation_layer]
27 | static_layer:
28 | plugin: nav2_costmap_2d::StaticLayer
29 | inflation_layer:
30 | plugin: nav2_costmap_2d::InflationLayer
31 | cost_scaling_factor: 3.0
32 | inflation_radius: 0.7
33 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/recoveries.yaml:
--------------------------------------------------------------------------------
1 | behavior_server:
2 | ros__parameters:
3 | costmap_topic: local_costmap/costmap_raw
4 | footprint_topic: local_costmap/published_footprint
5 | cycle_frequency: 10.0
6 | recovery_plugins: [spin, wait]
7 | spin:
8 | plugin: nav2_behaviors/Spin
9 | wait:
10 | plugin: nav2_behaviors/Wait
11 | global_frame: odom
12 | robot_base_frame: base_footprint
13 | transform_timeout: 0.1
14 | simulate_ahead_time: 2.0
15 | max_rotational_vel: 1.0
16 | min_rotational_vel: 0.4
17 | rotational_acc_lim: 3.2
18 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/robot.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/trees.launch.py:
--------------------------------------------------------------------------------
1 | from ament_index_python.packages import get_package_share_path
2 | from launch.actions import DeclareLaunchArgument
3 | from launch.actions import IncludeLaunchDescription
4 | from launch import LaunchDescription
5 | from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
6 | from launch_ros.actions import Node
7 | from launch_ros.substitutions import FindPackageShare
8 |
9 |
10 | def generate_launch_description():
11 | nav_path = get_package_share_path('[CONFIG_PACKAGE_NAME]')
12 | ld = LaunchDescription()
13 |
14 | ld.add_action(IncludeLaunchDescription(
15 | [FindPackageShare('[PACKAGE_NAME]'), '/launch/gazebo.launch.py'],
16 |
17 | ))
18 |
19 | ld.add_action(DeclareLaunchArgument(
20 | 'map_yaml',
21 | default_value=PathJoinSubstitution(
22 | [FindPackageShare('university_world'), 'maps', 'willow-2010-02-18-0.10.yaml'])))
23 |
24 | ld.add_action(Node(
25 | package='nav2_planner',
26 | executable='planner_server',
27 | name='planner_server',
28 | output='screen',
29 | parameters=[str(nav_path / 'config' / 'planner.yaml')],
30 | ))
31 |
32 | ld.add_action(Node(
33 | package='nav2_map_server',
34 | executable='map_server',
35 | name='map_server',
36 | output='screen',
37 | parameters=[{'yaml_filename': LaunchConfiguration('map_yaml')}],
38 | ))
39 |
40 | ld.add_action(Node(
41 | package='nav2_controller',
42 | executable='controller_server',
43 | output='screen',
44 | parameters=[str(nav_path / 'config' / 'controller.yaml')],
45 | ))
46 |
47 | ld.add_action(Node(
48 | package='tf2_ros',
49 | executable='static_transform_publisher',
50 | arguments=['--frame-id', '/map', '--child-frame-id', '/odom'],
51 | ))
52 |
53 | ld.add_action(Node(
54 | package='nav2_behaviors',
55 | executable='behavior_server',
56 | output='screen',
57 | parameters=[str(nav_path / 'config' / 'recoveries.yaml')],
58 | ))
59 |
60 | bt_path = get_package_share_path('nav2_bt_navigator')
61 | ld.add_action(Node(
62 | package='nav2_bt_navigator',
63 | executable='bt_navigator',
64 | output='screen',
65 | parameters=[str(nav_path / 'config' / 'bt_nav.yaml'), {'default_bt_xml_filename': str(
66 | bt_path / 'behavior_trees' / 'navigate_w_replanning_and_recovery.xml')}],
67 | ))
68 |
69 | ld.add_action(Node(
70 | package='nav2_lifecycle_manager',
71 | executable='lifecycle_manager',
72 | output='screen',
73 | parameters=[{'autostart': True},
74 | {'node_names':
75 | ['map_server', 'planner_server', 'controller_server', 'behavior_server', 'bt_navigator']}]))
76 |
77 | ld.add_action(Node(
78 | package='rviz2',
79 | executable='rviz2',
80 | arguments=['-d', PathJoinSubstitution([FindPackageShare('[CONFIG_PACKAGE_NAME]'), 'config', 'local.rviz'])],
81 | output='screen'
82 | ))
83 |
84 | return ld
85 |
--------------------------------------------------------------------------------
/nav_u_robot_generator/templates/variables.yaml:
--------------------------------------------------------------------------------
1 | nav_u_robot_generator:
2 | ros__parameters:
3 | robot_name: [ROBOT_NAME]
4 | author_name: [AUTHOR_NAME]
5 | author_email: [AUTHOR_EMAIL]
6 | width: [WIDTH]
7 | length: [LENGTH]
8 | height: [HEIGHT]
9 | wheel_radius: [WHEEL_RADIUS]
10 | sensor_offset: [SENSOR_OFFSET_MULT]
11 | body_color: [BODY_COLOR]
12 | wheel_color: [WHEEL_COLOR]
13 | sensor_range: [SENSOR_RANGE]
14 | sensor_samples: [SENSOR_SAMPLES]
15 | sensor_noise: [SENSOR_NOISE]
16 | sensor_type: [SENSOR_TYPE]
17 | parent_path: [PARENT_PATH]
18 | shape: [SHAPE]
19 | max_vel_x: [MAX_VEL_X]
20 | max_vel_theta: [MAX_VEL_THETA]
21 |
--------------------------------------------------------------------------------
/repos.yaml:
--------------------------------------------------------------------------------
1 | repositories:
2 | src/metro_gazebo_plugins:
3 | type: git
4 | url: https://github.com/MetroRobots/metro_gazebo_plugins.git
5 | version: workshop2023
6 | src/metro_nav:
7 | type: git
8 | url: https://github.com/MetroRobots/metro_nav.git
9 | version: main
10 | src/navigation_university:
11 | type: git
12 | url: https://github.com/MetroRobots/navigation_university.git
13 | version: main
14 |
--------------------------------------------------------------------------------
/setup.cfg:
--------------------------------------------------------------------------------
1 | [flake8]
2 | max_line_length=120
3 |
--------------------------------------------------------------------------------
/university_world/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project(university_world)
3 | find_package(ament_cmake REQUIRED)
4 | install(DIRECTORY models/
5 | DESTINATION share/${PROJECT_NAME}/models
6 | )
7 | install(DIRECTORY maps/
8 | DESTINATION share/${PROJECT_NAME}/maps
9 | )
10 | install(DIRECTORY worlds/
11 | DESTINATION share/${PROJECT_NAME}/worlds
12 | )
13 |
14 | ament_package()
15 |
--------------------------------------------------------------------------------
/university_world/maps/willow-2010-02-18-0.10.pgm:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MetroRobots/navigation_university/6d9e94020a42eda94314e03d28126a9b636c0dc2/university_world/maps/willow-2010-02-18-0.10.pgm
--------------------------------------------------------------------------------
/university_world/maps/willow-2010-02-18-0.10.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MetroRobots/navigation_university/6d9e94020a42eda94314e03d28126a9b636c0dc2/university_world/maps/willow-2010-02-18-0.10.png
--------------------------------------------------------------------------------
/university_world/maps/willow-2010-02-18-0.10.yaml:
--------------------------------------------------------------------------------
1 | image: willow-2010-02-18-0.10.pgm
2 | resolution: 0.100000
3 | origin: [0.000000, 0.000000, 0.000000]
4 | negate: 0
5 | occupied_thresh: 0.65
6 | free_thresh: 0.196
7 |
--------------------------------------------------------------------------------
/university_world/models/nowhere/meshes/a_map.stl:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/MetroRobots/navigation_university/6d9e94020a42eda94314e03d28126a9b636c0dc2/university_world/models/nowhere/meshes/a_map.stl
--------------------------------------------------------------------------------
/university_world/models/nowhere/model.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | Navigation University World
5 | 1.0
6 | model.sdf
7 |
8 |
9 | David V. Lu!!
10 | davidvlu@gmail.com
11 |
12 |
13 |
14 | NAVU
15 |
16 |
17 |
--------------------------------------------------------------------------------
/university_world/models/nowhere/model.sdf:
--------------------------------------------------------------------------------
1 |
2 |
3 | 1
4 |
5 |
6 |
7 | 0 0 0 0 0 0
8 |
9 |
10 | model://nowhere/meshes/a_map.stl
11 | 1 1 1
12 |
13 |
14 | 10
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 | 0 0 0 0 0 0
28 |
29 |
30 | model://nowhere/meshes/a_map.stl
31 | 1 1 1
32 |
33 |
34 |
35 |
39 |
40 |
41 |
42 |
43 |
44 |
--------------------------------------------------------------------------------
/university_world/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | university_world
5 | 0.0.0
6 | World for Navigation U
7 | David V. Lu!!
8 | BSD 3-clause
9 |
10 | ament_cmake
11 |
12 | gazebo_ros
13 |
14 | ament_cmake
15 |
16 |
17 |
18 |
--------------------------------------------------------------------------------
/university_world/worlds/a.world:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 | model://ground_plane
6 |
7 |
8 | model://sun
9 |
10 |
11 | false
12 |
13 |
14 | 1
15 |
16 | model://willowgarage
17 |
18 |
19 |
20 |
21 | 0 0 40 0 1.51 0
22 |
23 |
24 |
25 |
26 |
--------------------------------------------------------------------------------