README
New BCR Robot
https://github.com/blackcoffeerobotics/bcr_bot/assets/13151010/0fc570a3-c70c-415b-8222-b9573d5911c8
About
This repository contains a Gazebo and Isaac Sim simulation for a differential drive robot, equipped with an IMU, a depth camera, stereo camera and a 2D LiDAR. The primary contriution of this project is to support multiple ROS and Gazebo distros. Currently, the project supports the following versions -
Each of the following sections describes depedencies, build and run instructions for each of the above combinations
Noetic + Classic (Ubuntu 20.04)
Dependencies
In addition to ROS1 Noetic and Gazebo Classic installations, the dependencies can be installed with rosdep
# From the root directory of the workspace. This will install everything mentioned in package.xml
rosdep install --from-paths src --ignore-src -r -y
Source Build
catkin build --packages-select bcr_bot
Binary Install
To install BCR bot in the binaries:
sudo apt-get install ros-noetic-bcr-bot
Run
To launch the robot in Gazebo,
roslaunch bcr_bot gazebo.launch
To view in rviz,
roslaunch bcr_bot rviz.launch
Configuration
The launch file accepts multiple launch arguments,
roslaunch bcr_bot gazebo.launch
camera_enabled:=True \
two_d_lidar_enabled:=True \
position_x:=0.0 \
position_y:=0.0 \
orientation_yaw:=0.0 \
odometry_source:=world \
world_file:=small_warehouse.world \
robot_namespace:="bcr_bot"
Note: To use stereo_image_proc with the stereo images excute following command:
ROS_NAMESPACE=bcr_bot/stereo_camera rosrun stereo_image_proc stereo_image_proc
Humble + Classic (Ubuntu 22.04)
Dependencies
In addition to ROS2 Humble and Gazebo Classic installations, we need to manually install gazebo_ros_pkgs (since the same branch supports Classic and Fortress)
sudo apt-get install ros-humble-gazebo-ros-pkgs
Remainder of the dependencies can be installed with rosdep
# From the root directory of the workspace. This will install everything mentioned in package.xml
rosdep install --from-paths src --ignore-src -r -y
Source Build
colcon build --packages-select bcr_bot
Binary Install
To install BCR bot in the binaries:
sudo apt-get install ros-humble-bcr-bot
Run
To launch the robot in Gazebo,
ros2 launch bcr_bot gazebo.launch.py
To view in rviz,
ros2 launch bcr_bot rviz.launch.py
Configuration
The launch file accepts multiple launch arguments,
ros2 launch bcr_bot gazebo.launch.py \
camera_enabled:=True \
two_d_lidar_enabled:=True \
stereo_camera_enabled:=False \
position_x:=0.0 \
position_y:=0.0 \
orientation_yaw:=0.0 \
odometry_source:=world \
world_file:=small_warehouse.sdf \
robot_namespace:="bcr_bot"
Note: To use stereo_image_proc with the stereo images excute following command:
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 + Fortress (Ubuntu 22.04)
Dependencies
In addition to ROS2 Humble and Gazebo Fortress installations, we need to manually install interfaces between ROS2 and Gazebo sim as follows,
sudo apt-get install ros-humble-ros-gz-sim ros-humble-ros-gz-bridge ros-humble-ros-gz-interfaces
Remainder of the dependencies can be installed with rosdep
# From the root directory of the workspace. This will install everything mentioned in package.xml
rosdep install --from-paths src --ignore-src -r -y
Source Build
colcon build --packages-select bcr_bot
Binary Install
To install BCR bot in the binaries:
sudo apt-get install ros-humble-bcr-bot
Run
To launch the robot in Gazebo,
ros2 launch bcr_bot ign.launch.py
To view in rviz,
ros2 launch bcr_bot rviz.launch.py
Configuration
The launch file accepts multiple launch arguments,
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:
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, we need to manually install interfaces between ROS2 and Gazebo sim as follows,
sudo apt-get install ros-humble-ros-gzharmonic
Remainder of the dependencies can be installed with rosdep
# 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
colcon build --packages-select bcr_bot
Run
To launch the robot in Gazebo,
ros2 launch bcr_bot gz.launch.py
To view in rviz,
ros2 launch bcr_bot rviz.launch.py
Configuration
The launch file accepts multiple launch arguments,
ros2 launch bcr_bot gz.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:
ros2 launch stereo_image_proc stereo_image_proc.launch.py left_namespace:=bcr_bot/stereo_camera/left right_namespace:=bcr_bot/stereo_camera/right
Harmonic support is not available in the bcr_bot binaries yet.
Warning: gz-harmonic
cannot be installed alongside gazebo-classic (eg. gazebo11) since both use the gz
command line tool.
Humble + Isaac Sim (Ubuntu 22.04)
Dependencies
In addition to ROS2 Humble Isaac Sim installation with ROS2 extension is required. Remainder of bcr_bot specific dependencies can be installed with rosdep
# 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
colcon build --packages-select bcr_bot
Run
To launch the robot in Isaac Sim:
Open Isaac Sim and load the
warehouse_scene.usd
orscene.usd
from here.Add in extra viewports for different camera views.
Start the Simulation: Run the simulation directly within Isaac Sim.
The following USDs are included in the package: -
warehouse_scene.usd
- Warehouse scene with a robot. -scene.usd
- Scene with a robot in a empty world. -bcr_bot.usd
- Robot model that can be imported into any scene. -ActionGraphFull.usd
- Action graph for the robot to publish all the required topics.
To view in rviz:
ros2 launch bcr_bot rviz.launch.py
NOTE: The command to run mapping and navigation is common between all versions of gazebo and Isaac sim see here.
Mapping with SLAM Toolbox
SLAM Toolbox is an open-source package designed to map the environment using laser scans and odometry, generating a map for autonomous navigation.
NOTE: The command to run mapping is common between all versions of gazebo.
To start mapping:
ros2 launch bcr_bot mapping.launch.py
Use the teleop twist keyboard to control the robot and map the area:
ros2 run teleop_twist_keyboard teleop_twist_keyboard cmd_vel:=/bcr_bot/cmd_vel
To save the map:
cd src/bcr_bot/config
ros2 run nav2_map_server map_saver_cli -f bcr_map
Simulation and Visualization
Gz Sim (Ignition Gazebo) (small_warehouse World):
Isaac Sim:
Rviz (Depth camera) (small_warehouse World):