Welcome to Flatland’s documentation!¶
Flatland is a performance centric 2D robot simulator started at Avidbots Corp.. It is intended for use as a light weight alternative to Gazebo Simulator for ground robots on a flat surface. Flatland uses Box2D for physics simulation and it is built to integrate directly with ROS. Flatland loads its simulation environment from YAML files and provide a plugin system for extending its functionalities.
The code is open source and available on Github, BSD3 License.
Class APIs are documented here.

Flatland Simulator Overview¶
This document provides an overview of Flatland Simulator.
Flatland Simulator is a light weight, performance centric 2D robot simulator. It is built to integrate directly with ROS and uses Box2D for physics simulation. This project is divided into four ROS packages: flatland_server, flatland_plugins, and flatland_viz, and flatland messages.
Flatland Server¶
Flatland server contains the core functionalities of Flatland Simulator including simulation environment, objects, plugin interfaces, and ROS services. All of flatland server runs in a single ROS node, in a single thread. The following are some of the commonly used terminologies in the Flatland Server.
- Simulation Manager: Simulation manager is responsible for managing the state of the simulator. It manages how the world progresses through time, as well ROS Services to interact with the simulation.
- World: World is everything that lives in the simulation, including the layers, models, time, and other physical properties. It also manages the plugins.
- Layer: Layer represents the static environment features in the simulation such as walls in a building. It allows large scale static features to be loaded and represented in an efficient manner. Flatland allows a powerful feature where multiple layers can be used to represent what is effectively a 2.5D world.
- Model: Models are collection of bodies. It can be used to represent any physical entities, such as robots, people, automatic doors, or chairs.
- Body: A body is a indeformable and inseparable piece of entity. A body does not need to contiguous, the actual physical outlines are defined by a collection of footprints. Body manages physical states such as position and velocity. The concept is equivalent to a Body in Box2D physics engine.
- Footprint: A footprint defines the actual physical size, shape, and material properties. It manages physical properties such as density and friction. It is contiguous. The concept is equivalent to a Fixture in Box2D physics engine.
- Joint: A joint is used to connect two pieces of bodies. It defines additional constraints on how the two bodies must interact with each other. The concept is equivalent to a Joint in Box2D physics engine.
- Pose: Pose is always the x, y, and angle of an object
- Origin: Origin is the position and orientation of the coordinate system
Flatland Plugins¶
Flatland Plugins contains the useful plugins that were developed for use with the flatland 2D simulator.
Flatland Visualization¶
Flatland Visualization contains the visualization portion of 2D simulator. Visualization in flatland is completely ROS based. Once the visualization option is turned on, the 2D simulator would convert the models and layers to ROS markers messages and publish them through ROS topics. Thus, flatland visualization can also be viewed directly on rviz, however the user needs to manually subscribe to topics, whereas flatland_viz is written to automatically show visualization for models and layers in the simulation.
Flatland Messages¶
The package flatland_msgs defines ROS messages and services used by the Flatland Simulator.
Software Architecture¶
The following figure shows the top level software architecture. The architecture closely resembles the Rviz top level software architecture.

Build¶
The software uses CMakeFiles and a catkin workspace. To build: cd to the root of the catkin workspace and type catkin_make.

Quick Start¶
Here is a quick guide for setting up 2D simulator.
Flatland uses YAML files to setup the simulation, much like how Gazebo uses URDF files.
Create a YAML file called world.yaml with the following content
Here we define a world with a layer called “map” and one model “turtlebot”. See Configuring World for more details.
properties: {} layers: - name: "map" map: "conestogo_office.yaml" color: [0.4, 0.4, 0.4, 1] models: - name: turtlebot model: "turtlebot.model.yaml"
One way of defining a layer map is to use data generated from ROS map_server, if you have map from map_server you can replace map.yaml with the path to the YAML file from map server, and skip the rest of this section. See Configuring Layers for more details.
Otherwise, create a file named conestogo_office.yaml with the following content, download the map image below, and place both the yaml file and the image in the same directory as world.yaml
- To define a model, create a file named turtlebot.model.yaml with the following content and place it in the same directory as world.yaml. For more details about the model yaml format, see Configuring Models.
bodies: - name: base pose: [0, 0, 0] type: dynamic color: [1, 1, 1, 0.4] footprints: - type: circle radius: 0.5 density: 1 - type: polygon points: [[-.45, -.05], [-.45, 0.05], [-.35, 0.05], [-.35, -0.05]] density: 1 - type: polygon points: [[-.125, -.4], [-.125, -.3], [.125, -.3], [.125, -.4]] density: 1 - type: polygon points: [[-.125, .4], [-.125, .3], [.125, .3], [.125, .4]] density: 1 plugins: - type: DiffDrive name: turtlebot_drive body: base
- Finally, after having the Flatland packages installed. Run the launch file with the path to the world.yaml. You should be able to see the flatland_viz window with the map and the robot. You can send Twist commands to /cmd_vel to move the robot.
$ roslaunch flatland_server server.launch world_path:=/path/to/world.yaml

Create Plugin Tutorial¶
Description: This tutoial provides the information needed to create a plugin for use in the flatland simulator.
Tutorial Level: BEGINNER
With the flatland simulator, similar to Rviz, Gazebo and ROS, it is possible to extend the built-in functionality using plugins. A flatland simulator plugin is a C++ class that derives from the flatland_server::ModelPlugin base class.
This tutorial provides step by step instruction on how to write your own plugin and get it working inside the flatland simulator.
1. Prerequisites¶
The following tutorials provide a good foundation for understanding the flatland simulator architecture:
2. Getting Started¶
We will be creating a very simple plugin. The plugin will do one thing: print “Hello world” to the ROS_ERROR_STREAM. Even though the plugin itself is quite simple, the process for getting it to function inside Flatland simulator has many steps.
3. Install ROS¶
Go to the location on your harddrive you wish to install the Flatland stack. Create the top level of the cakin workspace:
mkdir flatland_ws
cd flatland_ws/
Create the source directory:
mkdir src
cd src
Git clone the Flatland stack:
git clone https://github.com/avidbots/flatland.git
cd ..
From inside the flatland_ws directory, build the software:
catkin_make
Source the setup file:
source devel/setup.bash
Run the Flatland simulator:
roslaunch flatland_server server.launch
You should see a Flatland window appear:

4. Create a Flatland Plugin¶
Go to model_plugin for detailed instructions on how to write a plugin.
Create a new file called simple.h in the flatland_plugins/include/flatland_plugins directory.
#include <flatland_server/model_plugin.h>
#ifndef FLATLAND_PLUGINS_SIMPLE_H
#define FLATLAND_PLUGINS_SIMPLE_H
using namespace flatland_server;
namespace flatland_tutorials {
class Simple : public ModelPlugin {
public:
void OnInitialize(const YAML::Node &config) override;
};
};
#endif
Create a new file called simple.cpp in the flatland_plugins/src directory.
#include <flatland_plugins/simple.h>
#include <pluginlib/class_list_macros.h>
#include <ros/ros.h>
using namespace flatland_server;
namespace flatland_tutorials {
void Simple::OnInitialize(const YAML::Node &config) {
ROS_ERROR_STREAM("Hello world");
}
};
PLUGINLIB_EXPORT_CLASS(flatland_tutorials::Simple, flatland_server::ModelPlugin)
5. Compiling the Plugin¶
You may need to add to the include path. Refer to the documentation for the specific SDK/editor you are using.
Edit the file flatland_plugins.xml. Add the following before the closing </library> tag.
<class type="flatland_plugins::Simple" base_class_type="flatland_server::ModelPlugin">
<description>Simplest possible plugin to print hello world</description>
</class>
Locate the add_library section and add the following before the closing ‘)’ :
src/simple.cpp
Edit the file flatland_server/test/conestogo_office_test/cleaner.model.yaml. After the line plugins: add the following followed by a blank line.
- type: Simple
name: simple
6. Running the Flatland simulator with installed plugin¶
Run the Flatland simulator:
roslaunch flatland_server server.launch
Kill the program and look at the console output. You should see the message “Hello world” embedded in the output.


