Skip to content

qualcomm-qrb-ros/qrb_ros_simulation

Folders and files

NameName
Last commit message
Last commit date

Latest commit

ย 

History

23 Commits
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 
ย 

QRB ROS Simulation

Qualcomm QRB ROS

ROS project designed to set up the Qualcomm robotic simulation environment

Qualcomm Ubuntu Jazzy


๐Ÿ‘‹ Overview

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.
architecture

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.

๐Ÿ”Ž Table of Contents

โš“ APIs

qrb_ros_simulation APIs

๐Ÿ”น ROS Topics Published

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

๐Ÿ”น ROS Topics Subscribed

Name Type Description
/cmd_vel geometry_msgs.msg.Twist Velocity command input for robot movement

๐Ÿ”นROS Actions Advertised

Name Type Description
/rm_group_controller/follow_joint_trajectory control_msgs.action.FollowJointTrajectory Action interface for joint trajectory control

๐Ÿ”น ROS parameters

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
  • RML-63 robotic arm: 2.0
  • QRB Robot Base AMR(Mini): 0.0
  • QRB Mobile Manipulator Robot: 0.0
initial_y float Initial Y position (meters) of robot entity in world coordinates
  • RML-63 robotic arm: -2.0
  • QRB Robot Base AMR(Mini): 0.0
  • QRB Mobile Manipulator Robot: 0.0
initial_z float Initial Z position (meters) of robot entity in world coordinates
  • RML-63 robotic arm: 1.03
  • QRB Robot Base AMR(Mini): 0.0
  • QRB Mobile Manipulator Robot: 0.0
initial_roll float Initial roll orientation (radians) of robot entity around X-axis
  • RML-63 robotic arm: 0.0
  • QRB Robot Base AMR(Mini): 0.0
  • QRB Mobile Manipulator Robot: 0.0
initial_pitch float Initial pitch orientation (radians) of robot entity around Y-axis
  • RML-63 robotic arm: 0.0
  • QRB Robot Base AMR(Mini): 0.0
  • QRB Mobile Manipulator Robot: 0.0
initial_yaw float Initial yaw orientation (radians) of robot entity around Z-axis
  • RML-63 robotic arm: 3.14159
  • QRB Robot Base AMR(Mini): 0.0
  • QRB Mobile Manipulator Robot: 0.0
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'

โœจ Set up development environment

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
  1. Please reference Install ROS Jazzy to install ros-jazzy-desktop and setup ROS env.
  2. 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
  1. Build the docker image locally
cd qrb_ros_simulation
chmod +x scripts/docker_build.sh
./scripts/docker_build.sh
  1. Start a docker container
chmod +x scripts/docker_run.sh
./scripts/docker_run.sh
  1. Enable SSH service in the docker container
# set the password of user root
(docker) passwd
# enable SSH service
(docker) service ssh start
  1. 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.

๐Ÿ‘จโ€๐Ÿ’ป Build from source

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

๐Ÿš€ Usage

Four pre-configured robotic models are ready to be launched directly.

๐Ÿ”น RML-63 robotic arm

  1. launch RML-63 robotic arm in gazebo
ros2 launch qrb_ros_sim_gazebo gazebo_rml_63_gripper.launch.py
  1. Press the Play button to start the simulation
  2. 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

๐Ÿ”น QRB Robot Base AMR

ros2 launch qrb_ros_sim_gazebo gazebo_robot_base.launch.py

๐Ÿ”น QRB Robot Base AMR Mini

ros2 launch qrb_ros_sim_gazebo gazebo_robot_base_mini.launch.py

๐Ÿ”น QRB Mobile Manipulator Robot

  1. launch
ros2 launch qrb_ros_sim_gazebo gazebo_mobile_manipulator.launch.py
  1. Press the Play button to start the simulation
  2. 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

๐Ÿค Contributing

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๐Ÿ’ก.

โค๏ธ Contributors

Thanks to all our contributors who have helped make this project better!

quic-weijshen
quic-weijshen
fulaliu
fulaliu
teng
teng
xionfu
xionfu
jiaxshi
jiaxshi
quic-zhanlin
quic-zhanlin
quic-zhaoyuan
quic-zhaoyuan

๐Ÿ“œ License

Project is licensed under the BSD-3-Clause License. See LICENSE for the full license text.

About

No description, website, or topics provided.

Resources

License

Code of conduct

Contributing

Stars

Watchers

Forks

Releases

No releases published

Packages

No packages published

Contributors 6