Skip to content

Latest commit

 

History

History
228 lines (168 loc) · 11.8 KB

README.md

File metadata and controls

228 lines (168 loc) · 11.8 KB

rmf_simulation

This repository contains simulation plugins used in Open-RMF. It currently supports Gazebo Classic 11 and Gazebo Fortress.

Simulation plugins are split in Building simulation and Robot simulation plugins

Building Simulation

Building simulation plugins are located under rmf_building_sim_* and used to simulate different aspect of buildings such as doors, lifts and crowds (currently through the Menge library). Utility plugins to help with simulation, such as UI widgets to toggle battery consumption and set charging behavior, as well as toggling floor visibility, are also placed in this category.

Door plugin

The door plugin is a model plugin that can be attached to door models to make them interface with Open-RMF. It adds a publisher for door state and a subscription to door requests. An example SDF snippet is below:

<plugin name="door" filename="libdoor.so">
  <v_max_door>0.5</v_max_door>
  <a_max_door>0.3</a_max_door>
  <a_nom_door>0.15</a_nom_door>
  <dx_min_door>0.01</dx_min_door>
  <f_max_door>500.0</f_max_door>
  <door name="main_door" type="DoubleSwingDoor" left_joint_name="left_joint" right_joint_name="right_joint" />
</plugin>

Where:

  • v_max_door is the maximum velocity of the door joints.
  • a_max_door is the maximum acceleration of the door joints.
  • a_nom_door is the nominal acceleration that the door controller will aim for when opening / closing doors.
  • dx_min_door is the threshold used to determine whether the door is open, closed or moving. Specifically if all the door joints are within dx_min_door of their closed position the door will be considered closed, if they are within dx_min_door of their open position the door will be considered closed, otherwise it will be considered moving.
  • f_max_door is the maximum effort for the physics simulation.
  • door is a child element with a series of child attributes:
    • name is the name of the door, as seen by Open-RMF.
    • type is a string that describes the door type, supported door types can be found in rmf_building_map_tools repo.
    • left_joint_name and right_joint_name are the names of the left and right joint for the door, for double doors both are expected to be names of joints in the model, for single doors one of them can be empty or set to empty_joint to make the simulation plugin ignore it.

Lift plugin

The lift plugin is a model plugin that can be attached to lifts to make them interface with Open-RMF. It adds a publisher for lift state and a subscription to lift requests. An example SDF snippet is below:

<plugin name="lift" filename="liblift.so">
  <lift_name>lift_1</lift_name>
  <floor name="L1" elevation="0.0">
    <door_pair cabin_door="CabinDoor_lift_1_lift_1_door" shaft_door="ShaftDoor_lift_1_L1_lift_1_door" />
  </floor>
  <floor name="L2" elevation="10.0">
    <door_pair cabin_door="CabinDoor_lift_1_lift_1_door" shaft_door="ShaftDoor_lift_1_L2_lift_1_door" />
  </floor>
  <initial_floor>L1</initial_floor>
  <v_max_cabin>2.0</v_max_cabin>
  <a_max_cabin>1.2</a_max_cabin>
  <a_nom_cabin>1.0</a_nom_cabin>
  <dx_min_cabin>0.001</dx_min_cabin>
  <f_max_cabin>25323.0</f_max_cabin>
  <cabin_joint_name>cabin_joint</cabin_joint_name>
</plugin>

Where:

  • lift_name is the name of the lift, as seen by Open-RMF.
  • floor describes a floor, there can be any amount of floor elements with:
    • name attribute with the name of the floor, as seen by Open-RMF.
    • elevation attribute with the height in meters of the floor, relative to the ground plane.
    • door_pair child element with a cabin_door attribute to specify which cabin door should open at this floor and a shaft_door attribute to specify which shaft door should open. These names should match the names of doors in the world file.
  • initial_floor The floor that the lift should start at.
  • v_max_cabin, a_max_cabin, a_nom_cabin, dx_min_cabin and f_max_cabin are motion parameters with the same meaning as the ones in the door plugin.
  • cabin_joint_name is the name of the main joint of the cabin, which is the one to be actuated vertically.

Crowd simulation

Crowd simulation configuration is added as a world plugin and is more complex and autogenerated, for an in depth description check the documentation here

Toggle charging

Toggle charging is a world plugin, added by default to all Open-RMF worlds that adds a GUI to toggle charging behaviors, such as enabling / disabling battery consumption or setting chargers to instantly refill the robot battery to reduce idle time in simulations.

It is added with the following snippet:

<plugin name="toggle_charging" filename="libtoggle_charging.so" />

Toggle floors

Toggle charging is a world plugin, added by default to all Open-RMF worlds, that adds a GUI plugin with buttons to enable / disable visibility of specific floors, to make visualization of intermediate floors easier.

An example SDF snippet:

<plugin name="toggle_floors" filename="libtoggle_floors.so">
  <floor name="L1" model_name="clinic_L1">
    <model name="OpenRobotics/PotatoChipChair" />
    <model name="OpenRobotics/PotatoChipChair_2" />
  </floor>
</plugin>

The plugin element has a list of floor children, each of them with:

  • name attribute that will be displayd in the GUI button.
  • model_name points to the name of the floor model generated by rmf_building_map_tools.
  • A list of model children, each with the name of a model that resides on that level.

Robot simulation

Robot simulation plugins under rmf_robot_sim_* are used to simulate aspects of robots behavior, including robot navigation and interfaces to workcells.

Slotcar