Create Model Tutorial¶
Description: This tutoial provides the information needed to create a model for use in the flatland simulator.
Tutorial Level: BEGINNER
This tutorial provides step by step instruction on how to create your own model and get it working inside the flatland simulator.
1. Prerequisites¶
The following tutorials provide a good foundation for understanding the flatland simulator architecture:
2. Getting Started¶
Note
Flatland includes the Box2d physics engine library.
Box2D is a 2D rigid body simulation library. For the simulation of a robotic cleaner and its environment, the vehicle moves along the floor: it is constrained to translate in only two dimensions.
We take advantage of this fact to simplify the problem of simulating a physical body from six dimensions to three dimensions. Specifically, the vehicle is constrained by gravity to move only in the x-y plane. The vehicle’s rotation is also constrained by the floor to rotate only about the z-axis.
Our 2D approximation of the 3D world uses x, y and theta. The Box2d library is specifically designed for this type of simulation. Flatland provides Box2d with the information needed to setup the 2D simulation including initial position and model properties
3. Box2d Core Concepts¶
For a complete description of the Box2d core concepts, see the user doccumentation here b2d_docs. This section provides a brief description of the Box2d core concepts that apply to making a model.
shape: A shape is 2D geometrical object, such as a circle or polygon.
|
rigid body: A chunk of matter that can not be deformed
|
fixture: A fixture binds a shape to a body and adds material
properties such as density, friction, and restitution.
|
constraint: A constraint is a physical connection that removes
degrees of freedom from bodies.
|
joint: This is a constraint used to hold two or more bodies together.
|
joint limit: A joint limit restricts the range of motion of a joint.
|
world: A physics world is a collection of bodies, fixtures, and
constraints that interact together
|
You can create a brand new model in flatland using a model definition yaml file. In that file, you define the Box2d model parameters including the shape, fixtures, joints and limits.
You can also write a plugin and asscociate it with your model. Through the plugin you have access to the Box2d physics engine. So you can do things like apply a force or an impact to any body in your model. You can also get back the new vehicle pose so it can be displayed inside the Flatland world.
3. Yaml Model File Format¶
bodies:
- name: base
type: dynamic
color: [1, 1, 1, 0.75]
footprints:
- type: polygon
density: 100
points: [ [-1.03, -0.337],
[.07983, -0.337],
[.30, -.16111],
[.30, .16111],
[.07983, 0.337],
[-1.03, 0.337] ]
- name: front_wheel
color: [1, 1, 1, 0.75]
footprints:
- type: polygon
density: 1.0
points: [[ 0.0875, -0.0250],
[ 0.0875, 0.0250],
[-0.0875, 0.0250],
[-0.0875, -0.0250]]
- name: rear_left_wheel
color: [1, 1, 1, 0.75]
footprints:
- type: polygon
density: 1.0
points: [[ 0.0875, -0.0255],
[ 0.0875, 0.0255],
[-0.0875, 0.0255],
[-0.0875, -0.0255]]
- name: rear_right_wheel
color: [1, 1, 1, 0.75]
footprints:
- type: polygon
density: 1.0
points: [[ 0.0875, -0.0255],
[ 0.0875, 0.0255],
[-0.0875, 0.0255],
[-0.0875, -0.0255]]
joints:
- type: revolute
name: front_wheel_revolute
bodies:
- name: front_wheel
anchor: [0, 0]
- name: base
anchor: [0, 0]
- type: weld
name: rear_right_wheel_weld
bodies:
- name: rear_left_wheel
anchor: [0, 0]
- name: base
anchor: [-0.83, 0.29]
- type: weld
name: rear_left_wheel_weld
bodies:
- name: rear_right_wheel
anchor: [0, 0]
- name: base
anchor: [-0.83, -0.29]
plugins:
- type: ModelTfPublisher
name: tf_publisher
publish_tf_world: true
- type: TricycleDrive
name: cleaner_drive
body: base
front_wheel_joint: front_wheel_revolute
rear_left_wheel_joint: rear_left_wheel_weld
rear_right_wheel_joint: rear_right_wheel_weld
odom_frame_id: map
- type: Laser
name: laser_front
frame: laser_front
topic: scan
body: base
broadcast_tf: true
origin: [0.28, 0, 0]
range: 20
angle: {min: -2.356194490192345, max: 2.356194490192345, increment: 0.004363323129985824}
noise_std_dev: 0.05
update_rate: 40

Spawn Model Tutorial¶
Description: This tutoial provides the information needed to spawn a model for use in the flatland simulator.
Tutorial Level: BEGINNER
This tutorial provides step by step instruction on how to spawn a model using the Flatland UI.
Note
Flatland and Rviz tools can be used interchangeably in either the Flatland or Rviz software.
1. Prerequisites¶
The following tutorials provide a good foundation for understanding the flatland simulator architecture:
2. Installation¶
To use the Spawn Model Tool, first it must be installed. The following animated gif shows the installation process.
First click on the + button to bring up the tool selection dialog. Next choose the Spawn model tool from the available tools.
Finally, click the ok button to confirm your selection. A new button appears on the right side of the toolbar.

Warning
If the Flatland window is too small, some of the tools might not be visible.
3. Usage¶
To spawn a model begin by clicking the spawn model tool button in the toolbar at the top of
the Flatland window. The spawn model popup dialog appears. The spawn model tool must be provided
with a valid Flatland model file in Yaml format.

4. Number checkbox¶
The number checkbox enables automatically appending the model name with a number that increases by one each time. This ensures each model name will always be unique. It is a good idea to turn this on if you intend to spawn more than one occurance of the same model.

5. Name text field¶
The name text field recieves the file name of the file chosen using the file selection dialog (with the path removed). You can choose to override this name with a name of your choosing.

6. Placing and rotating model¶
There are three sequential phases to spawning a model.
The menu, translation and the rotation. When you click on the spawn model button
you enter the menu phase. During this phase you can change the model name.
When ready to proceed, click the ok button. You are now in the translation phase. The dialog disappers and your 2D model appears attached to the cursor. Move the cursor to the location on the floor where you want to place your model. Left click to place the model and enter the rotation phase.
During the rotation phase, the model remains pinned to one location on the floor, however it will rotate to point at the cursor. Move the cursor in a circle around your model until it is pointing in the desrired direction. Left click to exit the spawn model tool. The model will appear in the Flatland world at the desrired position and orientation.


