Skip to content


ardupilot  None  ros2  dds  micro ros  xrce  lua  sitl  scripts  plugin  gazebo  garden  SITL  debug  mavlink  gimbal  rangefinder  pymavlink  mavros  distance sensor  system_time  timesync  ardurover  script  cheat sheet  wireshark  mavproxy  mission planner  pixhawk  cpp  index  cmake  gtest  ctest  demo  101  variables  cpack  deb  package  dpkg  eigen  linear algebra  c++  format  fmt  smart pointers  data structure  map  container  multithreading  spdlog  cyclonedds  eprosima  fastdds  aptly  apt  repository  repo  local  mirror  encryption  pgp  docker  arm  qemu  state  networking  network  template  python  app  devcontainer  gui  tutorial  tips  volume  mount  compose  multi-stage  stage  docker compose  microsoft  dotnet  .net  c#  vscode  git  branch  tag  bundle  backup  hooks  pre-commit  submodules  marpit  presentation  marp  markdown  mermaid  mkdocs  video  ffmpeg  gstreamer  cheat-sheet  sdp  nvidia  opencv  appsrc  appsink  acceleration  va-api  intel  v4l2loopback  pipe  compositor  alpha  shmsink  shmsrc  intersink  intersrc  tee  queue  udp  stream  klv  misb  mpeg-ts  gst  mpeg  metadata  binding  gi  kml  geo  gis  spatial  gdal  ogr  raster  vector  qgc  qgroundcontrol  snippets  cheat Sheet  asyncio  event  future  thread  task  can  canbus  click  cli  cupy  numpy  gpu  dataclass  slots  dev container  fastapi  rest  uvicorn  debian  setup  stdeb  project  jupyter  widgets  interactive  plot  matplotlib  ipywidgets  3d  subplot  open3d  point cloud  packaging  pyproject  pipx  package manager  black  isort  templates  cookiecutter  docs  project document  docstrings  flake8  linter  git-hook  mypy  unittest  pytest  pylint  from a-z  fixture  scope  logging  pytest.ini  mock  parameterize  enum  flag  iterator  generator  yaml  yml  logging config  tuple  namedtuple  typing  annotation  generic  literal  protocol  self  typed dict  typevar  pyzmq  zmq  msgpack  slam  cartographer  slam_toolbox  build system  colcon  action  namespace  remap  control2  diff-drive  ignition  ros2_control  effort  velocity  gdb  mix  multi language  qos  plugins  ros  pub  sub  msg  node  time  rclcpp  parameters  zero-copy  shm  loan message  rmw  image  large message  discovery  zenoh  bridge  zenoh-plugin-ros2dds  pico  algorithm  calibration  diff  pid  dev  colcon_cd  clean  custom  bloom  rpi  core  settings  behavior  py_trees  bt  behavior_trees  blackboard  visualization  debugging  diagnostic  DiagnosticTask  rclpy  tutorials  diagnostics  math  ned  enu  coordinate  apm  rat_runtime_monitor  bag  rosbag  rosbags  tools  smach  state machine  yasmin  web  rosbridge  vue  profile  gazebo-classic  launch  spawn  model  cook  camera  sensors  gps  imu  ray  gazebo_ros_ray_sensor  lidar  ultrsonic  range  ultrasonic  gazebo classic  wrench  gazebo_ros_state  gz  sdf  world  vscode tips  gazebogz-sim-joint-position-controller-system  simulation  ros_gz_bridge  ign  xacro  diff_drive  odom  odometry  joint_state  argument  OpaqueFunction  DeclareLaunchArgument  LaunchConfiguration  tmux  tmuxp  nav  nav2  turtlebot  perception  tf  vision  cv_bridge  setup.py  name  test  goal abort  cancel goal  action client  action server  custom messages  executor  MultiThreadedExecutor  SingleThreadedExecutor  lifecycle  parameter  param  dynamic-reconfigure  get  global server  persist_parameter  service  client  package.xml  msgs  executers  rep  rqt  humble  rviz  rviz2  pose  marker  tf2  static  graphro  local_setup  rosdep  project settings  vcstool  urdf  robot_state_publisher  urdf_to_graphiz  joint  link  robotics  path planning  trajectory  speed  filters  control  kalman_filter  kalman  filter  pcl  fusing  foc  bldc  arduino  drv8313  simple foc  quaternions  euler  rotation  code  extensions  remote  cache  offline  ssh  tasks  json  schema  server  deep learning  ai  beginner  regression  reinforcement learning  q learning  gym  gymnasium  deepsort  onnx  inference  build  source  wheel  cuda  siam-mask  tracking  segmentation  yolo  ultralytics  yolov8  jetson  tensorrt  rest api  js  javascript  async  alpine.js  mqtt  nano  terabee  i2c  l6234  blink  platformio  lw20  benewake  TF03  serial  tf_mini  libs  cross-compiler  esp32  idf  esp-idf  rtos  hello world  mp6050  mpu9250  mpu6050  embedded  kconfig  semaphore  mutex  timer  adafruit  sensor  mb1202  uart  tfmini  gpio  raspberry pi  arducam  lidat  ubuntu  stm32  nucleo  mbed  blue pill  swd  library  teensy  microros  udev  rule  usb  micro python  pymakr  config  material  workshope  classic  texture  topic  gzstring  position  force  joints  loop device  rootfs  linux  rm  sudo  sudoers  nopasswd  visudo  shell  key  gpg  sign  commands  update-alternative  debconf  dpkg-show  dpkg-reconfigure  debconf-communicate  ip  ss  netstat  systemd  socat  tc  mtu  select  projects  courses to follow  matrix  graphics  2d  course  storm32  deploy  drone  quad  uav  geometric control  se3  so3  joint_states  JointState  Header  rrbot  JointTrajectory  gazebo_ros_joint_pose_trajectory  vrx  buoyancy 

