The QRB ROS Simulation is a ROS project designed to set up the Qualcomm robotic simulation environment.
- This project provides simulation configurations for various robotic systems, including robotic arms, AMRs, sensors, and more.
- This project enables extensive testing and validation of robotic development without the need for physical Qualcomm robot prototypes.
The qrb_ros_sim_description
is a ROS 2 package. It contains the description assets referenced by the simulation, including URDF, model meshes, etc. These assets are consumed by simulator to render the models and environments.
The qrb_ros_sim_gazebo
is a ROS 2 package. It provides Gazebo integration and ROS 2 launch files to start worlds and robots, wire up controllers, and expose standard ROS topics via the ros-gz stack.
Name | Type | Description |
---|---|---|
/clock | rosgraph_msgs.msg.Clock | Providing simulation time |
/tf | tf2_msgs.msg.TFMessage | Real-time coordinate frame transformations |
/tf_static | tf2_msgs.msg.TFMessage | Static coordinate frame transformations |
/robot_description | std_msgs.msg.String | URDF description of the robot model |
/joint_states | sensor_msgs.msg.JointState | Current state of all joints |
/camera/color/camera_info | sensor_msgs.msg.CameraInfo | Intrinsic parameters of RGB camera |
/camera/color/image_raw | sensor_msgs.msg.Image | Raw image stream from RGB camera |
/camera/depth/camera_info | sensor_msgs.msg.CameraInfo | Intrinsic parameters of depth camera |
/camera/depth/image_raw | sensor_msgs.msg.Image | Raw depth image stream |
/camera/depth/points | sensor_msgs.msg.PointCloud2 | 3D point cloud data generated from depth |
/scan | sensor_msgs.msg.LaserScan | Laser scan data from the LiDAR sensor |
/imu | sensor_msgs.msg.Imu | Inertial data including acceleration and angular velocity |
/odom | nav_msgs.msg.Odometry | Odometry data including position and velocity |
Name | Type | Description |
---|---|---|
/cmd_vel | geometry_msgs.msg.Twist | Velocity command input for robot movement |
Name | Type | Description |
---|---|---|
/rm_group_controller/follow_joint_trajectory | control_msgs.action.FollowJointTrajectory | Action interface for joint trajectory control |
Name | Type | Description | Default Value |
---|---|---|---|
launch_config_file | string | Path to a YAML configuration file. Parameters defined in this file have HIGHEST PRIORITY and will override the command-line and default values | '' |
world_model | string | Name of the Gazebo world model to load (without .sdf extension) | 'warehouse' |
Click to show more
Name | Type | Description | Default Value |
---|---|---|---|
launch_config_file | string | Path to a YAML configuration file. Parameters defined in this file have HIGHEST PRIORITY and will override the command-line and default values | '' |
world_model | string | Name of the Gazebo world model to load (without .sdf extension) | 'warehouse' |
robot_entity_name | string | Name of the robot entity in the simulation environment | 'qrb_robot' |
namespace | string | ROS namespace | '' |
initial_x | float | Initial X position (meters) of robot entity in world coordinates |
|
initial_y | float | Initial Y position (meters) of robot entity in world coordinates |
|
initial_z | float | Initial Z position (meters) of robot entity in world coordinates |
|
initial_roll | float | Initial roll orientation (radians) of robot entity around X-axis |
|
initial_pitch | float | Initial pitch orientation (radians) of robot entity around Y-axis |
|
initial_yaw | float | Initial yaw orientation (radians) of robot entity around Z-axis |
|
enable_laser | string | Enable/disable LiDAR sensor ("true"/"false") | 'true' |
laser_config_file | string | Path to LiDAR sensor configuration YAML file | '{qrb_ros_sim_gazebo package}/ config/params/{model}_laser_params.yaml' |
enable_imu | string | Enable/disable Inertial Measurement Unit (IMU) sensor ("true"/"false") | 'true' |
imu_config_file | string | Path to IMU configuration YAML fil | '{qrb_ros_sim_gazebo package}/ config/params/imu_params.yaml' |
enable_odom | string | Enable/disable odometry sensor ("true"/"false") | 'true' |
enable_odom_tf | string | Enable/disable odometry tf data publication ("true"/"false") | 'false' |
enable_rgb_camera | string | Enable/disable RGB camera sensor ("true"/"false") | 'true' |
rgb_camera_config_file | string | Path to RGB camera configuration YAML file | '{qrb_ros_sim_gazebo package}/ config/params/rgb_camera_params.yaml' |
enable_depth_camera | string | Enable/disable depth camera sensor ("true"/"false") | 'true' |
depth_camera_config_file | string | Path to depth camera configuration YAML file | '{qrb_ros_sim_gazebo package}/ config/params/depth_camera_params.yaml' |
You can setup ROS2 Jazzy on your host machine with ubuntu24.04 OR you can use a docker-based development environment directly.
Ubuntu24.04 host
- Please reference Install ROS Jazzy to install ros-jazzy-desktop and setup ROS env.
- Install gazebo with ROS and other dependencies
sudo apt-get install -y ros-jazzy-ros-gz ros-jazzy-gz-ros2-control ros-jazzy-ros2-controllers
Next, you can follow the steps of โBuild from sourceโโ and โโUsage to launch the simulation environment.
Docker
- Build the docker image locally
cd qrb_ros_simulation
chmod +x scripts/docker_build.sh
./scripts/docker_build.sh
- Start a docker container
chmod +x scripts/docker_run.sh
./scripts/docker_run.sh
- Enable SSH service in the docker container
# set the password of user root
(docker) passwd
# enable SSH service
(docker) service ssh start
- In a separate terminal, login to the docker container by SSH
ssh -X -p 222 root@your_host_ip
Next, you can follow the steps of โBuild from sourceโโ and โโUsage to launch the simulation environment within the docker container.
Download qrb_ros_simulation and meshes files
mkdir -p ~/qrb_ros_simulation_ws
cd ~/qrb_ros_simulation_ws
git clone https://github.com/qualcomm-qrb-ros/qrb_ros_simulation.git
cd qrb_ros_simulation
chmod +x scripts/meshes_download.sh
./scripts/meshes_download.sh
Build the project
source /opt/ros/jazzy/setup.bash
cd ~/qrb_ros_simulation_ws
colcon build
source install/local_setup.sh
Four pre-configured robotic models are ready to be launched directly.
- launch RML-63 robotic arm in gazebo
ros2 launch qrb_ros_sim_gazebo gazebo_rml_63_gripper.launch.py
- Press the
Play
button to start the simulation - In a separate terminal, load the controllers of RML-63
cd ~/qrb_ros_simulation_ws
source install/local_setup.sh
ros2 launch qrb_ros_sim_gazebo gazebo_rml_63_gripper_load_controller.launch.py
ros2 launch qrb_ros_sim_gazebo gazebo_robot_base.launch.py
ros2 launch qrb_ros_sim_gazebo gazebo_robot_base_mini.launch.py
- launch
ros2 launch qrb_ros_sim_gazebo gazebo_mobile_manipulator.launch.py
- Press the
Play
button to start the simulation - In a separate terminal, load the controllers of RML-63
cd ~/qrb_ros_simulation_ws
source install/local_setup.sh
ros2 launch qrb_ros_sim_gazebo gazebo_rml_63_gripper_load_controller.launch.py
We love community contributions! Get started by reading our CONTRIBUTING.md.
Feel free to create an issue for bug report, feature requests or any discussion๐ก.
Thanks to all our contributors who have helped make this project better!
![]() quic-weijshen |
![]() fulaliu |
![]() teng |
![]() xionfu |
![]() jiaxshi |
![]() quic-zhanlin |
![]() quic-zhaoyuan |
Project is licensed under the BSD-3-Clause License. See LICENSE for the full license text.