Create Custom Robot Tutorial¶
Description: This tutoial provides the information needed to create a robot from scratch for use in the flatland simulator.
Tutorial Level: BEGINNER
1. Prerequisites¶
The following tutorials provide a good foundation for understanding the flatland simulator architecture:
2. Create the model Yaml file¶
Create a new Yaml file, or make a copy of an existing Yaml file as a starting place. The Yaml files can be located anywhere, however, the usual location is within the Flatland simulator directory structure:
flatland_server/test/conestogo_office_tests
We will start with a simple custom model and increase the complexity as we go. Edit your custom robot model file to contain the following:
bodies:
- name: base
type: dynamic
color: [1, 1, 1, 1]
footprints:
- type: polygon
density: 100
points: [ [-1.03, -0.337],
[.07983, -0.337],
[.30, -.16111],
[.30, .16111],
[.07983, 0.337],
[-1.03, 0.337] ]
This model has one body, of type dynamic and color white. It defines a polygonal footprint with a density of 100. The shape is a box with corners trimmed.
3. Configure Flatland to load your model¶
There are two ways to load a model into the Flatland simulator. You can load
your model ineractively using the Spawn Model Tool or you can configure the
simulaor to automatically load your model on startup.
Note
Any errors generated while loading a model will be sent to the console where the Flatland simulator was started.
If you want to configure the Flatland Simulator to load your specific robot model during startup, follow the instructions below.
Make a copy of the default world Yaml file:
cd flatland_server/test/conestogo_office_test
cp world.yaml custom_world.yaml
Edit your custom world yaml file and add the following:
models:
- name: your_custom_model
pose: [0, 0, 0]
model: "your_custom_model.yaml"
Note
Delete the default model if desired.
To run the Flatland simulator with your custom model, you must provide the following world_path override on the launch command:
roslaunch flatland_server server.launch world_path:=/home/mikeb/Dev/flatland_ws/src/flatland/flatland_server/test/conestogo_office_test/your_custom_world.yaml
Warning
You need to modify the path above to use the location of your Flatland installation.
You should see the flatland window appear with your new custom robot at x=0, y=0.

Launching Flatland Server Node¶
Flatland Server provides a launch file to start the 2D simulator. The parameters for the launch file is specified below.
Run this following command to launch the simulator using default parameters
$ roslaunch flatland_server server.launch world_path:=/path/to/world.yaml
Here are the full list of parameters with the default values
$ roslaunch flatland_server server.launch world_path:=/path/to/world.yaml \
update_rate:=200.0 \
step_size:=0.005 \
show_viz:=true \
viz_pub_rate:=30.0 \
use_rviz:=false
- world_path: path to world.yaml
- update_rate: the real time rate to run the simulation loop in Hz
- step_size: amount of time to step each loop in seconds
- show_viz: show visualization, pops the flatland_viz window and publishes visualization messages, either true or false
- viz_pub_rate: rate to publish visualization in Hz, works only when show_viz=true
- use_rviz: works only when show_viz=true, set this to disable flatland_viz popup

Configuring World¶
The simulation world is defined by a YAML file as shown below. Examples can be found in flatland_server/tests.
# required, world properties
properties:
# optional, defaults to 10, number of velocity iterations for the Box2D
# physics solver
velocity_iterations: 10
# optional, defaults to 10, number of position iterations for the Box2D
# physics solver
position_iterations: 10
# required, specifies a list of layers, maximum number of layers is 16,
# constrained by Box2D's collision masks
layers:
# required, name of the layer, each layer name must be unique
- name: "layer_1"
# required, path to the map yaml file, begin with "/" to indicate
# absolute path, otherwise relative path w.r.t this file is used
map: "layer_1.yaml"
# optional, defaults to [1, 1, 1, 1], color for visualization specified
# by [r, g, b, alpha]
color: [1, 1, 1, 1]
# you can also specify a list of names. These names will point to the same
# entity in the physics engine. This introduces an efficient way of organizing
# entities into the same physical layer without loading the same map more
# than once. Only the first name in this list is used to identify this entity,
# such as in visualizations or collision handling. The number of layers here
# also counts towards the maximum number of 16 layers.
- name: ["layer_2", "layer_3", "layer_4"]
map: "/absolute/path/layer_2.yaml"
# optional, specifies a list of models to be loaded into the world, if you
# don't need models to load right at the start, you don't need provide this
# yaml entry
models:
# required, name of the model, must be unique in the world
- name: turtlebot1
# optional, defaults to "", specifies the namespace of the robot. Used
# for situations where multiple models of the same type are instantiated,
# in order to avoid conflicts in TF transforms and ROS topic names. It is
# used to initialize the namespace of the node handle of model plugins
# under this model. Not enforced to be unique when set, but it should be
# unique for all practical purposes
namespace: ""
# optional, defaults to [0, 0, 0], pose to put the model, in the format
# of [position x, position y, angle yaw] in the world coordinate
pose: [0, 0, 0]
# required, path to the model yaml file, begin with "/" to indicate
# absolute path, otherwise relative path w.r.t this file is used
model: "turtlebot.model.yaml"
- name: turtlebot12
namespace: "turtlebot2"
model: "turtlebot.model.yaml"
- name: person
model: "/absolute/path/person.model.yaml"

Configuring Layers¶
In Flatland, a layer represents the static environment features in the simulation, they are defined by map YAML files and implemented as line segments (Box2D edge shapes). Layers can be loaded in two ways, either using data obtained from ROS map_server (an image), or directly from a list of line segments. Examples can be found in flatland_server/tests.
From Map Server Data¶
Map server yaml and image format is specified here. Flatland extracts line segments by first thresholding the image by the occupied_thresh which creates a binary image, then put a line segment between two rows or columns of pixels where a transition from 0 to 1, or 1 to 0 occurs. Collinear lines are merged. Note large and noisy maps could easily results in hundreds of thousands of line segments which degrades performance.
An example of the YAML file is shown below. Note that the “negate” and “free_thresh” are not used to generate line segments.
image: map.png # begin with "/" for absolute, otherwise relative w.r.t this file
resolution: 0.050000
origin: [-16.600000, -6.650000, 0.000000]
negate: 0 # NOT used
occupied_thresh: 0.65
free_thresh: 0.196 # NOT used
An example of map image is shown below.

Directly from Line Segments¶
Loading line segments directly give flexibility for users to decide how to specify line segments that represent their environment.
To load line segments, you need need to create a line segments YAML file similar to the map server yaml file, as well as a data file containing the actual line segments.
An example of the line segments map YAML file is shown below. All parameters are required.
type: line_segments # required for indicating file type is line segments
data: map_lines.dat # path to line segments data file, begin with "/" for absolute, otherwise relative w.r.t this file
scale: 0.1 # same use as resolution in map server yaml
origin: [-1.20, -5, 1.23] # same use as origin in map server yaml
A Line segment data file is simply a file with each line containing a line segment. There are four columns: x1, y1, x2, y2. (x1, y1) is the start point of a line segment, (x2, y2) is the end point of a line segment. For example, a line segment file with just two line segments, one from (0, 0) to (1, 1), and the other from (2, 3) to (-1, 2) will be as follows.
0 0 1 1
2 3 -1 2

