Skip to content

Commit 0220efd

Browse files
Adding TB3 minimal simulation (#7)
* adding prototype for TB3 * working BT3
1 parent e90b54c commit 0220efd

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

58 files changed

+3844
-129
lines changed

README.md

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
1-
# nav2_minimal_turtlebot4_simulation
1+
# nav2_minimal_turtlebot_simulation
22

3-
A minimum description & simulation of the TB4 using standard ROS-GZ tools for ``nav2_bringup`` and user example.
3+
A minimum description & simulation of the TB3/TB4 using standard ROS-GZ tools for ``nav2_bringup`` and user example.
44

55
It is largely ROS distribution agnostic, using launch files and URDFs so it should be easy to use for any ROS 2 distribution & release into Rolling for all future ones.
6+

nav2_min_tb4_sim/README.md

Lines changed: 0 additions & 86 deletions
This file was deleted.
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
cmake_minimum_required(VERSION 3.8)
2+
project(nav2_minimal_tb3_sim)
3+
4+
# find dependencies
5+
find_package(ament_cmake REQUIRED)
6+
7+
install(
8+
DIRECTORY configs launch worlds urdf models
9+
DESTINATION share/${PROJECT_NAME}
10+
)
11+
12+
if(BUILD_TESTING)
13+
find_package(ament_lint_auto REQUIRED)
14+
ament_lint_auto_find_test_dependencies()
15+
endif()
16+
17+
ament_package()

nav2_minimal_tb3_sim/README.md

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
# Nav2 Minimal Turtlebot3 Simulation
2+
3+
This is a minimum simulation for the Turtlebot3 for use with Nav2. This is setup to strip out external dependencies and complexities to the bare minimum needed for simulating the robot for Nav2's bringup which hopefully will not require changes from distribution-to-distribution.
Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
# replace clock_bridge
2+
- ros_topic_name: "clock"
3+
gz_topic_name: "/clock"
4+
ros_type_name: "rosgraph_msgs/msg/Clock"
5+
gz_type_name: "gz.msgs.Clock"
6+
direction: GZ_TO_ROS
7+
8+
# no equivalent in TB3 - add
9+
- ros_topic_name: "joint_states"
10+
gz_topic_name: "joint_states"
11+
ros_type_name: "sensor_msgs/msg/JointState"
12+
gz_type_name: "gz.msgs.Model"
13+
direction: GZ_TO_ROS
14+
15+
# replace odom_bridge - check gz topic name
16+
# gz topic published by DiffDrive plugin
17+
- ros_topic_name: "odom"
18+
gz_topic_name: "/odom"
19+
ros_type_name: "nav_msgs/msg/Odometry"
20+
gz_type_name: "gz.msgs.Odometry"
21+
direction: GZ_TO_ROS
22+
23+
# replace odom_tf_bridge - check gz and ros topic names
24+
# gz topic published by DiffDrive plugin
25+
# prefix ros2 topic with gz
26+
- ros_topic_name: "tf"
27+
gz_topic_name: "/tf"
28+
ros_type_name: "tf2_msgs/msg/TFMessage"
29+
gz_type_name: "gz.msgs.Pose_V"
30+
direction: GZ_TO_ROS
31+
32+
# replace imu_bridge - check gz topic name
33+
- ros_topic_name: "imu"
34+
gz_topic_name: "/imu"
35+
ros_type_name: "sensor_msgs/msg/Imu"
36+
gz_type_name: "gz.msgs.IMU"
37+
direction: GZ_TO_ROS
38+
39+
# replace lidar_bridge
40+
- ros_topic_name: "scan"
41+
gz_topic_name: "/scan"
42+
ros_type_name: "sensor_msgs/msg/LaserScan"
43+
gz_type_name: "gz.msgs.LaserScan"
44+
direction: GZ_TO_ROS
45+
46+
# replace cmd_vel_bridge
47+
- ros_topic_name: "cmd_vel"
48+
gz_topic_name: "/cmd_vel"
49+
ros_type_name: "geometry_msgs/msg/Twist"
50+
gz_type_name: "gz.msgs.Twist"
51+
direction: ROS_TO_GZ
Lines changed: 109 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,109 @@
1+
# Copyright (C) 2023 Open Source Robotics Foundation
2+
# Copyright (C) 2024 Open Navigation LLC
3+
#
4+
# Licensed under the Apache License, Version 2.0 (the "License");
5+
# you may not use this file except in compliance with the License.
6+
# You may obtain a copy of the License at
7+
#
8+
# http://www.apache.org/licenses/LICENSE-2.0
9+
#
10+
# Unless required by applicable law or agreed to in writing, software
11+
# distributed under the License is distributed on an "AS IS" BASIS,
12+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13+
# See the License for the specific language governing permissions and
14+
# limitations under the License.
15+
16+
import os
17+
from pathlib import Path
18+
19+
from ament_index_python.packages import get_package_share_directory
20+
21+
from launch import LaunchDescription
22+
from launch.actions import AppendEnvironmentVariable
23+
from launch.actions import DeclareLaunchArgument
24+
from launch.conditions import IfCondition
25+
from launch.substitutions import LaunchConfiguration
26+
27+
from launch_ros.actions import Node
28+
29+
30+
def generate_launch_description():
31+
bringup_dir = get_package_share_directory('nav2_minimal_tb3_sim')
32+
33+
namespace = LaunchConfiguration('namespace')
34+
use_simulator = LaunchConfiguration('use_simulator')
35+
robot_name = LaunchConfiguration('robot_name')
36+
robot_sdf = LaunchConfiguration('robot_sdf')
37+
pose = {'x': LaunchConfiguration('x_pose', default='-2.00'),
38+
'y': LaunchConfiguration('y_pose', default='-0.50'),
39+
'z': LaunchConfiguration('z_pose', default='0.01'),
40+
'R': LaunchConfiguration('roll', default='0.00'),
41+
'P': LaunchConfiguration('pitch', default='0.00'),
42+
'Y': LaunchConfiguration('yaw', default='0.00')}
43+
44+
# Declare the launch arguments
45+
declare_namespace_cmd = DeclareLaunchArgument(
46+
'namespace',
47+
default_value='',
48+
description='Top-level namespace')
49+
50+
declare_use_simulator_cmd = DeclareLaunchArgument(
51+
'use_simulator',
52+
default_value='True',
53+
description='Whether to start the simulator')
54+
55+
declare_robot_name_cmd = DeclareLaunchArgument(
56+
'robot_name',
57+
default_value='turtlebot3_waffle',
58+
description='name of the robot')
59+
60+
declare_robot_sdf_cmd = DeclareLaunchArgument(
61+
'robot_sdf',
62+
default_value=os.path.join(bringup_dir, 'urdf', 'gz_waffle.sdf'),
63+
description='Full path to robot sdf file to spawn the robot in gazebo')
64+
65+
bridge = Node(
66+
package='ros_gz_bridge',
67+
executable='parameter_bridge',
68+
parameters=[
69+
{
70+
'config_file': os.path.join(
71+
bringup_dir, 'configs', 'turtlebot3_waffle_bridge.yaml'
72+
),
73+
}
74+
],
75+
output='screen',
76+
)
77+
78+
spawn_model = Node(
79+
condition=IfCondition(use_simulator),
80+
package='ros_gz_sim',
81+
executable='create',
82+
output='screen',
83+
arguments=[
84+
'-entity', robot_name,
85+
'-file', robot_sdf,
86+
'-robot_namespace', namespace,
87+
'-x', pose['x'], '-y', pose['y'], '-z', pose['z'],
88+
'-R', pose['R'], '-P', pose['P'], '-Y', pose['Y']]
89+
)
90+
91+
set_env_vars_resources = AppendEnvironmentVariable(
92+
'GZ_SIM_RESOURCE_PATH', os.path.join(bringup_dir, 'models'))
93+
set_env_vars_resources2 = AppendEnvironmentVariable(
94+
'GZ_SIM_RESOURCE_PATH',
95+
str(Path(os.path.join(bringup_dir)).parent.resolve()))
96+
97+
# Create the launch description and populate
98+
ld = LaunchDescription()
99+
ld.add_action(declare_namespace_cmd)
100+
ld.add_action(declare_robot_name_cmd)
101+
ld.add_action(declare_robot_sdf_cmd)
102+
ld.add_action(declare_use_simulator_cmd)
103+
104+
ld.add_action(set_env_vars_resources)
105+
ld.add_action(set_env_vars_resources2)
106+
107+
ld.add_action(bridge)
108+
ld.add_action(spawn_model)
109+
return ld

0 commit comments

Comments
 (0)