Table of Content

ROS2 Gazebo Project#

A template project integrating ROS 2 and Gazebo simulator. base on

  • <name>_description: holds the sdf description of the simulated system and any other assets.
  • <name>_gazebo: holds gazebo specific code and configurations
  • <name>_application: holds ros2 specific code and configurations.
  • <name>_bringup: holds launch files and high level utilities.

Gazebo Garden ROS2 humble

ros_gz package binaries not compatible with gazebo garden we need to download the package and build it as part of the workspace. check github ros_gz


Template#

The template base on ament_cmake packages I prepared ament_python package,

Warning

The template project use dsv file to config gazebo environment variables GZ_SIM_RESOURCE_PATH GZ_SIM_SYSTEM_PLUGIN_PATH The ament_python not support the dsv or i don’t find how to use this feature I config the environment variable from the launch files more

Add copy folder function to setup.py

Add helper method to copy data_files files and folders recursive.

def package_files(directory_list):
"""helper method to copy data_files recursive
"""
data_files=[
    ('share/ament_index/resource_index/packages',['resource/' + package_name]),
    ('share/' + package_name, ['package.xml']),
]
paths_dict = {}
for directory in directory_list:
    for (path, _, filenames) in os.walk(directory):
        for filename in filenames:
            file_path = os.path.join(path, filename)
            install_path = os.path.join('share', package_name, path)
            if install_path in paths_dict:
                paths_dict[install_path].append(file_path)
            else:
                paths_dict[install_path] = [file_path]

for src, dst in paths_dict.items():
    data_files.append((src, dst))

return data_files
usage
setup(
name=package_name,
version='0.0.0',
packages=find_packages(exclude=['test']),
data_files=package_files(["models"]),
...
...
)

launch#

Basic launch run Gazebo world with model from (_description) project

basic.launch.py
import pathlib
from ament_index_python.packages import get_package_share_directory

import launch
from launch.actions import IncludeLaunchDescription, SetEnvironmentVariable
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import EnvironmentVariable


def generate_launch_description():
    ld = launch.LaunchDescription()
    pkg_ros_gz_sim = get_package_share_directory("ros_gz_sim")
    pkg_project_gazebo = get_package_share_directory("nav_gazebo")
    pkg_project_description = get_package_share_directory("nav_description")

    modules = pathlib.Path(pkg_project_description).joinpath("models").as_posix()
    worlds = pathlib.Path(pkg_project_gazebo).joinpath("worlds").as_posix()

    resources = ":".join([modules, worlds])

    gz_resource_path = SetEnvironmentVariable(
        name="GZ_SIM_RESOURCE_PATH",
        value=[EnvironmentVariable("GZ_SIM_RESOURCE_PATH"), resources],
    )

    gz_sim = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            pathlib.Path(pkg_ros_gz_sim)
            .joinpath("launch", "gz_sim.launch.py")
            .as_posix()
        ),
        launch_arguments={
            "gz_args": "-v4 -r empty.sdf"
        }.items(),
    )

    ld.add_action(gz_resource_path)
    ld.add_action(gz_sim)
    return ld