Configuring Models¶
In Flatland, a model is a collection of bodies, and it can be used to represent any physical things. An example of a model file for a turtlebot (not exactly) is shown here. Examples can be found in flatland_server/tests.
# required, list of bodies of the model, must have at least one body
bodies:
# required, name of the body, must be unique within the model
- name: base_link
# optional, default true. If false (see yaml preprocessor for details), this body is skipped
enabled: true
# optional, defaults to [0, 0, 0], in the form of [x, y, theta] w.r.t the
# model pose specified in world yaml. Pose is simply the initial pose
# of the body, it does not add additional constrains in any way
pose: [0, 0, 0]
# optional, default to dynamic, must be one of dynamic, static, kinematic,
# these are consistent with Box2D's body types
type: dynamic
# optional, default to [1 ,1, 1, 0.5], in the form of [r, g, b, alpha],
# for visualization
color: [1, 1, 1, 0.5]
# optional, defaults to 0.0, specifies the Box2D body linear damping
linear_damping: 0
# optional, defaults to 0.0, specifies the Box2D body angular damping
angular_damping: 0
# required, list of footprints for the body, you can have any number of
# footprints
footprints:
# required, type of footprint, valid options are circle and polygon
- type: circle
# required, radius of the circle footprint, only used for circle type
radius: 0.5
# optional, defaults to [0, 0], in the form of [x, y] w.r.t the origin
# of the body, only used for circle type
center: [0.0, 0.0]
# optional, defaults to ["all"], a list of layers specifying which
# layer the footprint belongs to, collisions/contacts only occurs
# between objects in the same layer, used for all footprint types
layers: ["all"]
# optional, defaults to true
# If set to "false" entirely disables collision with this object
# Does not disable interactions like the laser scan plugin.
collision: true
# required, the density of footprint in kg/m^2 in Box2D, used for all
# footprint types
density: 1
# optional, default to 0.0, specifies Box2D fixture friction, used for
# all footprint types
friction: 0
# optional, default to 0.0, specifies Box2D fixture restitution, used
# for all footprint types
restitution: 0
# optional, default to false, whether to set as Box2D sensor, sensor
# detects collisions/contacts but does not have responses, used for
# all footprint types
sensor: false
# body for the rear wheel
- name: rear_wheel
footprints:
# an example for polygon type
- type: polygon
# required, vertices for polygon, 3 <= length <= 8 (limited by Box2D),
# in the form of [x, y] coordinates w.r.t body origin, only used for
# polygon type
points: [[-0.05, -0.05], [-0.05, 0.05], [0.05, 0.05], [0.05, -0.05]]
density: 1
# body for left wheel
- name: left_wheel
footprints:
- type: polygon
points: [[-.125, -0.05], [-.125, 0.05], [.125, 0.05], [.125, -0.05]]
density: 1
# body for right wheel, notice how left wheel and right wheel are the same
# they will be spawned in the same location with pose [0, 0, 0] by default,
# joints need to be used to snap them in place
- name: right_wheel
footprints:
- type: polygon
points: [[-.125, -0.05], [-.125, 0.05], [.125, 0.05], [.125, -0.05]]
density: 1
# optional, list of model joints
joints:
# required, type of the joint, available options are revolute or weld,
# corresponds to Box2D joint types, applies to all joint types
- type: revolute
# required, name of the joint, unique within the body, applies to all
# joint types
name: rear_wheel_revolute
# optional, default true. If false (see yaml preprocessor for details), this joint is skipped
enabled: true
# optional, default to false, specifies whether two bodies connected a
# this joint should collide with each other, applies to all joint types
collide_connected: false
# optional, in the format of [lower limit, upper limit], if specified
# confines the rotation of the joint within the limits, or it is free to
# rotate 360 degrees otherwise, applies only to revolute joints
limits: [0, 0]
# required, specifies the anchor point on each body, applies to all joint
# types
bodies:
# required, name of a body from this body
- name: rear_wheel
# required, an anchor point w.r.t. the origin of the body
anchor: [0, 0]
# required, name of another body in the model
- name: base_link
# required, an anchor point w.r.t. the origin of the body
anchor: [-0.83, -0.29]
# now specifying a weld joint, note that weld joint is not 100% fixed due
# to how the physics is numerically solved, i.e. if an infinite force is
# applied to immoveable object or a high impact collision, then the joint
# will deform. Maximum rigidity can be achieved by setting zero to frequency
# and damping, and increase velocity and position iterations in world
# properties. For 100% zero deformation, use a single body with multiple
# fixtures
- type: weld
name: left_wheel_weld
# optional, defaults to 0, specifies the angle of the weld, applies only
# to revolute joints
angle: 0
# optional, defaults to 0, specifies the frequency of the weld joint in
# Box2D, unit is in Hz, applies only to weld joints
frequency: 0
# optional, defaults to 0, specifies the damping ratio of the weld joint
# in Box2D, applies only to weld joints
damping: 0
bodies:
- name: left_wheel
anchor: [0, 0]
- name: base_link
anchor: [-0.83, -0.29]
- type: weld
name: right_wheel_weld
bodies:
- name: left_wheel
anchor: [0, 0]
- name: base_link
anchor: [-0.83, -0.29]
# optional, list of plugins for the model
plugins:
# required, type of the plugin to load. Note the plugin must be configured
# property to be discovered. See the Writing Model Plugins page
- type: Laser
# optional, default true. If false (see yaml preprocessor for details), this plugin is skipped
enabled: true
# required, name of the plugin to load, must be unique in a model
name: kinect
# the rest of the parameters are extracted by the corresponding model plugins
body: base_link
range: 20
angle: {min: -2.356194490192345, max: 2.356194490192345, increment: 0.004363323129985824}
noise_std_dev: 0.01
update_rate: 10
- type: DiffDrive
name: turtlebot_drive
body: base_link

Yaml Preprocessor¶
Flatland Server has a lua preprocessor for YAML with simple bindings for the environment variables and rosparam. The intent is to be able to build parametric models that are defined by dimensions and flags found in either environment variables or rosparam, in a similar way to xacro+urdf. Because this is parsed at model load time, any roslaunch rosparam loading will have completed and those parameters will be available.
Including additional YAML files¶
The YAML preprocessor allows for including of other YAML files using the $include keyword. When this string is encountered, the following filename is parsed as a YAML file and substituted for the $include-string. The file path bay be absolute or relative. Relative file paths are relative to the YAML file currently being processed.
# project/param/parent.yaml
foo: 123
bar: $include child.yaml # Looks in current directory (project/param/) for relative filenames
baz: $include /absolute/path/to/project/param/child.yaml # or an absolute path can be specified
# project/param/child.yaml
a: 1
b: 2
# result of YAML preprocessing parent.yaml:
foo: 123
bar:
a: 1
b: 2
baz:
a: 1
b: 2
There is also a special form of $include, $[include], that can be used to populate a sequence with an arbitrary number of items. Each individual document in the specified YAML file (separated by — as is standard for multi-document YAML files) becomes its own element in the sequence. For example:
# parent.yaml
foo:
- first
- $[include] child.yaml
- last
#child.yaml
one
---
a: foo
b: baz
---
three
# result of YAML preprocessing of parent.yaml:
foo:
- first
- one
- a: foo
b: baz
- three
- last
body/joint/plugin enabled flag¶
Model bodies, plugins and joints now have a new flag enabled which can be set to true or false either directly in the yaml, or based on more complex logic from a lua $eval string that returns “true” or “false”. Disabled bodies, plugins and joints are skipped during yaml loading, and as a result are never instantiated. From Flatland’s perspective enabled: false causes the affected body/plugin/joint to be deleted.
bindings for env and param¶
Additional lua function bindings (beyond the normal standard libraries such as string, math, etc.):
-- returns an environment variable, blank string + warning if not found
env(EnvName)
-- returns an environment variable, Default if not found
env(EnvName, Default)
-- returns a rosparam, blank string + warning if not found
param(ParamPath)
-- returns a rosparam, Default if not found
param(ParamPath, Default)
Sample expressions¶
foo: $eval "Some arbitrary LUA expression"
bar: | # Multiline string
$eval -- $eval flag required to trigger LUA parsing
if env("FRONT_WHEEL",true) then
return 1.2
else
return 2.4
end
Lua expressions can explicitly return their value, but if no return is given, one will be prepended to the statement.
env + param examples¶
# in: (SOME_ENV not set)
foo: $eval env("SOME_ENV")
# out:
foo: ""
# in: (SOME_ENV not set)
foo: $eval env("SOME_ENV", false)
# out:
foo: false
# in: (export SOME_ENV=true)
foo: $eval env("SOME_ENV")
# out:
foo: true
# in: (rosparam /test/param not set)
foo: $eval param("/test/param", 0)/2.0
# out:
foo: 0
# in: (rosparam /test/param set to 5.0)
foo: $eval param("/test/param", 0)/2.0 + 1
# out:
foo: 2.5

