|
| 1 | +Defining worlds, robots, and sensors |
| 2 | +===================================== |
| 3 | + |
| 4 | +**Goal:** Learn the basics of defining MVSim world files, adding vehicles and sensors, and the main features available. |
| 5 | + |
| 6 | +**Tutorial level:** Advanced |
| 7 | + |
| 8 | +**Time:** 30 minutes |
| 9 | + |
| 10 | +.. contents:: Contents |
| 11 | + :depth: 2 |
| 12 | + :local: |
| 13 | + |
| 14 | +Background |
| 15 | +---------- |
| 16 | + |
| 17 | +MVSim worlds are defined in XML files (``.world.xml``). |
| 18 | +A world file describes the environment (ground, walls, obstacles), the vehicles (dynamics model, shape, sensors), |
| 19 | +and simulation parameters (physics timestep, GUI options). |
| 20 | + |
| 21 | +MVSim provides a library of predefined vehicle and sensor definitions that you can reuse in your worlds via XML includes. |
| 22 | +You can also define everything from scratch for full control. |
| 23 | + |
| 24 | +Prerequisites |
| 25 | +------------- |
| 26 | + |
| 27 | +You should have completed the :doc:`Getting-Started-MVSim` tutorial and have MVSim installed. |
| 28 | + |
| 29 | +Tasks |
| 30 | +----- |
| 31 | + |
| 32 | +1 Minimal world file |
| 33 | +^^^^^^^^^^^^^^^^^^^^^^ |
| 34 | + |
| 35 | +Here is a minimal world file that creates an empty environment with one robot: |
| 36 | + |
| 37 | +.. code-block:: xml |
| 38 | +
|
| 39 | + <mvsim_world version="1.0"> |
| 40 | + <!-- Simulation settings --> |
| 41 | + <simul_timestep>5e-3</simul_timestep> |
| 42 | +
|
| 43 | + <!-- GUI options --> |
| 44 | + <gui> |
| 45 | + <cam_distance>15</cam_distance> |
| 46 | + </gui> |
| 47 | +
|
| 48 | + <!-- Ground plane --> |
| 49 | + <element class="ground_grid"> |
| 50 | + </element> |
| 51 | +
|
| 52 | + <!-- A differential-drive robot --> |
| 53 | + <vehicle name="robot1"> |
| 54 | + <init_pose>0 0 0</init_pose> <!-- x y yaw(deg) --> |
| 55 | +
|
| 56 | + <!-- Dynamical model --> |
| 57 | + <dynamics class="differential"> |
| 58 | + <!-- Params --> |
| 59 | + <l_wheel pos="0.0 0.5" mass="4.0" width="0.20" diameter="0.40" /> |
| 60 | + <r_wheel pos="0.0 -0.5" mass="4.0" width="0.20" diameter="0.40" /> |
| 61 | +
|
| 62 | + <!-- Visual and physical shape --> |
| 63 | + <chassis mass="15.0" zmin="0.05" zmax="0.6"> |
| 64 | + </chassis> |
| 65 | +
|
| 66 | + <!-- Motor controller --> |
| 67 | + <controller class="twist_pid"> |
| 68 | + <!-- Params --> |
| 69 | + <KP>4.1543</KP> |
| 70 | + <KI>1.9118</KI> |
| 71 | + <KD>0.0000</KD> |
| 72 | + <max_torque>14.44</max_torque> |
| 73 | + <V>0.0</V><W>0</W> |
| 74 | + </controller> |
| 75 | + </dynamics> |
| 76 | +
|
| 77 | + <!-- Motor controller: accept twist commands, PID controller --> |
| 78 | + <controller class="twist_pid"> |
| 79 | + <KP>100</KP> <KI>5</KI> <max_torque>50</max_torque> |
| 80 | + </controller> |
| 81 | + </vehicle> |
| 82 | + </mvsim_world> |
| 83 | +
|
| 84 | +Save this as ``my_world.world.xml`` and launch it: |
| 85 | + |
| 86 | +.. code-block:: console |
| 87 | +
|
| 88 | + $ mvsim launch my_world.world.xml |
| 89 | +
|
| 90 | +2 Using predefined vehicles and sensors |
| 91 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 92 | + |
| 93 | +Instead of defining vehicles from scratch, you can use the predefined definitions that ship with MVSim. |
| 94 | +These are XML files in the ``definitions/`` directory of the MVSim package. |
| 95 | + |
| 96 | +**Available vehicles:** |
| 97 | + |
| 98 | +- ``turtlebot3_burger.vehicle.xml`` -- TurtleBot3 Burger (differential drive) |
| 99 | +- ``jackal.vehicle.xml`` -- Clearpath Jackal UGV (4-wheel differential) |
| 100 | +- ``ackermann.vehicle.xml`` -- Generic Ackermann (car-like) vehicle |
| 101 | +- ``pickup.vehicle.xml`` -- Pickup truck (Ackermann) |
| 102 | +- ``agricobiot2.vehicle.xml`` -- Agricultural robot (Ackermann drivetrain) |
| 103 | + |
| 104 | +**Available sensors:** |
| 105 | + |
| 106 | +- ``lidar2d.sensor.xml`` -- Generic 2D laser scanner |
| 107 | +- ``rplidar-a2.sensor.xml`` -- RPLidar A2 |
| 108 | +- ``velodyne-vlp16.sensor.xml`` -- Velodyne VLP-16 3D LiDAR |
| 109 | +- ``ouster-os1.sensor.xml`` -- Ouster OS1 3D LiDAR |
| 110 | +- ``helios-32-FOV-70.sensor.xml`` -- Helios 32-beam 3D LiDAR |
| 111 | +- ``camera.sensor.xml`` -- RGB camera |
| 112 | +- ``rgbd_camera.sensor.xml`` -- Depth camera (RGBD) |
| 113 | +- ``imu.sensor.xml`` -- Inertial measurement unit |
| 114 | +- ``gnss.sensor.xml`` -- GPS/GNSS receiver |
| 115 | + |
| 116 | +To use a predefined vehicle with sensors attached, use XML includes: |
| 117 | + |
| 118 | +.. code-block:: xml |
| 119 | +
|
| 120 | + <mvsim_world version="1.0"> |
| 121 | + <simul_timestep>5e-3</simul_timestep> |
| 122 | +
|
| 123 | + <gui> |
| 124 | + <cam_distance>15</cam_distance> |
| 125 | + </gui> |
| 126 | +
|
| 127 | + <element class="ground_grid"> |
| 128 | + </element> |
| 129 | +
|
| 130 | + <!-- Include the Jackal vehicle definition --> |
| 131 | + <include file="$(ros2 pkg prefix mvsim)/share/mvsim/definitions/jackal.vehicle.xml" |
| 132 | + default_sensors="true" |
| 133 | + /> |
| 134 | +
|
| 135 | + <vehicle name="r1" class="jackal"> |
| 136 | + <init_pose>0 0 170</init_pose> <!-- In global coords: x,y, yaw(deg) --> |
| 137 | + <init_vel>0 0 0</init_vel> <!-- In local coords: vx,vy, omega(deg/s) --> |
| 138 | +
|
| 139 | + <!-- You can also attach sensors to vehicles in separate includes, |
| 140 | + or define them inline within the vehicle block. --> |
| 141 | + <!-- <include file="$(ros2 pkg prefix mvsim)/share/mvsim/definitions/lidar2d.sensor.xml" sensor_x="1.7" sensor_z="1.01" sensor_yaw="0" max_range="70.0" sensor_name="laser1" /> --> |
| 142 | + </vehicle> |
| 143 | +
|
| 144 | + <variable name="WALL_THICKNESS" value="0.2"></variable> |
| 145 | +
|
| 146 | + <!-- Wall with a single door --> |
| 147 | + <element class="vertical_plane"> |
| 148 | + <x0>-10</x0> <y0>-10</y0> |
| 149 | + <x1>-10</x1> <y1>10</y1> |
| 150 | + <z>0.0</z> <height>3.0</height> |
| 151 | + <cull_face>NONE</cull_face> |
| 152 | + <texture>https://mrpt.github.io/mvsim-models/textures-cgbookcase/wall-bricks-01.png</texture> |
| 153 | + <texture_size_x>2.5</texture_size_x> |
| 154 | + <texture_size_y>2.5</texture_size_y> |
| 155 | + <thickness>${WALL_THICKNESS}</thickness> <!-- Wall thickness in meters --> |
| 156 | +
|
| 157 | + <!-- Door at 50% position (middle of wall), 1.2m wide, standard height --> |
| 158 | + <door> |
| 159 | + <position>0.5</position> <!-- 0.0 = start point, 1.0 = end point --> |
| 160 | + <width>1.2</width> <!-- meters --> |
| 161 | + <z_min>0.0</z_min> <!-- bottom of door --> |
| 162 | + <z_max>2.1</z_max> <!-- top of door --> |
| 163 | + <name>main_entrance</name> |
| 164 | + </door> |
| 165 | + </element> |
| 166 | +
|
| 167 | +
|
| 168 | + </mvsim_world> |
| 169 | +
|
| 170 | +3 World environment elements |
| 171 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 172 | + |
| 173 | +MVSim supports several types of environment elements: |
| 174 | + |
| 175 | +**Occupancy grid maps** load a grayscale image as a 2D obstacle map, commonly used for indoor navigation testing: |
| 176 | + |
| 177 | +.. code-block:: xml |
| 178 | +
|
| 179 | + <element class="occupancy_grid"> |
| 180 | + <file>map.png</file> |
| 181 | + <resolution>0.05</resolution> <!-- meters/pixel --> |
| 182 | + </element> |
| 183 | +
|
| 184 | +**Elevation maps** define terrain height from a grayscale heightmap image, useful for outdoor scenarios: |
| 185 | + |
| 186 | +.. code-block:: xml |
| 187 | +
|
| 188 | + <element class="elevation_map"> |
| 189 | + <resolution>1.0</resolution> |
| 190 | + <elevation_image>terrain.png</elevation_image> |
| 191 | + <elevation_image_min_z>0.0</elevation_image_min_z> |
| 192 | + <elevation_image_max_z>5.0</elevation_image_max_z> |
| 193 | + </element> |
| 194 | +
|
| 195 | +**Textured planes** add visual ground surfaces: |
| 196 | + |
| 197 | +.. code-block:: xml |
| 198 | +
|
| 199 | + <element class="horizontal_plane"> |
| 200 | + <cull_face>BACK</cull_face> |
| 201 | + <x_min>-25</x_min> <x_max>25</x_max> |
| 202 | + <y_min>-25</y_min> <y_max>25</y_max> |
| 203 | + <z>0.0</z> |
| 204 | + <texture>asphalt.png</texture> |
| 205 | + <texture_size_x>5.0</texture_size_x> |
| 206 | + <texture_size_y>5.0</texture_size_y> |
| 207 | + </element> |
| 208 | +
|
| 209 | +**Blocks** are static or dynamic rigid bodies (boxes, custom shapes) that serve as obstacles or manipulable objects: |
| 210 | + |
| 211 | +.. code-block:: xml |
| 212 | +
|
| 213 | + <block class="obstacle1"> |
| 214 | + <shape_from_visual/> |
| 215 | + <visual> |
| 216 | + <model_uri>package://mvsim/models/box.dae</model_uri> |
| 217 | + </visual> |
| 218 | + <init_pose>3.0 2.0 0</init_pose> |
| 219 | + <mass>20</mass> |
| 220 | + </block> |
| 221 | +
|
| 222 | +4 Vehicle dynamics models |
| 223 | +^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 224 | + |
| 225 | +MVSim provides three main dynamics models: |
| 226 | + |
| 227 | +- **Differential drive** (``class="differential"``): Two-wheeled robots like TurtleBot3. |
| 228 | + Controlled via linear and angular velocity. |
| 229 | + |
| 230 | +- **Ackermann** (``class="ackermann"``): Car-like vehicles with front-wheel steering. |
| 231 | + Controlled via linear velocity and steering angle. |
| 232 | + |
| 233 | +- **Ackermann drivetrain** (``class="ackermann_drivetrain"``): Realistic drivetrain model with |
| 234 | + open or Torsen differentials, useful for more accurate vehicle behavior simulation. |
| 235 | + |
| 236 | +Each vehicle can use different motor controllers: |
| 237 | + |
| 238 | +- ``twist_pid``: Accepts ``geometry_msgs/msg/Twist`` commands with PID velocity tracking. |
| 239 | + This is the most common choice for ROS 2 integration. |
| 240 | +- ``twist_ideal``: Instantaneous velocity commands (no dynamics delay). |
| 241 | +- ``twist_front_steer_pid``: For Ackermann vehicles controlled via linear velocity and steering angle. |
| 242 | +- ``raw``: Direct wheel torque control. |
| 243 | + |
| 244 | +5 Sensor noise and configuration |
| 245 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 246 | + |
| 247 | +Sensors in MVSim support configurable noise models. |
| 248 | +For example, an IMU sensor with noise parameters: |
| 249 | + |
| 250 | +.. code-block:: xml |
| 251 | +
|
| 252 | + <sensor class="imu" name="imu1"> |
| 253 | + <pose>0 0 0.5 0 0 0</pose> <!-- x y z roll pitch yaw --> |
| 254 | + <rate_hz>100</rate_hz> |
| 255 | +
|
| 256 | + <!-- Gyroscope noise --> |
| 257 | + <gyroscope_noise> |
| 258 | + <noise_std>1e-3</noise_std> <!-- rad/s --> |
| 259 | + <bias_initial_std>1e-4</bias_initial_std> |
| 260 | + <bias_drift>1e-6</bias_drift> |
| 261 | + </gyroscope_noise> |
| 262 | +
|
| 263 | + <!-- Accelerometer noise --> |
| 264 | + <accelerometer_noise> |
| 265 | + <noise_std>1e-2</noise_std> <!-- m/s^2 --> |
| 266 | + <bias_initial_std>1e-3</bias_initial_std> |
| 267 | + <bias_drift>1e-5</bias_drift> |
| 268 | + </accelerometer_noise> |
| 269 | + </sensor> |
| 270 | +
|
| 271 | +LiDAR sensors support parameters for range, angular resolution, and noise: |
| 272 | + |
| 273 | +.. code-block:: xml |
| 274 | +
|
| 275 | + <sensor class="laser" name="laser1"> |
| 276 | + <pose>0.15 0 0.3 0 0 0</pose> |
| 277 | + <rate_hz>10</rate_hz> |
| 278 | + <ray_count>360</ray_count> |
| 279 | + <fov_degrees>360</fov_degrees> |
| 280 | + <range_max>20.0</range_max> |
| 281 | + <range_std_noise>0.01</range_std_noise> <!-- meters --> |
| 282 | + <raytrace_3d>true</raytrace_3d> <!-- use 3D collision for 2D scans --> |
| 283 | + </sensor> |
| 284 | +
|
| 285 | +6 Additional features |
| 286 | +^^^^^^^^^^^^^^^^^^^^^^ |
| 287 | + |
| 288 | +**Multi-robot simulation:** |
| 289 | +MVSim natively supports multiple vehicles in the same world. |
| 290 | +Each vehicle gets its own ROS 2 namespace, TF tree, and set of topics. |
| 291 | +Robots can detect each other with their sensors and physically interact through collisions. |
| 292 | + |
| 293 | +**Property regions:** |
| 294 | +You can define regions in the world with different physical properties, such as varying friction coefficients |
| 295 | +or GPS-denied zones where GNSS sensors stop reporting positions. |
| 296 | + |
| 297 | +**Animated actors:** |
| 298 | +MVSim supports skeletal-animated 3D characters (e.g., pedestrians) that follow waypoint paths, |
| 299 | +useful for testing perception and planning in dynamic environments. |
| 300 | + |
| 301 | +**Joints and articulated vehicles:** |
| 302 | +Vehicles can be connected using distance joints (ropes/cables) or revolute joints (hinges), |
| 303 | +enabling simulation of trailers, tow ropes, and articulated systems. |
| 304 | + |
| 305 | +**XML advanced features:** |
| 306 | +World files support ``<include>`` directives, variable substitution, mathematical expressions, |
| 307 | +``<for>`` loops, and ``<if>`` conditionals, making it possible to procedurally generate complex environments. |
| 308 | + |
| 309 | +**Headless and faster-than-real-time:** |
| 310 | +MVSim can run without a GUI and at configurable simulation speed, |
| 311 | +which is useful for automated testing and reinforcement learning workflows. |
| 312 | + |
| 313 | +Comparison with other simulators |
| 314 | +-------------------------------- |
| 315 | + |
| 316 | +MVSim occupies a different niche compared to other simulators: |
| 317 | + |
| 318 | +**Strengths:** |
| 319 | + |
| 320 | +- Very lightweight: low CPU and memory usage, fast startup times. |
| 321 | +- Focused vehicle dynamics with multiple friction and drivetrain models. |
| 322 | +- Simple XML-based world format, easy to get started. |
| 323 | +- Native multi-robot support with per-vehicle ROS 2 namespaces. |
| 324 | +- Faster-than-real-time simulation for batch testing. |
| 325 | +- Procedural world generation via XML loops and conditionals. |
| 326 | + |
| 327 | +**Limitations:** |
| 328 | + |
| 329 | +- Physics is 2D (Box2D): no full 3D rigid body dynamics. |
| 330 | + Objects do not tip over or fly. |
| 331 | + Elevation maps add terrain height but the physics remains fundamentally 2D. |
| 332 | +- Sensor simulation is less detailed than full 3D simulators: camera rendering and LiDAR models |
| 333 | + are functional but not photorealistic. |
| 334 | +- Smaller ecosystem of pre-built models and environments compared to Gazebo. |
| 335 | +- Focused on wheeled mobile robots. |
| 336 | + |
| 337 | +Further resources |
| 338 | +----------------- |
| 339 | + |
| 340 | +- `MVSim documentation <https://mvsimulator.readthedocs.io/>`__ |
| 341 | +- `MVSim GitHub repository <https://github.com/MRPT/mvsim>`__ |
| 342 | +- `MVSim paper (SoftwareX) <https://doi.org/10.1016/j.softx.2023.101443>`__ |
0 commit comments