Skip to content

Commit

Permalink
Feat/add gps launch (#14)
Browse files Browse the repository at this point in the history
* include gps launch

Signed-off-by: stevedan <[email protected]>

* working version

Signed-off-by: stevedan <[email protected]>

* lintering

Signed-off-by: stevedan <[email protected]>

* Update nav2_minimal_tb3_sim/configs/turtlebot3_waffle_gps_bridge.yaml

Co-authored-by: Steve Macenski <[email protected]>
Signed-off-by: Stevedan Ogochukwu Omodolor <[email protected]>

* Change naming

Signed-off-by: stevedan <[email protected]>

* change artifat from v1 to v4

Signed-off-by: stevedan <[email protected]>

---------

Signed-off-by: stevedan <[email protected]>
Signed-off-by: Stevedan Ogochukwu Omodolor <[email protected]>
Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
stevedanomodolor and SteveMacenski authored Oct 1, 2024
1 parent f4eefd0 commit f0eeedb
Show file tree
Hide file tree
Showing 6 changed files with 1,114 additions and 1 deletion.
2 changes: 1 addition & 1 deletion .github/workflows/test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ jobs:
with:
import-token: ${{ secrets.GITHUB_TOKEN }}
target-ros2-distro: ${{ matrix.ros_distro }}
- uses: actions/upload-artifact@v1
- uses: actions/upload-artifact@v4
with:
name: colcon-logs
path: ros_ws/log
50 changes: 50 additions & 0 deletions nav2_minimal_tb3_sim/configs/turtlebot3_waffle_gps_bridge.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
# replace clock_bridge
- topic_name: "/clock"
ros_type_name: "rosgraph_msgs/msg/Clock"
gz_type_name: "gz.msgs.Clock"
direction: GZ_TO_ROS

# no equivalent in TB3 - add
- topic_name: "joint_states"
ros_type_name: "sensor_msgs/msg/JointState"
gz_type_name: "gz.msgs.Model"
direction: GZ_TO_ROS

# replace odom_bridge - check gz topic name
# gz topic published by DiffDrive plugin
- topic_name: "odom"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS

# replace odom_tf_bridge - check gz and ros topic names
# gz topic published by DiffDrive plugin
# prefix ros2 topic with gz
- topic_name: "tf"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS

# replace imu_bridge - check gz topic name
- topic_name: "imu/data"
ros_type_name: "sensor_msgs/msg/Imu"
gz_type_name: "gz.msgs.IMU"
direction: GZ_TO_ROS

# replace lidar_bridge
- topic_name: "scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "gz.msgs.LaserScan"
direction: GZ_TO_ROS

# replace cmd_vel_bridge
- topic_name: "cmd_vel"
ros_type_name: "geometry_msgs/msg/Twist"
gz_type_name: "gz.msgs.Twist"
direction: ROS_TO_GZ

# replace navsat_bridge - check gz topic name
- topic_name: "gps/fix"
ros_type_name: "sensor_msgs/msg/NavSatFix"
gz_type_name: "gz.msgs.NavSat"
direction: GZ_TO_ROS
132 changes: 132 additions & 0 deletions nav2_minimal_tb3_sim/launch/spawn_tb3_gps.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,132 @@
# Copyright (C) 2023 Open Source Robotics Foundation
# Copyright (C) 2024 Open Navigation LLC
#
# 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 pathlib import Path


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.substitutions import LaunchConfiguration
from launch.substitutions.command import Command
from launch.substitutions.find_executable import FindExecutable

from launch_ros.actions import Node


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

namespace = LaunchConfiguration('namespace')
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_robot_name_cmd = DeclareLaunchArgument(
'robot_name',
default_value='turtlebot3_waffle_gps',
description='name of the robot',
)

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

bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
namespace=namespace,
parameters=[
{
'config_file': os.path.join(
bringup_dir, 'configs', 'turtlebot3_waffle_gps_bridge.yaml'
),
'expand_gz_topic_names': True,
'use_sim_time': True,
}
],
output='screen',
)

spawn_model = Node(
package='ros_gz_sim',
executable='create',
output='screen',
namespace=namespace,
arguments=[
'-name',
robot_name,
'-string',
Command(
[
FindExecutable(name='xacro'),
' ',
'namespace:=',
LaunchConfiguration('namespace'),
' ',
robot_sdf,
]
),
'-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(bringup_dir, 'models')
)
set_env_vars_resources2 = AppendEnvironmentVariable(
'GZ_SIM_RESOURCE_PATH', str(Path(os.path.join(bringup_dir)).parent.resolve())
)

# 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(set_env_vars_resources)
ld.add_action(set_env_vars_resources2)

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

0 comments on commit f0eeedb

Please sign in to comment.