Flatland ROS Services¶
Flatland offers means for manipulating the simulation through ROS services. The following are the services offered by the simulator.
Spawning Models¶
Models can be spawned dynamically after instantiation of the world. The parameters are same as the ones for models in YAML files, all input parameters are required.
Request:
string yaml_path # path to model yaml file
string name # name of the model
string ns # namespace, use "" for no namespace
geometry_msgs/Pose2D pose # model pose
Response:
bool success # to check if the operation is successful
string message # error message if unsuccessful
Deleting Models¶
Request:
string name # name of the model to delete
Response:
bool success # check if the operation is successful
string message # error message if unsuccessful
Moving Models¶
After spawning the model in the world, this service can be used to directly set the position and orientation of the vehicle in the global frame.
Request:
string name # name of the model to move
geometry_msgs/Pose2D pose # desired new global pose
Response:
bool success # check if the operation is successful
string message # error message if unsuccessful

Writing Model Plugins¶
Flatland is designed with extensibility in mind. Users can write their own Plugins to tailor the simulator for their specific needs. A Model Plugin is a plugin that is attached to a given model and perform specific functions for that model. You can check flatland_plugins for existing examples of plugins.
ModelPlugin Base Class Overview¶
The plugin system is implemented using ROS pluginlib. All model plugins must implement the base class ModelPlugin with the critical class members listed below. When the model plugin initializes, the YAML Node containing the parameters for the plugin is passed in. It is up to the plugin to extract data from the YAML Nodes and throw exceptions if any errors occur. Any exceptions derived from std::exception will be caught and handled gracefully. However, we recommend throwing exceptions from flatland_server/exceptions.h.
class ModelPlugin {
public:
// ROS node handle initialize with robot namespace, if namespace is "", it
// will work as if there are no namespace
ros::NodeHandle nh_;
const std::string &GetName() const;
const std::string &GetType() const;
Model *GetModel();
// This function must be overridden for initialization. The YAML Node is
// passed in for processing by the specific plugin
virtual void OnInitialize(const YAML::Node &config) = 0;
// These two functions are called before and after the physics step, the
// time data contained in timekeeper and ROS simulation time from
// ros::Time::Now() have been set correctly
virtual void BeforePhysicsStep(const Timekeeper &timekeeper) {} // time t
virtual void AfterPhysicsStep(const Timekeeper &timekeeper) {} // time t + dt
// helper function to filter contact and returns true if the model is involved
// in the contact, or false otherwise. If true, entity returns the pointer
// to the entity that collided with the model, this_fixture returns the
// fixture in the model, other_fixture returns the fixture in the entity
bool FilterContact(b2Contact *contact, Entity *&entity,
b2Fixture *&this_fixture, b2Fixture *&other_fixture);
// simplified version that just return true / false
bool FilterContact(b2Contact *contact);
// Box2D collision callbacks use the FilterContact method to check if the this
// plugin's model is involved in the collision, See Box2D documentation for
// complete information about these callbacks. These call backs are always
// called between the BeforePhysicsStep() and AfterPhysicsStep(). The simulation
// time is always equal to the time at BeforePhysicsStep().
// Called when two fixtures starts to contact
virtual void BeginContact(b2Contact *contact) {} // time t
// called when two fixtures stops contact
virtual void EndContact(b2Contact *contact) {} // time t
// called before solving collision, may be called multiple times in a time step
virtual void PreSolve(b2Contact *contact, const b2Manifold *oldManifold) {} // time t
// called after solving collision, may be called multiple times in a time step
virtual void PostSolve(b2Contact *contact, const b2ContactImpulse *impulse) {} // time t
}
Box2D contact object is generated when two Box2D fixtures collide, it contains all the information about the collision. Box2D fixtures are the underlying physics implementation of footprints in the simulation. From b2Contacts, you can obtain which two fixtures have collided. From b2Fixtures, we can get the b2Body that the fixture belongs to, which also has a one to one relationship to the Flatland’s Bodies. Each b2Body contain a pointer to a Flatland Body, and each Flatland Body has pointer to a entity that is either a layer or a model. Use the Type() method to determine if an entity is a model or layer. This is shown as below.
// Get the body
flatland_server::Body *b1 = (flatland_server::Body*) contact->GetFixtureA()->GetBody()->GetUserData();
flatland_server::Body *b2 = (flatland_server::Body*) contact->GetFixtureB()->GetBody()->GetUserData();
flatland_server::Entity *e = b1->GetEntity();
if (e->Type() == flatland_server::Entity::EntityType::LAYER) {
// entity is Layer
} else if (e->Type() == flatland_server::Entity::EntityType::MODEL) {
// entity is Model
}
Creating the Plugin¶
Say you would want to make a plugin to have a body in the model move at given constant x, y and yaw rates. This will reside in a package called my_plugins.
- Create a subclass of ModelPlugin. Note that the name space must be flatland_plugins. We must implement the OnInitialize() abstract method, and we need to override the BeforePhysicsStep() to apply the velocity. The velocities are stored in the vel_x, vel_y, and omega members. We also need to keep a pointer to the body we are going to apply the velocity to.
// include/my_plugins/const_velocity_plugin.h #include <Box2D/Box2D.h> #include <flatland_server/model_plugin.h> #include <flatland_server/timekeeper.h> #include <flatland_server/body.h> #include <yaml-cpp/yaml.h> #ifndef FLATLAND_PLUGINS_CONST_VELOCITY #define FLATLAND_PLUGINS_CONST_VELOCITY namespace flatland_plugins { class ConstVelocity : public flatland_server::ModelPlugin { public: double vel_x, vel_y, omega; flatland_server::Body *body; void OnInitialize(const YAML::Node &config) override; void BeforePhysicsStep(const flatland_server::Timekeeper &timekeeper) override; }; } #endifWe then write the implementation for the ConstVelocity class, the PLUGINLIB_EXPORT_CLASS macro is used to register the class within the plugin system. YamlReader class is used to help extracting data from the YAML Node.
// src/const_velocity_plugin.cpp #include <flatland_plugins/laser.h> #include <pluginlib/class_list_macros.h> #include <flatland_server/yaml_reader.h> #include <flatland_server/exceptions.h> namespace flatland_plugins { void ConstVelocity::OnInitialize(const YAML::Node &config) { flatland_server::YamlReader reader(config); vel_x = reader.Get<double>("vel_x"); vel_y = reader.Get<double>("vel_y"); omega = reader.Get<double>("omega"); body = GetModel()->GetBody(reader.Get<std::string>("body")); // check a valid body is given if (body == nullptr) { throw flatland_server::YAMLException("Body with with the given name does not exist"); } } void ConstVelocity::BeforePhysicsStep(const flatland_server::Timekeeper &timekeeper) { body->GetPhysicsBody()->SetLinearVelocity(b2Vec2(vel_x, vel_y)); body->GetPhysicsBody()->SetAngularVelocity(omega); } } PLUGINLIB_EXPORT_CLASS(flatland_plugins::ConstVelocity, flatland_server::ModelPlugin)
- Add pluginlib and flatland_server as dependencies in package.xml and CMakeLists.txt. We also need to add the source of the plugin to compile as a library in CMakeLists.txt.
package.xml:
<depend>flatland_server</depend> <depend>pluginlib</depend>CMakeLists.txt:
find_package(catkin REQUIRED COMPONENTS pluginlib flatland_server )include_directories(include) add_library(my_plugins_lib src/const_velocity_plugin.cpp)
At this point, the code should compile, but we can’t load the plugin dynamically yet because flatland_server would not know its existence. To do this we need to add a flatland_plugins.xml file to list the plugins defined in this package and then export it.
Create a file called flatland_plugins.xml. The <library> tag specifies the compiled library we want to export, note that prefix “lib” is always added to compiled library binaries. The <class> tag declares plugins we want to export. Add as many <class> tags as required for the plugins that needs to be exported. The description of parameter are as follows.
- type: The fully qualified type of the plugin, which is my_plugins::ConstVelocity we just created
- base_class: The fully qualified base class type for the plugin, which will always be flatland_server::ModelPlugin.
- description: A description of what the plugin does
flatland_plugins.xml:
<library path="lib/libmy_plugins_lib"> <class type="my_plugins::ConstVelocity" base_class_type="flatland_server::ModelPlugin"> <description>Constant velocity plugin</description> </class> </library>Finally, add the following to package.xml <export> tag to export the plugin. The name of the tag should always be flatland_server. And the name of the xml file should be the same as the one defined above.
package.xml:
<export> <flatland_server plugin="${prefix}/flatland_plugins.xml" /> </export>
- To verify that things are working correctly, build the workspace, source devel/setup.bash, and run the following command. You should see the the full path to the flatland_plugins.xml file. This means the exporting is configuring correctly.
$ rospack plugins --attrib=plugin flatland_server
Using a plugin
To use a model plugin, simply add a plugin entry under plugins as shown in the example model yaml file below. After adding the model to the world, the model should travel at the specified velocities.
bodies: - name: base footprints: - type: polygon points: [[.5, .5], [-.5, .5], [-.5, -.5], [.5, -.5]] density: 1 plugins: - type: ConstVelocity name: const_velocity_drive body: base vel_x: 1 vel_y: 0.2 omega: -0.5
- If there are issues, check that PLUGINLIB_EXPORT_CLASS is used to export the plugin class, check the spelling of classes, library files, plugin.xml XML tags, and file names to make everything is hooked up correctly.
Model Namespacing¶
Models have a optional namespace parameter. When it is not set, it defaults to “”, and it is equivalent to having no namespace. Namespace allows the simulation to load multiple of the same model, without worrying about the topic names and TF frames conflicting between these models. The node handle of model plugins are initialized with the model’s namespace, and the namespace will be automatically added to all topic names subscribed and advertised. This is shown below.
nh_ = ros::NodeHandle(model_->namespace_);
To avid conflicts in TF frame IDs, if the plugins choose to publish TF, use tf::resolve() function to prepend the namespace to frames on the model as shown below.
tf::resolve(GetModel()->NameSpaceTF(frame_id));
NameSpaceTF will not prepend to frame_id’s beginning with “/”. It will instead strip the leading “/”.
YAML Reader¶
Flatland server provides YAML Reader to simplify the process of extracting data from YAML files. It provides methods to extract scalars, lists, and array as well as providing error checking, checks for invalid/unused keys, and it throws exceptions with messages telling the user what and where the error is. Check YamlReader from API documentation, and examples throughout flatland_server and flatland_plugins for more details.
Simulation Time¶
Using the launch file provided, ROS will be configured to use simulation time. One can use ros::Time::now() to get the current time. Simulation time can be obtained from the timekeeper object, as well as other time related information such as step size.
Update Timer¶
It is often desireable to perform updates at a slower rate than what the simulation is running at. For example, the simulation might be executing in real time speed at 200Hz, and you wish to publish laser data at 10Hz. This can be done through the flatland_plugins/UpdateTimer class. The following code snippet shows how it can be used, and more information and examples can be obtained from API documentation as well as examples in flatland_plugins.
#include <flatland_plugins/update_timer.h>
UpdateTimer update_timer;
update_timer.SetRate(10); // set rate in Hz
void YourPlugin::BeforePhysicsStep(const Timekeeper &timekeeper) {
// check if an update is REQUIRED
if (!update_timer.CheckUpdate(timekeeper)) {
return;
}
// the code here will be run at 10Hz
}

