Skip to content

Commit

Permalink
Added support for gz harmonic
Browse files Browse the repository at this point in the history
  • Loading branch information
harrisonseby authored and D-1shu committed Jun 13, 2024
1 parent 0916770 commit f48c234
Show file tree
Hide file tree
Showing 8 changed files with 432 additions and 31 deletions.
55 changes: 55 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,7 @@ This repository contains a Gazebo simulation for a differential drive robot, equ
1. [ROS Noetic + Gazebo Classic 11 (branch ros1)](#noetic--classic-ubuntu-2004)
2. [ROS2 Humble + Gazebo Classic 11 (branch ros2)](#humble--classic-ubuntu-2204)
3. [ROS2 Humble + Gazebo Fortress (branch ros2)](#humble--fortress-ubuntu-2204)
4. [ROS2 Humble + Gazebo Harmonic (branch ros2)](#humble--harmonic-ubuntu-2204)

Each of the following sections describes depedencies, build and run instructions for each of the above combinations

Expand Down Expand Up @@ -133,6 +134,58 @@ colcon build --packages-select bcr_bot

### Run

To launch the robot in Gazebo,
```bash
ros2 launch bcr_bot ign.launch.py
```
To view in rviz,
```bash
ros2 launch bcr_bot rviz.launch.py
```

### Configuration

The launch file accepts multiple launch arguments,
```bash
ros2 launch bcr_bot ign.launch.py \
camera_enabled:=True \
stereo_camera_enabled:=False \
two_d_lidar_enabled:=True \
position_x:=0.0 \
position_y:=0.0 \
orientation_yaw:=0.0 \
odometry_source:=world \
world_file:=small_warehouse.sdf
```
**Note:** To use stereo_image_proc with the stereo images excute following command:
```bash
ros2 launch stereo_image_proc stereo_image_proc.launch.py left_namespace:=bcr_bot/stereo_camera/left right_namespace:=bcr_bot/stereo_camera/right
```

## Humble + Harmonic (Ubuntu 22.04)

### Dependencies

In addition to ROS2 Humble and [Gazebo Harmonic installations](https://gazebosim.org/docs/harmonic/install_ubuntu), we need to manually install interfaces between ROS2 and Gazebo sim as follows,

```bash
sudo apt-get install ros-humble-ros-gzharmonic
```
Remainder of the dependencies can be installed with [rosdep](http://wiki.ros.org/rosdep)

```bash
# From the root directory of the workspace. This will install everything mentioned in package.xml
rosdep install --from-paths src --ignore-src -r -y
```

### Build

```bash
colcon build --packages-select bcr_bot
```

### Run

To launch the robot in Gazebo,
```bash
ros2 launch bcr_bot gz.launch.py
Expand Down Expand Up @@ -160,6 +213,8 @@ ros2 launch bcr_bot gz.launch.py \
```bash
ros2 launch stereo_image_proc stereo_image_proc.launch.py left_namespace:=bcr_bot/stereo_camera/left right_namespace:=bcr_bot/stereo_camera/right
```
**Warning:** `gz-harmonic` cannot be installed alongside gazebo-classic (eg. gazebo11) since both use the `gz` command line tool.

### Simulation and Visualization
1. Gz Sim (Ignition Gazebo) (small_warehouse World):
![](res/gz.jpg)
Expand Down
30 changes: 15 additions & 15 deletions launch/bcr_bot_gz_spawn.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,20 +72,20 @@ def generate_launch_description():
package="ros_gz_bridge",
executable="parameter_bridge",
arguments=[
"/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist",
"/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock",
"/odom@nav_msgs/msg/Odometry[ignition.msgs.Odometry",
"/tf@tf2_msgs/msg/TFMessage[ignition.msgs.Pose_V",
"/scan@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
"/kinect_camera@sensor_msgs/msg/Image[ignition.msgs.Image",
"/stereo_camera/left/image_raw@sensor_msgs/msg/Image[ignition.msgs.Image",
"stereo_camera/right/image_raw@sensor_msgs/msg/Image[ignition.msgs.Image",
"kinect_camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"stereo_camera/left/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"stereo_camera/right/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"/kinect_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked",
"/imu@sensor_msgs/msg/Imu[ignition.msgs.IMU",
"/world/default/model/bcr_bot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model"
"/cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist",
"/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
"/odom@nav_msgs/msg/Odometry[gz.msgs.Odometry",
"/tf@tf2_msgs/msg/TFMessage[gz.msgs.Pose_V",
"/scan@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan",
"/kinect_camera@sensor_msgs/msg/Image[gz.msgs.Image",
"/stereo_camera/left/image_raw@sensor_msgs/msg/Image[gz.msgs.Image",
"stereo_camera/right/image_raw@sensor_msgs/msg/Image[gz.msgs.Image",
"kinect_camera/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo",
"stereo_camera/left/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo",
"stereo_camera/right/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo",
"/kinect_camera/points@sensor_msgs/msg/PointCloud2[gz.msgs.PointCloudPacked",
"/imu@sensor_msgs/msg/Imu[gz.msgs.IMU",
"/world/default/model/bcr_bot/joint_state@sensor_msgs/msg/JointState[gz.msgs.Model"
],
remappings=[
('/world/default/model/bcr_bot/joint_state', 'bcr_bot/joint_states'),
Expand Down Expand Up @@ -126,4 +126,4 @@ def generate_launch_description():
DeclareLaunchArgument("odometry_source", default_value="world"),
robot_state_publisher,
gz_spawn_entity, transform_publisher, gz_ros2_bridge
])
])
129 changes: 129 additions & 0 deletions launch/bcr_bot_ign_spawn.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
#!/usr/bin/python3

from os.path import join
from xacro import parse, process_doc

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, Command

from launch_ros.actions import Node

from ament_index_python.packages import get_package_share_directory

def get_xacro_to_doc(xacro_file_path, mappings):
doc = parse(open(xacro_file_path))
process_doc(doc, mappings=mappings)
return doc

def generate_launch_description():

bcr_bot_path = get_package_share_directory("bcr_bot")
position_x = LaunchConfiguration("position_x")
position_y = LaunchConfiguration("position_y")
orientation_yaw = LaunchConfiguration("orientation_yaw")
camera_enabled = LaunchConfiguration("camera_enabled", default=True)
stereo_camera_enabled = LaunchConfiguration("stereo_camera_enabled", default=False)
two_d_lidar_enabled = LaunchConfiguration("two_d_lidar_enabled", default=True)
odometry_source = LaunchConfiguration("odometry_source")

# robot_description_content = get_xacro_to_doc(
# join(bcr_bot_path, "urdf", "bcr_bot.xacro"),
# {"sim_gz": "true",
# "two_d_lidar_enabled": "true",
# "conveyor_enabled": "false",
# "camera_enabled": "true"
# }
# ).toxml()

robot_state_publisher = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
name="robot_state_publisher",
parameters=[
{'robot_description': Command( \
['xacro ', join(bcr_bot_path, 'urdf/bcr_bot.xacro'),
' camera_enabled:=', camera_enabled,
' stereo_camera_enabled:=', stereo_camera_enabled,
' two_d_lidar_enabled:=', two_d_lidar_enabled,
' odometry_source:=', odometry_source,
' sim_ign:=', "true"
])}],
remappings=[
('/joint_states', 'bcr_bot/joint_states'),
]
)

gz_spawn_entity = Node(
package="ros_gz_sim",
executable="create",
arguments=[
"-topic", "/robot_description",
"-name", "bcr_bot",
"-allow_renaming", "true",
"-z", "0.28",
"-x", position_x,
"-y", position_y,
"-Y", orientation_yaw
]
)

gz_ros2_bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
arguments=[
"/cmd_vel@geometry_msgs/msg/Twist@ignition.msgs.Twist",
"/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock",
"/odom@nav_msgs/msg/Odometry[ignition.msgs.Odometry",
"/tf@tf2_msgs/msg/TFMessage[ignition.msgs.Pose_V",
"/scan@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
"/kinect_camera@sensor_msgs/msg/Image[ignition.msgs.Image",
"/stereo_camera/left/image_raw@sensor_msgs/msg/Image[ignition.msgs.Image",
"stereo_camera/right/image_raw@sensor_msgs/msg/Image[ignition.msgs.Image",
"kinect_camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"stereo_camera/left/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"stereo_camera/right/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"/kinect_camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked",
"/imu@sensor_msgs/msg/Imu[ignition.msgs.IMU",
"/world/default/model/bcr_bot/joint_state@sensor_msgs/msg/JointState[ignition.msgs.Model"
],
remappings=[
('/world/default/model/bcr_bot/joint_state', 'bcr_bot/joint_states'),
('/odom', 'bcr_bot/odom'),
('/scan', 'bcr_bot/scan'),
('/kinect_camera', 'bcr_bot/kinect_camera'),
('/stereo_camera/left/image_raw', 'bcr_bot/stereo_camera/left/image_raw'),
('/stereo_camera/right/image_raw', 'bcr_bot/stereo_camera/right/image_raw'),
('/imu', 'bcr_bot/imu'),
('/cmd_vel', 'bcr_bot/cmd_vel'),
('kinect_camera/camera_info', 'bcr_bot/kinect_camera/camera_info'),
('stereo_camera/left/camera_info', 'bcr_bot/stereo_camera/left/camera_info'),
('stereo_camera/right/camera_info', 'bcr_bot/stereo_camera/right/camera_info'),
('/kinect_camera/points', 'bcr_bot/kinect_camera/points'),
]
)

transform_publisher = Node(
package="tf2_ros",
executable="static_transform_publisher",
arguments = ["--x", "0.0",
"--y", "0.0",
"--z", "0.0",
"--yaw", "0.0",
"--pitch", "0.0",
"--roll", "0.0",
"--frame-id", "kinect_camera",
"--child-frame-id", "bcr_bot/base_footprint/kinect_camera"]
)

return LaunchDescription([
DeclareLaunchArgument("camera_enabled", default_value = camera_enabled),
DeclareLaunchArgument("stereo_camera_enabled", default_value = stereo_camera_enabled),
DeclareLaunchArgument("two_d_lidar_enabled", default_value = two_d_lidar_enabled),
DeclareLaunchArgument("position_x", default_value="0.0"),
DeclareLaunchArgument("position_y", default_value="0.0"),
DeclareLaunchArgument("orientation_yaw", default_value="0.0"),
DeclareLaunchArgument("odometry_source", default_value="world"),
robot_state_publisher,
gz_spawn_entity, transform_publisher, gz_ros2_bridge
])
6 changes: 3 additions & 3 deletions launch/gz.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,15 @@ def generate_launch_description():
return LaunchDescription([

AppendEnvironmentVariable(
name='IGN_GAZEBO_RESOURCE_PATH',
name='GZ_SIM_RESOURCE_PATH',
value=join(bcr_bot_path, "worlds")),

AppendEnvironmentVariable(
name='IGN_GAZEBO_RESOURCE_PATH',
name='GZ_SIM_RESOURCE_PATH',
value=join(bcr_bot_path, "models")),

DeclareLaunchArgument("use_sim_time", default_value=use_sim_time),
DeclareLaunchArgument("world_file", default_value=world_file),

gz_sim, spawn_bcr_bot_node
])
])
48 changes: 48 additions & 0 deletions launch/ign.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
#!/usr/bin/python3

from os.path import join
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration,PythonExpression
from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python.packages import get_package_share_directory
from launch.actions import AppendEnvironmentVariable


def generate_launch_description():
use_sim_time = LaunchConfiguration("use_sim_time", default=True)

bcr_bot_path = get_package_share_directory("bcr_bot")
world_file = LaunchConfiguration("world_file", default = join(bcr_bot_path, "worlds", "small_warehouse.sdf"))
gz_sim_share = get_package_share_directory("ros_gz_sim")

gz_sim = IncludeLaunchDescription(
PythonLaunchDescriptionSource(join(gz_sim_share, "launch", "gz_sim.launch.py")),
launch_arguments={
"gz_args" : PythonExpression(["'", world_file, " -r'"])

}.items()
)

spawn_bcr_bot_node = IncludeLaunchDescription(
PythonLaunchDescriptionSource(join(bcr_bot_path, "launch", "bcr_bot_ign_spawn.launch.py")),
launch_arguments={
# Pass any arguments if your spawn.launch.py requires
}.items()
)

return LaunchDescription([

AppendEnvironmentVariable(
name='IGN_GAZEBO_RESOURCE_PATH',
value=join(bcr_bot_path, "worlds")),

AppendEnvironmentVariable(
name='IGN_GAZEBO_RESOURCE_PATH',
value=join(bcr_bot_path, "models")),

DeclareLaunchArgument("use_sim_time", default_value=use_sim_time),
DeclareLaunchArgument("world_file", default_value=world_file),

gz_sim, spawn_bcr_bot_node
])
5 changes: 5 additions & 0 deletions urdf/bcr_bot.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
<xacro:arg name="conveyor_enabled" default="false"/>
<xacro:arg name="ground_truth_frame" default="map"/>
<xacro:arg name="sim_gazebo" default="false" />
<xacro:arg name="sim_ign" default="false" />
<xacro:arg name="sim_gz" default="false" />
<xacro:arg name="odometry_source" default="world" />

Expand All @@ -58,6 +59,10 @@
<xacro:include filename="$(find bcr_bot)/urdf/gazebo.xacro"/>
</xacro:if>

<xacro:if value="$(arg sim_ign)">
<xacro:include filename="$(find bcr_bot)/urdf/ign.xacro"/>
</xacro:if>

<xacro:if value="$(arg sim_gz)">
<xacro:include filename="$(find bcr_bot)/urdf/gz.xacro"/>
</xacro:if>
Expand Down
Loading

0 comments on commit f48c234

Please sign in to comment.