World Building, Robot Modeling, Sensor Simulation & Drone Integration
Weeks 12 and 13 introduce Gazebo Jazzy, the next-generation robot simulator integrated with ROS2 Jazzy. Unlike legacy Gazebo Classic, Gazebo Jazzy (gz-sim) is built on a modular plugin-based architecture with physically accurate rendering and first-class ROS2 integration via ros_gz_bridge.
World design, SDF environments, physics and wind simulation
URDF/SDF robot modeling, sensors, drone & flight controller integration
Smart City Environment + Intelligent Quadcopter Drone with Vision
Gazebo Jazzy is the modern simulator release aligned with ROS2 Jazzy. It replaces legacy Gazebo Classic with a plugin-based architecture, offering improved performance, realistic sensors, and seamless ROS2 integration via ros_gz_bridge and ros_gz_sim.
sudo apt update
sudo apt install -y \
ros-jazzy-ros-gz \
ros-jazzy-ros-gz-bridge \
ros-jazzy-ros-gz-sim \
ros-jazzy-ros-gz-interfaces \
ros-jazzy-gz-ros2-control
# Verify
gz sim --version
~/.bashrc contains: source /opt/ros/jazzy/setup.bash
# Launch empty world to verify
gz sim empty.sdf
# Or via ROS2
ros2 launch ros_gz_sim gz_sim.launch.py gz_args:="empty.sdf"
| Component | Description | Command |
|---|---|---|
gz sim | Main simulator | gz sim world.sdf |
gz topic | Inspect Gazebo topics | gz topic -l |
gz model | Spawn/inspect models | gz model -l |
ros_gz_bridge | Bridge ROS2 ↔ Gazebo | ros2 run ros_gz_bridge parameter_bridge |
ros_gz_sim | Launch Gazebo from ROS2 | ros2 launch ros_gz_sim gz_sim.launch.py |
gz fuel | Online model library | app.gazebosim.org/fuel |
# List all Gazebo topics
gz topic -l
# Echo a topic
gz topic -e -t /model/my_robot/pose
# List models in simulation
gz model -l
# Get model info
gz model -m my_robot -i
SDF is the primary world format for Gazebo Jazzy. Every world contains physics, plugins, models, and lights inside a <world> tag.
<?xml version="1.0"?>
<sdf version="1.9">
<world name="smart_city">
<!-- Physics -->
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<!-- Required plugins -->
<plugin filename="gz-sim-physics-system"
name="gz::sim::systems::Physics"/>
<plugin filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster"/>
<plugin filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands"/>
<plugin filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<!-- Sun -->
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
<direction>-0.5 0.1 -0.9</direction>
</light>
<!-- Ground plane -->
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry><plane><normal>0 0 1</normal><size>500 500</size></plane></geometry>
</collision>
<visual name="visual">
<geometry><plane><normal>0 0 1</normal><size>500 500</size></plane></geometry>
<material><ambient>0.8 0.8 0.8 1</ambient></material>
</visual>
</link>
</model>
</world>
</sdf>
<!-- Building block -->
<model name="building_1">
<static>true</static>
<pose>10 5 0 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry><box><size>8 6 12</size></box></geometry>
</collision>
<visual name="visual">
<geometry><box><size>8 6 12</size></box></geometry>
<material><ambient>0.5 0.5 0.6 1</ambient><diffuse>0.6 0.6 0.7 1</diffuse></material>
</visual>
</link>
</model>
<!-- No-fly zone (red transparent cylinder) -->
<model name="no_fly_zone_1">
<static>true</static>
<pose>20 20 0 0 0 0</pose>
<link name="link">
<visual name="visual">
<geometry><cylinder><radius>10</radius><length>0.1</length></cylinder></geometry>
<material><ambient>1 0 0 0.4</ambient><diffuse>1 0 0 0.4</diffuse></material>
</visual>
</link>
</model>
<!-- Add inside <world> -->
<plugin filename="gz-sim-wind-effects-system"
name="gz::sim::systems::WindEffects">
<horizontal>
<magnitude>
<time_for_rise>10</time_for_rise>
<sin>
<amplitude_percent>0.05</amplitude_percent>
<period>60</period>
</sin>
<noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev></noise>
</magnitude>
<direction>
<time_for_rise>30</time_for_rise>
<sin><amplitude>5</amplitude><period>20</period></sin>
<noise type="gaussian"><mean>0</mean><stddev>0.03</stddev></noise>
</direction>
</horizontal>
<vertical>
<noise type="gaussian"><mean>0</mean><stddev>0.03</stddev></noise>
</vertical>
</plugin>
<wind>
<linear_velocity>3 1 0</linear_velocity>
</wind>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
</physics>
# Bridge multiple topics
ros2 run ros_gz_bridge parameter_bridge \
/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock \
/model/drone/pose@geometry_msgs/msg/PoseStamped[gz.msgs.Pose \
/lidar@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan \
/camera/image@sensor_msgs/msg/Image[gz.msgs.Image \
/imu@sensor_msgs/msg/Imu[gz.msgs.IMU \
/gps@sensor_msgs/msg/NavSatFix[gz.msgs.NavSat \
/cmd_vel@geometry_msgs/msg/Twist]gz.msgs.Twist
# ros2_gz_bridge.launch.py
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
'/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock',
'/model/drone/pose@geometry_msgs/msg/PoseStamped[gz.msgs.Pose',
'/lidar@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan',
'/camera/image_raw@sensor_msgs/msg/Image[gz.msgs.Image',
'/camera/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo',
'/imu/data@sensor_msgs/msg/Imu[gz.msgs.IMU',
'/navsat@sensor_msgs/msg/NavSatFix[gz.msgs.NavSat',
'/cmd_vel@geometry_msgs/msg/Twist]gz.msgs.Twist',
],
output='screen',
)
return LaunchDescription([bridge])
<?xml version="1.0"?>
<robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
<link name="base_link">
<visual>
<geometry><box size="0.5 0.3 0.1"/></geometry>
<material name="blue"><color rgba="0.0 0.0 0.8 1.0"/></material>
</visual>
<collision><geometry><box size="0.5 0.3 0.1"/></geometry></collision>
<inertial>
<mass value="5.0"/>
<inertia ixx="0.05" ixy="0" ixz="0" iyy="0.05" iyz="0" izz="0.05"/>
</inertial>
</link>
<link name="left_wheel">
<visual>
<geometry><cylinder length="0.05" radius="0.1"/></geometry>
<material name="black"><color rgba="0.1 0.1 0.1 1.0"/></material>
</visual>
<collision><geometry><cylinder length="0.05" radius="0.1"/></geometry></collision>
<inertial><mass value="0.5"/><inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/></inertial>
</link>
<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<origin xyz="0 0.175 -0.05" rpy="-1.5707 0 0"/>
<axis xyz="0 0 1"/>
</joint>
</robot>
sudo apt install -y gz-tools2
gz sdf -p my_robot.urdf > my_robot.sdf
gz sdf --check my_robot.sdf
<sensor name="lidar" type="gpu_lidar">
<pose>0 0 0.2 0 0 0</pose>
<update_rate>10</update_rate>
<lidar>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-3.14159</min_angle>
<max_angle>3.14159</max_angle>
</horizontal>
</scan>
<range><min>0.08</min><max>25</max><resolution>0.01</resolution></range>
<noise type="gaussian"><mean>0</mean><stddev>0.01</stddev></noise>
</lidar>
</sensor>
<sensor name="camera" type="camera">
<pose>0.25 0 0.1 0 0 0</pose>
<update_rate>30</update_rate>
<camera>
<horizontal_fov>1.3962634</horizontal_fov>
<image><width>640</width><height>480</height><format>R8G8B8</format></image>
<clip><near>0.02</near><far>300</far></clip>
<noise type="gaussian"><mean>0</mean><stddev>0.007</stddev></noise>
</camera>
</sensor>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>100</update_rate>
<imu>
<angular_velocity>
<x><noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev></noise></x>
<y><noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev></noise></y>
<z><noise type="gaussian"><mean>0</mean><stddev>0.0002</stddev></noise></z>
</angular_velocity>
<linear_acceleration>
<x><noise type="gaussian"><mean>0</mean><stddev>0.017</stddev></noise></x>
<y><noise type="gaussian"><mean>0</mean><stddev>0.017</stddev></noise></y>
<z><noise type="gaussian"><mean>0</mean><stddev>0.017</stddev></noise></z>
</linear_acceleration>
</imu>
</sensor>
<sensor name="navsat" type="navsat">
<always_on>1</always_on>
<update_rate>10</update_rate>
<navsat>
<position_sensing>
<horizontal><noise type="gaussian"><mean>0</mean><stddev>0.001</stddev></noise></horizontal>
<vertical><noise type="gaussian"><mean>0</mean><stddev>0.001</stddev></noise></vertical>
</position_sensing>
</navsat>
</sensor>
<?xml version="1.0"?>
<sdf version="1.9">
<model name="quadcopter">
<pose>0 0 0.2 0 0 0</pose>
<link name="base_link">
<inertial>
<mass>1.5</mass>
<inertia>
<ixx>0.029125</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.029125</iyy><iyz>0</iyz>
<izz>0.055225</izz>
</inertia>
</inertial>
<visual name="body_visual">
<geometry><box><size>0.47 0.47 0.11</size></box></geometry>
<material><ambient>0.1 0.1 0.1 1</ambient></material>
</visual>
<collision name="body_collision">
<geometry><box><size>0.47 0.47 0.11</size></box></geometry>
</collision>
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on><update_rate>250</update_rate>
</sensor>
<sensor name="navsat" type="navsat">
<always_on>1</always_on><update_rate>10</update_rate>
</sensor>
<sensor name="downward_camera" type="camera">
<pose>0 0 -0.1 0 1.5707 0</pose>
<update_rate>30</update_rate>
<camera>
<horizontal_fov>1.5707</horizontal_fov>
<image><width>640</width><height>480</height></image>
<clip><near>0.1</near><far>100</far></clip>
</camera>
</sensor>
</link>
<!-- Rotor 0 (front-right, CW) -->
<link name="rotor_0">
<pose>0.13 -0.22 0.023 0 0 0</pose>
<inertial><mass>0.005</mass>
<inertia><ixx>9.75e-7</ixx><ixy>0</ixy><ixz>0</ixz><iyy>0.000166704</iyy><iyz>0</iyz><izz>0.000167604</izz></inertia>
</inertial>
<visual name="rotor_0_visual">
<geometry><cylinder><length>0.005</length><radius>0.1</radius></cylinder></geometry>
<material><ambient>0 0 1 0.8</ambient></material>
</visual>
</link>
<joint name="rotor_0_joint" type="revolute">
<parent>base_link</parent><child>rotor_0</child>
<axis><xyz>0 0 1</xyz><dynamics><damping>0.004</damping></dynamics></axis>
</joint>
<!-- Multicopter motor model -->
<plugin filename="gz-sim-multicopter-motor-model-system"
name="gz::sim::systems::MulticopterMotorModel">
<robotNamespace>quadcopter</robotNamespace>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>cw</turningDirection>
<maxRotVelocity>1000</maxRotVelocity>
<motorConstant>8.54858e-6</motorConstant>
<momentConstant>0.016</momentConstant>
<commandSubTopic>command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
</plugin>
<!-- Velocity control -->
<plugin filename="gz-sim-multicopter-control-system"
name="gz::sim::systems::MulticopterVelocityControl">
<robotNamespace>quadcopter</robotNamespace>
<commandSubTopic>cmd_vel</commandSubTopic>
<enableSubTopic>enable</enableSubTopic>
<comLinkName>base_link</comLinkName>
<velocityGain>2.7 2.7 2.7</velocityGain>
<attitudeGain>2 3 0.15</attitudeGain>
<angularRateGain>0.4 0.52 0.18</angularRateGain>
</plugin>
</model>
</sdf>
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
from std_msgs.msg import Bool
class DroneController(Node):
def __init__(self):
super().__init__('drone_controller')
self.enable_pub = self.create_publisher(Bool, '/quadcopter/enable', 10)
self.cmd_pub = self.create_publisher(Twist, '/quadcopter/cmd_vel', 10)
self.state = 'arming'
self.timer = self.create_timer(1.0, self.run)
self.get_logger().info('Drone controller ready')
def run(self):
if self.state == 'arming':
msg = Bool(); msg.data = True
self.enable_pub.publish(msg)
self.state = 'takeoff'
elif self.state == 'takeoff':
cmd = Twist(); cmd.linear.z = 2.0
self.cmd_pub.publish(cmd)
self.state = 'hover'
elif self.state == 'hover':
self.cmd_pub.publish(Twist()) # zero = hover
def main(args=None):
rclpy.init(args=args)
rclpy.spin(DroneController())
if __name__ == '__main__':
main()
For full flight stack integration, use PX4 SITL with the uXRCE-DDS bridge (native ROS2), or ArduCopter SITL with MAVROS. Both connect to Gazebo Jazzy via the ros_gz packages.
# Terminal 1 - ArduCopter SITL
cd ~/ardupilot
./Tools/autotest/sim_vehicle.py -v ArduCopter --console --map
# Terminal 2 - Launch Gazebo world
ros2 launch ros_gz_sim gz_sim.launch.py gz_args:="smart_city.sdf"
# Terminal 3 - MAVROS bridge
ros2 launch mavros apm.launch fcu_url:=udp://:14550@127.0.0.1:14555
# Terminal 4 - Check topics
ros2 topic list | grep mavros
Build a realistic urban simulation world in Gazebo Jazzy featuring buildings, roads, wind, and clearly marked no-fly zones.
# smart_city.launch.py
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
import os
def generate_launch_description():
pkg = get_package_share_directory('my_simulation')
world = os.path.join(pkg, 'worlds', 'smart_city.sdf')
gz = IncludeLaunchDescription(
PythonLaunchDescriptionSource([
get_package_share_directory('ros_gz_sim'), '/launch/gz_sim.launch.py'
]),
launch_arguments={'gz_args': world}.items()
)
bridge = Node(
package='ros_gz_bridge', executable='parameter_bridge',
arguments=['/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock'],
output='screen'
)
return LaunchDescription([gz, bridge])
Model a complete quadcopter, spawn it in the Smart City world, and implement autonomous vision-based navigation.
ros2 service call /emergency_land std_srvs/srv/Trigger "{}"#!/usr/bin/env python3
# no_fly_zone_detector.py
import rclpy, math
from rclpy.node import Node
from sensor_msgs.msg import NavSatFix
from std_msgs.msg import String
class NoFlyZoneDetector(Node):
ZONES = [
(31.9522, 35.9107, 50.0),
(31.9530, 35.9120, 30.0),
(31.9510, 35.9095, 40.0),
]
def __init__(self):
super().__init__('no_fly_zone_detector')
self.sub = self.create_subscription(NavSatFix, '/navsat', self.cb, 10)
self.pub = self.create_publisher(String, '/no_fly_zone_alert', 10)
def haversine(self, la1, lo1, la2, lo2):
R = 6371000
p1, p2 = math.radians(la1), math.radians(la2)
dp, dl = math.radians(la2-la1), math.radians(lo2-lo1)
a = math.sin(dp/2)**2 + math.cos(p1)*math.cos(p2)*math.sin(dl/2)**2
return R * 2 * math.atan2(math.sqrt(a), math.sqrt(1-a))
def cb(self, msg):
for i, (clat, clon, r) in enumerate(self.ZONES):
d = self.haversine(msg.latitude, msg.longitude, clat, clon)
if d < r:
alert = String()
alert.data = f'WARNING: No-fly zone {i+1}! Dist={d:.1f}m'
self.pub.publish(alert)
self.get_logger().warn(alert.data)
def main(args=None):
rclpy.init(args=args)
rclpy.spin(NoFlyZoneDetector())
if __name__ == '__main__':
main()
| Topic | Week 12 | Week 13 |
|---|---|---|
| Focus | World building & environments | Robot/drone modeling |
| Format | SDF world files | URDF + SDF model files |
| Key tools | gz sim, SDF editor | Xacro, gz sdf |
| Sensors | Lighting, wind, physics | LIDAR, Camera, IMU, GPS |
| ROS2 integration | ros_gz_bridge, clock | Sensor topics, cmd_vel |
| Project | Smart City + no-fly zones | Quadcopter with vision |
| Flight stack | — | Gazebo motor plugin / PX4 / ArduPilot |