Using a joystick¶
The purpose of the teleop_twist package is to provide a generic facility for tele-operating Twist-based ROS robots with a standard joystick. It is for use with a joystick such as the PS3 controller.

Download and install the joy software from the ROS wiki: joy.
Download and install the teleop_twist software from the ROS wiki: teleop_twist.
Run the software
roslaunch teleop_twist_joy teleop.launch
Note
It is best to launch from a dedicated terminal (ties up window).
Note
Ctrl-c to exit.

Bumper¶
The bumper plugins publishes the state of Collisions of bodies in the model. The Collision and Collisions message are defined in flatland_msgs. It publishes empty collisions if there are nothing colliding. Note that the force values published by the bumper is a ball park approximation of impact strength.
The definition of Collisions and Collision messages are shown below.
string entity_A # the name of this model
string body_A # this model's body
string entity_B # name of the other entity, model or layer, collided with this model
string body_B # body of the other entity
float64[] magnitude_forces # force of impact at each point
Vector2[] contact_positions # list of contact points
Vector2[] contact_normals # list of contact normals, normals always go from body_A to body_B
std_msgs/Header header
Collision[] collisions # list of Collision message
Vector2 is defined in flatland_msgs
float64 x
float64 y
The descriptions of parameters are shown below.
plugins:
# required, specify Bumper type to load the plugin
- type: Bumper
# required, name of the plugin, unique within the model
name: MyBumper
# optional, default to "map", the frame_id of the world coordinate system,
# Collision contain collision points that must have a reference frame
world_frame_id: world
# optional, default to "collisions", the topic name to publish collision
# messages, you begin with "/" to ignore model namespace
topic: collisions
# optional, default to inf (publishes every time step), the rate in Hz to
# publish the Collisions messages
update_rate: .inf
# optional, default to true, this works together with update_rate. Collision
# states may change in between updates with a given update_rate. It might
# appear and disappear between when the messages published. This option
# forces the bumper plugin to always publish if there are non-zero number
# collisions regardless of update_rate. If there are no collisions, it publishes
# empty list of collisions at update_rate
publish_all_collisions: true
# optional, default to [], the list of bodies to ignore, ignored bodies
# will not have their collision state published
exclude: []
# another example
- type: Bumper
name: MyOtherBumper
publish_all_collisions: false
update_rate: 60
exclude: ["left_wheel", "right_wheel"]

Bool Sensor¶
The boolean sensor plugin attaches to a single body of a model and publishes true std_msgs/Bool if something collides with it, and false otherwise.
This can be used on solid bodies (default), or sensor bodies (sensor: true).
The plugin also respects layers. For example a sensor body that exists only on layer “robot” will only emit true if an entity on layer :robot” collides with it.
The sensor plugin “latches” collisions, so if there is a collision since the previous publishing, it will always publish at least one true.
plugins:
# required, specify BoolSensor type to load the plugin
- type: BoolSensor
# required, name of the plugin, unique within the model
name: MyBoolSensor
# The ROS topic name to publish on ("/detector_out")
# This will respect model namespaces
# e.g. if this model has namespace "foo", it will publish on "/foo/detector_out"
topic: detector_out
# The update rate in hz
update_rate: 10
# The model body to detect collisions on
# Currently only supports collisions on a single body
body: detector