Slotcar is a model plugin that acts as a simple robot navigation stack, controlling the robot and sending updates to its fleet adapter through ROS 2 topics.

An example, taken from rmf_demos TinyRobot, is below:

 <plugin name="slotcar" filename="libslotcar.so">

   <nominal_drive_speed>0.5</nominal_drive_speed>
   <nominal_drive_acceleration>0.25</nominal_drive_acceleration>
   <max_drive_acceleration>0.75</max_drive_acceleration>

   <nominal_turn_speed>0.6</nominal_turn_speed>
   <nominal_turn_acceleration>1.5</nominal_turn_acceleration>
   <max_turn_acceleration>2.0</max_turn_acceleration>

   <tire_radius>0.1</tire_radius>
   <base_width>0.3206</base_width>

   <stop_distance>0.75</stop_distance>
   <stop_radius>0.75</stop_radius>

   <!-- Can the robot drive backwards -->
   <reversible>true</reversible>

   <!-- Battery params -->
   <nominal_voltage>12.0</nominal_voltage>
   <nominal_capacity>24.0</nominal_capacity>
   <charging_current>5.0</charging_current>

   <!-- Physical params -->
   <mass>20.0</mass>
   <inertia>10.0</inertia>
   <friction_coefficient>0.22</friction_coefficient>

   <!-- Power systems -->
   <nominal_power>20.0</nominal_power>

 </plugin>

The plugin has the following parameters:

  • nominal_drive_speed, nominal_drive_acceleration, max_drive_acceleration, motion parameters for linear velocity similar to the door plugin.
  • nominal_turn_speed, nominal_turn_acceleration, max_turn_acceleration, motion parameters for angular velocity.
  • tire_radius, base_width, used to convert the requested linear velocity from Open-RMF into a differential drive velocity for the single wheels. Currently only used for Gazebo Classic since Gazebo moves the model itself.
  • stop_distance and stop_radius are added to do simple collision avoidance for the robot, if a robot is closer than stop_distance + stop_radius to another object it will trigger an emergency stop.
  • reversible boolean that denotes whether the robot can drive backwards or not.
  • nominal_voltage voltage of the robot battery.
  • nominal_capacity capacity in Ampere-hour of the robot battery.
  • charging_current Current of the charger, ignored if the charging is set to instantaneous.
  • mass, robot mass in kilograms.
  • inertia, angular moment of inertia around the Z axis, in kg*m^2.
  • friction_coefficient, amount of energy lost in linear movement due to friction, between 0 and 1.
  • nominal_power, the amount of power used by the robot even when idle (in W).

Readonly

Readonly is a model plugin that can be attached to mobile entities that only provide their position to Open-RMF. The plugin uses the entity's current position and heading, together with a provided navigation graph, to estimate its itinerary and provide it to other fleets for traffic deconfliction.

An example from rmf_demos Caddy below:

<plugin name="readonly" filename="libreadonly.so">
  <!-- Map name where the robot is spawned -->
  <level_name>L1</level_name>
  <!-- Index of navigation graph for the robot as stored in BuildingMap msg -->
  <graph_index>2</graph_index>
  <!-- Name of waypoint where caddy is spawned in the map -->
  <spawn_waypoint>caddy</spawn_waypoint>
  <!-- Number of waypoints to include in predicted path -->
  <look_ahead>3</look_ahead>
  <!-- Update rate (hz) at which robot_state is published -->
  <update_rate>15</update_rate>
  <!-- Waypoint threshold (m). Radius around the waypoint to determine if caddy is at that waypoint   -->
  <waypoint_threshold>2.0</waypoint_threshold>
  <!-- If true, predicted path will merge robot with nearest lane -->
  <merge_lane>false</merge_lane>
  <!-- Normal distance of robot from its lane, greater than which its path will merge with the lane -->
  <lane_threshold>0.2</lane_threshold>
</plugin>

In this example, the robot will use navigation graph index 2 and try to generate a path with 3 waypoints ahead of its current location and heading and publish state updates at 15 Hz. waypoint_threshold, merge_lane and lane_threshold are used to determine whether a robot is on a waypoint, a lane, or outside of the navigation graph.

Teleport dispenser

Teleport dispenser is a model plugin that dispenses objects to a robot by finding the closest non static object and teleporting it to the closest robot. An example snippet is below:

<plugin name="teleport_dispenser" filename="libteleport_dispenser.so"/>

Teleport ingestor

Teleport ingestor is a model plugin that ingests an object from a robot by finding the closest non static items to a robot and teleporting it to the ingestor's location.

An example snippet is below:

<plugin name="teleport_ingestor" filename="libteleport_ingestor.so"/>

Repository organization

Most plugins are split into a common, gz and gz_classic package. The common package contains the simulator independent logic, such as ROS 2 publishers / subscribptions, core logic, while the gz and gz_classic packages contain a wrapper to interface to the specific simulators.

Supported versions

Since Gazebo and ROS 2 have a different release schedule, this package will follow the ros_gz supported version and, depending on which ROS 2 version Open-RMF is currently targeting, the Gazebo version will be set accordingly to allow using the binary release of the ros_gz_bridge. For example, previous supported versions have been ROS Galactic <-> Gazebo Edifice and ROS Humble <-> Gazebo Fortress.

Gazebo Classic support through the gz_classic plugins is only guaranteed until Gazebo 11 EOL (currently scheduled for January 2025) and might be removed afterwards. Users are encouraged to use Gazebo for future development.