Skip to content

Commit

Permalink
Initial support to the new Gazebo (#3634)
Browse files Browse the repository at this point in the history
* Initial support to the new Gazebo

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Added feedback

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Fixed build

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Added feeback

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Fixed physics tag

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Fixed physics tag

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Fix copyright and urdf

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* min range cannot be zero

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Simplify files

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Added feedback

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Added feedback

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Fix

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Try to reduce load

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Removed cast shadows

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Use Gazebo plugins instead of gz_ros2_control

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* update dependency

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Removed dependency

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Removed ros2_control and use ogre

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Use param file to configure bridge

Signed-off-by: Alejandro Hernández Cordero <[email protected]>

* Use sdf model and change to ogre instead of ogre2 for sensors

Signed-off-by: Addisu Z. Taddese <[email protected]>

* Support Garden and later, performance improvements

Signed-off-by: Addisu Z. Taddese <[email protected]>

* Use xacro for world file (#2)

Signed-off-by: Addisu Z. Taddese <[email protected]>

* Reviewer feedback

Signed-off-by: Addisu Z. Taddese <[email protected]>

* Add comment explaining temp file

Signed-off-by: Addisu Z. Taddese <[email protected]>

* Fix linter

Signed-off-by: Addisu Z. Taddese <[email protected]>

* Update nav2_bringup/worlds/gz_world_only.sdf.xacro

Co-authored-by: Addisu Z. Taddese <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>

---------

Signed-off-by: Alejandro Hernández Cordero <[email protected]>
Signed-off-by: Addisu Z. Taddese <[email protected]>
Signed-off-by: Addisu Z. Taddese <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Co-authored-by: Addisu Z. Taddese <[email protected]>
Co-authored-by: Addisu Z. Taddese <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
4 people authored Jun 5, 2024
1 parent c5c9b98 commit bc6e3b2
Show file tree
Hide file tree
Showing 6 changed files with 1,047 additions and 0 deletions.
106 changes: 106 additions & 0 deletions nav2_bringup/launch/tb3_gz_robot_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
# Copyright (C) 2023 Open Source Robotics Foundation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from ament_index_python.packages import get_package_share_directory

from launch import LaunchDescription
from launch.actions import AppendEnvironmentVariable
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition
from launch.substitutions import LaunchConfiguration

from launch_ros.actions import Node


def generate_launch_description():
bringup_dir = get_package_share_directory('nav2_bringup')

namespace = LaunchConfiguration('namespace')
use_simulator = LaunchConfiguration('use_simulator')
robot_name = LaunchConfiguration('robot_name')
robot_sdf = LaunchConfiguration('robot_sdf')
pose = {'x': LaunchConfiguration('x_pose', default='-2.00'),
'y': LaunchConfiguration('y_pose', default='-0.50'),
'z': LaunchConfiguration('z_pose', default='0.01'),
'R': LaunchConfiguration('roll', default='0.00'),
'P': LaunchConfiguration('pitch', default='0.00'),
'Y': LaunchConfiguration('yaw', default='0.00')}

# Declare the launch arguments
declare_namespace_cmd = DeclareLaunchArgument(
'namespace',
default_value='',
description='Top-level namespace')

declare_use_simulator_cmd = DeclareLaunchArgument(
'use_simulator',
default_value='True',
description='Whether to start the simulator')

declare_robot_name_cmd = DeclareLaunchArgument(
'robot_name',
default_value='turtlebot3_waffle',
description='name of the robot')

declare_robot_sdf_cmd = DeclareLaunchArgument(
'robot_sdf',
default_value=os.path.join(bringup_dir, 'worlds', 'gz_waffle.sdf'),
description='Full path to robot sdf file to spawn the robot in gazebo')

pkg_nav2_bringup = get_package_share_directory('nav2_bringup')
bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
parameters=[
{
'config_file': os.path.join(
pkg_nav2_bringup, 'params', 'turtlebot3_waffle_bridge.yaml'
),
}
],
output='screen',
)

spawn_model = Node(
condition=IfCondition(use_simulator),
package='ros_gz_sim',
executable='create',
output='screen',
arguments=[
'-entity', robot_name,
'-file', robot_sdf,
'-robot_namespace', namespace,
'-x', pose['x'], '-y', pose['y'], '-z', pose['z'],
'-R', pose['R'], '-P', pose['P'], '-Y', pose['Y']]
)

set_env_vars_resources = AppendEnvironmentVariable(
'GZ_SIM_RESOURCE_PATH',
os.path.join(get_package_share_directory('turtlebot3_gazebo'),
'models'))

# Create the launch description and populate
ld = LaunchDescription()
ld.add_action(declare_namespace_cmd)
ld.add_action(declare_robot_name_cmd)
ld.add_action(declare_robot_sdf_cmd)
ld.add_action(declare_use_simulator_cmd)

ld.add_action(set_env_vars_resources)

ld.add_action(bridge)
ld.add_action(spawn_model)
return ld
Loading

0 comments on commit bc6e3b2

Please sign in to comment.