Diff Drive¶
This plugin provides common features for a differential drive robots. All velocities and odometries are w.r.t. the robot origin
- Subscribes to a topic publishing geometry_msgs/Twist messages, and move the robot at the desired forward and rotation velocities
- Publishes to two topics with nav_msgs/Odometry messages, one for robot odometry which has noise, the other the ground truth odometry
plugins:
# required, specify DiffDrive type to load the plugin
- type: DiffDrive
# required, name of the plugin
name: turtlebot_drive
# required, body of a model to set velocities and obtain odometry
body: base
# optional, defaults to odom, the name of the odom frame
odom_frame_id: odom
# optional, defaults to inf, rate to publish odometry at, in Hz
pub_rate: .inf
# optional, defaults to "cmd_vel", the topic to subscribe for velocity
# commands
twist_sub: cmd_vel
# optional, defaults to "odometry/filtered", the topic to advertise for
# publish noisy odometry
odom_pub: odometry/filtered
# optional, defaults to "odometry/ground_truth", the topic to advertise for publish
# no noise ground truth odometry
ground_truth_pub: odometry/ground_truth
# optional, defaults to "twist", the topic to publish noisy local frame velocity
# that simulates encoder readings
twist_pub: twist
# optional, defaults to true, enables the advertising and publishing of both
# ground truth and noisy odometry
enable_odom_pub: true
# optional, defaults to true, enables the advertising and publishing of noisy local
# frame velocity
enable_twist_pub: true
# optional, defaults to [0, 0, 0], corresponds to noise on [x, y, yaw],
# the variances of gaussian noise to apply to the pose components of the
# odometry message
odom_pose_noise: [0, 0, 0]
# optional, defaults to [0, 0, 0], corresponds to noise on
# [x velocity, y velocity, yaw rate], the variances of gaussian noise to
# apply to the twist components of the odometry message
odom_twist_noise: [0, 0, 0]
# optional, defaults to the diagonal [x, y, yaw] components replaced by
# odom_pose_noise with all other values equals zero, must have length of 36,
# represents a 6x6 covariance matrix for x, y, z, roll, pitch, yaw.
# This does not involve in any of the noise calculation, it is simply
# the output values of odometry pose covariance
odom_pose_covariance: [0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0]
# optional, defaults to the diagonal [x velocity, y velocity, yaw rate]
# components replaced by odom_twist_noise with all other values equals zero,
# must have length of 36, represents a 6x6 covariance matrix for rates x,
# y, z, roll, pitch, yaw. This does not involve in any of the noise
# calculation, it is simply the output values of odometry twist covariance
odom_twist_covariance: [0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0]
# optional, defaults each parameter to 0.0 which means "no limit"
# sets dynamics constraints on angular velocity, acceleration (in rads/sec; rads/sec/sec)
angular_dynamics:
acceleration_limit: 0.0 # max acceleration (away from 0), in rads/s/s; 0.0 means "no limit"
deceleration_limit: 0.0 # max deceleration (towards 0), in rads/s/s; 0.0 means "no limit"; left blank, will default to acceleration_limit value
velocity_limit: 0.0 # max absolute velocity in rads/s; 0.0 means "no limit"
# optional, defaults each parameter to 0.0 which means "no limit"
# sets dynamics constraints on linear velocity, acceleration (in m/s; m/s/s)
linear_dynamics:
acceleration_limit: 0.0 # max acceleration (away from 0), in m/s/s; 0.0 means "no limit"
deceleration_limit: 0.0 # max deceleration (towards 0), in m/s/s; 0.0 means "no limit"; left blank, will default to acceleration_limit value
velocity_limit: 0.0 # max absolute velocity in m/s; 0.0 means "no limit"
ground_truth_frame_id: map # The name of the ground truth origin TF frame

Tricycle Drive¶
This plugin provides features for a specific implementation of tricycle robots.
- Subscribes to a topic publishing geometry_msgs/Twist messages. Note the yaw rate is the angle of the front wheel instead of actual yaw rate.
- Publishes to two topics of nav_msgs/Odometry messages, one for robot odometry which has noise, the other the ground truth odometry
The plugins makes several assumptions about the robot drive train, and uses these assumptions to extract required geometry parameters such as wheel base and axle track from the robot.
- Twist yaw rate is the angle of the front wheel
- Twist x velocity is the velocity at the front wheel
- The origin of the body is at the front wheel
- The model has front wheel with a revolute joint to the body, the anchor point on the wheel is at the origin, the anchor point on the body is at the origin
- The model has a rear left wheel with a weld joint to the body, the anchor point on the wheel is at the origin
- The model has rear right wheel with a weld joint to the body, the anchor point on the wheel is at the origin
- The perpendicular line from front wheel to rear axle (line segment from the rear left wheel to the rear right wheel) bisects the rear axle
- The x velocity and angle given are physically feasible, no additional checks are applied, and the tricycle model is used directly
- Kinematic limits can be specified for the steering angle, steering angular velocity, and steering angular acceleration, to model the tricycle model’s front wheel steering response to commanded steering angle changes. This does not fully account for lag in the steering response, but provides a slightly more realistic acceleration- and velocity-bounded steering response. A future update will introduce the steering lag model to the tricycle plugin.
The plugin also sets the angle of the front wheel for visualization purposes, it has no effect on the actual motion of the robot.
plugins:
# required, specify TricycleDrive type to load the plugin
- type: TricycleDrive
# required, name of the plugin
name: robot_drive
# required, body of a model to set velocities and obtain odometry
body: base
# required, the front wheel joint
front_wheel_joint: front_wheel_revolute
# required, the rear left wheel joint
rear_left_wheel_joint: rear_left_wheel_weld
# required, the rear right wheel joint
rear_right_wheel_joint: rear_right_wheel_weld
# optional, defaults to odom, the name of the odom frame
odom_frame_id: odom
# optional, defaults to inf, rate to publish odometry at, in Hz
pub_rate: inf
# optional, defaults to "cmd_vel", the topic to subscribe for velocity
# commands
twist_sub: cmd_vel
# optional, defaults to "odometry/filtered", the topic to advertise for
# publish noisy odometry
odom_pub: odometry/filtered
# optional, defaults to "cmd_vel", the topic to advertise for publish
# no noise ground truth odometry
ground_truth_pub: odometry/ground_truth
# optional, defaults to [0, 0, 0], corresponds to noise on [x, y, yaw],
# the variances of gaussian noise to apply to the pose components of the
# odometry message
odom_pose_noise: [0, 0, 0]
# optional, defaults to [0, 0, 0], corresponds to noise on
# [x velocity, y velocity, yaw rate], the variances of gaussian noise to
# apply to the twist components of the odometry message
odom_twist_noise: [0, 0, 0]
# optional, defaults to the diagonal [x, y, yaw] components replaced by
# odom_pose_noise with all other values equals zero, must have length of 36,
# represents a 6x6 covariance matrix for x, y, z, roll, pitch, yaw.
# This does not involve in any of the noise calculation, it is simply
# the output values of odometry pose covariance
odom_pose_covariance: [0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0
0, 0, 0, 0, 0, 0]
# optional, defaults to the diagonal [x velocity, y velocity, yaw rate]
# components replaced by odom_twist_noise with all other values equals zero,
# must have length of 36, represents a 6x6 covariance matrix for rates x,
# y, z, roll, pitch, yaw. This does not involve in any of the noise
# calculation, it is simply the output values of odometry twist covariance
odom_twist_covariance: [0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0]
# optional, defaults to 0.0 which means no limit
# sets the steering angular limit of the front wheel (absolute, rad)
# the steering angle will not exceed this absolute limit
max_steer_angle: 0.0
# optional, defaults each parameter to 0.0 which means "no limit"
# sets dynamics constraints on angular velocity, acceleration (in rads/sec; rads/sec/sec)
angular_dynamics:
acceleration_limit: 0.0 # max acceleration (away from 0), in rads/s/s; 0.0 means "no limit"
deceleration_limit: 0.0 # max deceleration (towards 0), in rads/s/s; 0.0 means "no limit"; left blank, will default to acceleration_limit value
velocity_limit: 0.0 # max absolute velocity in rads/s; 0.0 means "no limit"
# optional, defaults each parameter to 0.0 which means "no limit"
# sets dynamics constraints on linear velocity, acceleration (in m/s; m/s/s)
linear_dynamics:
acceleration_limit: 0.0 # max acceleration (away from 0), in m/s/s; 0.0 means "no limit"
deceleration_limit: 0.0 # max deceleration (towards 0), in m/s/s; 0.0 means "no limit"; left blank, will default to acceleration_limit value
velocity_limit: 0.0 # max absolute velocity in m/s; 0.0 means "no limit"
# DEPRECATED; Use angular_dynamics.velocity_limit instead
# optional, defaults to 0.0 which means no limit
# sets the steering angular velocity limit (absolute, rad/s)
# the steering angular velocity will not exceed this absolute limit
max_angular_velocity: 0.0
# DEPRECATED; Use angular_dynamics.acceleration_limit instead
# optional, defaults to 0.0 which means no limit
# sets the steering angular acceleration limit (absolute, rad/s^2)
# the steering angular acceleration will not exceed this absolute limit
max_steer_acceleration: 0.0
ground_truth_frame_id: map # The name of the ground truth origin TF frame

Laser¶
The laser plugin pushes 2D laser data. It attached to a body of the model with at a specified position and orientation. It can also publish the static TF between the body and the laser if asked to. It publishes sensor_msgs/LaserScan messages.
plugins:
# required, specify Laser to load this plugin
- type: Laser
# required, name of the laser plugin, must be unique
name: laser_back
# optional, default to "scan", topic to publish the laser data
topic: scan
# required, name of the body to attach the laser to
body: base_link
# optional, default to [0, 0, 0], in the form of [x, y, yaw], the position
# and orientation to place laser's coordinate system
origin: [0, 0, 0]
# optional, default to true, whether to publish TF
broadcast_tf: true
# optional, default to name of this plugin, the TF frame id to publish TF with
# only used when broadcast_tf=true
frame: laser_back
# required, maximum range of the laser, minimum range assumed to be zero, in meters
range: 20
# optional, default to 0.0, standard deviation of a gaussian noise
noise_std_dev: 0
# required, w.r.t to the coordinate system, scan from min angle to max angle
# at steps of specified increments
# Scan direction defaults to counter-clockwise but clockwise rotations can be
# simulated by providing a decrementing angle configuration.
# e.g. min: 2, max: -2, increment: -0.1 (clockwise)
angle: {min: -2.356194490192345, max: 2.356194490192345, increment: 0.004363323129985824}
# optional, default to inf (as fast as possible), rate to publish laser scan messages
update_rate: .inf
# optional, default to ["all"], the layers to operate the laser at,
# lasers only detects objects in the specified layers
layers: ["all"]
# optional, invert the mounting orientation of the lidar (default: false)
# This will invert the laser's body->laser frame TF (roll=PI)
# And sweep the lidar scan across a field mirrored across its mounted axis
# (as if you physically mounted the lidar upside down)
upside_down: false
# another example
- type: Laser
name: laser_front
body: base_link
range: 30
angle: {min: -1.5707963267948966, max: 1.5707963267948966, increment: 1.5707963267948966}
layers: ["layer_1", "layer_2", "layer_3"]
update_rate: 100
noise_std_dev: 0.01

Model TF Publisher¶
Model TF publisher broadcasts TF of bodies in the model. It obtains world position and orientation of bodies from the simulation, calculates relative transformation w.r.t. the specifies reference body, and broadcast the TF.
plugins:
# required, specify model tf publisher plugin to load this plugin
- type: ModelTfPublisher
# required, name of the model tf publisher plugin, must be unique
name: state_publisher
# optional, defaults to inf (broadcast every iteration)
update_rate: .inf
# optional, defaults to false, whether to broadcast TF w.r.t. to a frame frame
publish_tf_world: false
# optional, defaults to map, the world frame ID, only used when
# publish_tf_world is set to true
world_frame_id: map
# optional, defaults to the first body in the model, the reference body to
# broadcast all other bodies' TF with respect to. Does not affect actual
# transformation, only affects how the TF tree looks
reference: base_link
# optional, defaults to [], bodies to not broadcast TF for
exclude: []
# another example
- type: ModelTfPublisher
name: state_publisher_2
# another example
- type: ModelTfPublisher
name: state_publisher_3
exclude: ["castor_wheel"]

Tween¶
The tween plugin moves a body from it’s start location to a relative end position.
This can be done using a variety of tween modes and easings.
Modes¶
yoyo
- move back and forth between the start and end position repeatedlyonce
- move to the end position and stoploop
- move to the end position then teleport back, then repeat indefinitelytrigger
- move towards the end position if the “trigger_topic” ros topic recievestrue
, move towards start otherwise.
Easings¶
The default easing is “linear”, but the following is a complete list of supported easing modes:
linear
quadraticIn
,quadraticOut
,quadraticInOut
cubicIn
,cubicOut
,cubicInOut
quarticIn
,quarticOut
,quarticInOut
quinticIn
,quinticOut
,quinticInOut
exponentialIn
,exponentialOut
,exponentialInOut
circularIn
,circularOut
,circularInOut
backIn
,backOut
,backInOut
elasticIn
,elasticOut
,elasticInOut
bounceIn
,bounceOut
,bounceInOut
You can see visual examples of these easing modes here at easings.net.
Configuration¶
plugins:
# required, specify Tween type to load the plugin
- type: Tween
# required, name of the plugin, unique within the model
name: MyTweenPlugin
# The tween mode (documented above, default 'yoyo')
mode: yoyo
# The easing mode (documented above, default 'linear')
easing: cubicInOut
# The ROS topic name to subscribe to for 'trigger' mode ("/tween_trigger")
# This will respect model namespaces
# e.g. if this model has namespace "foo", it will publish on "/foo/tween_trigger"
trigger_topic: tween_trigger
# animation duration in seconds (default 1 second)
duration: 10
# The tween delta pose (delta x, y and angle)
# The following will move the object to x += 2, y += 3, and angle += 1.1
# relative to the start position
delta: [2, 3, 1.1]
# The model body to move
body: some_body

GPS¶
This plugin provides a simple simulation of a perfectly-accurate GPS receiver.
- Reference latitude and longitude are set in the plugin’s YAML parameters. The reference coordinates correspond to (0, 0) in the Flatland world frame.
- The model’s ground truth position in the Flatland world frame is treated as the position in an East-North-Up (ENU) reference frame relative to (0, 0).
- The ENU coordinates are converted to latitude and longitude using the specified reference coordinates and plugging everything into standard equations as defined on Wikipedia
- Publishes a sensor_msgs/NavSatFix message with the current geodetic position of the vehicle.
plugins:
# required, specify Gps type to load the plugin
- type: Gps
# required, name of the plugin
name: turtlebot_gps
# required, body of a model to set location of simulated GPS antenna
body: base
# optional, defaults to "gps/fix", the topic to advertise for GPS fix outputs
topic: gps/fix
# optional, defaults to 10, rate to publish GPS fix, in Hz
update_rate: 10
# optional, defaults to true, whether to publish TF
broadcast_tf: true
# optional, default to name of this plugin, the TF frame id to publish TF with
# only used when broadcast_tf=true
frame: my_frame_name
# optional, defaults to 0.0, latitude in degrees corresponding
# to (0, 0) in world frame
ref_lat: 0.0
# optional, defaults to 0.0, longitude in degrees corresponding
# to (0, 0) in world frame
ref_lon: 0.0
# optional, default to [0, 0, 0], in the form of [x, y, yaw], the position
# and orientation to place GPS antenna relative to specified model body
origin: [0, 0, 0]