mrsim-gazebo
mrsim-gazebo
is a gazebo plugin for multi-rotor
simulation.
It emulates the tk3-mikrokopter software running on Mikrokopter hardware via a pty implementing the tk3-mikrokopter communication protocol and all the tk3-mikrokopter features so that the hardware can be fully emulated.
The rotor dynamics are simulated using a realistic motor model and a simple thrust/drag propeller model. The same hardware velocity controller as implemented in the tk3-mikrokopter software controls the propellers velocities. Then, at the user’s choice, either the geometry of a model can be used to compute the total wrench applied to the rigid body, or an explicit allocation matrix can be specified.
Installation
After configuring, compiling and installing the software in the $PREFIX
folder, the plugin can be found in $PREFIX/lib/gazebo/mrsim-gazebo.so
. To
load it from gazebo, an option is to configure the environment variable
GAZEBO_PLUGIN_PATH
so that it contains this directory. For instance:
% export GAZEBO_PLUGIN_PATH=$PREFIX/lib/gazebo:${GAZEBO_PLUGIN_PATH}
A few sample world and models are installed in $PREFIX/share/gazebo/
.
You can configure GAZEBO_MODEL_PATH
for convenience:
% export GAZEBO_MODEL_PATH=$PREFIX/share/gazebo/models:${GAZEBO_MODEL_PATH}
mrsim-gazebo
is a Model plugin. Check the mrsim-quadrotor model provided in
the above directory for an example usage.
Configuration
Base link
A base link name is mandatory. This represents the link where the emulated IMU is attached. It usually corresponds to the main link of your model.
<plugin name="mrsim" filename="mrsim-gazebo.so">
<link>base</link>
</plugin>
Rotors
The optional rotors
element describes a list of rotors controlled by the
plugin.
<plugin name="mrsim" filename="mrsim-gazebo.so">
<link>base</link>
<rotors>
<rotor><joint spin="cw">rotor-1</joint></rotor>
<rotor><joint spin="ccw">rotor-2</joint></rotor>
<rotor><joint spin="cw">rotor-3</joint></rotor>
<rotor><joint spin="ccw">rotor-4</joint></rotor>
</rotors>
</plugin>
Each rotor
sub-element must contain the name of a hinge joint representing a
motor axle. The Z axis of the named joint must correspond to the direction of a
positive thrust and the spin
attribute (cw
or ccw
) indicates the
propeller direction of rotation.
Motors parameters
The rotors section can define motors parameters:
<plugin name="mrsim" filename="mrsim-gazebo.so">
<link>base</link>
<rotors>
<cf>6.5e-4</cf> <!-- Rotor thrust coefficient (N/Hz²) -->
<ct>1e-5</ct> <!-- Rotor quadratic torque coefficient (N.m/Hz²) -->
<vfxy>1.5</vfxy><!-- Vibration force radial amplitude, (%cf) -->
<vfz>4</vfz> <!-- Vibration force axial amplitude, (%cf) -->
<vtxy>2</vtxy> <!-- Vibration torque radial amplitude, (%ct) -->
<vtz>2</vtz> <!-- Vibration torque axial amplitude, (%ct) -->
<b>0</b> <!-- Rotor linear torque coefficient (N.m.s) -->
<J>8e-5</J> <!-- Rotor inertia (kg.m²) along Z -->
<K>0.0126</K> <!-- Torque constant (N.m/A) -->
<R>0.15</R> <!-- Electric resistance (Ohm) -->
<L>2e-4</L> <!-- Electric inductance (H) -->
<V>16</V> <!-- Battery voltage (V) -->
<I>40</I> <!-- Maximum current (A) -->
<rotor> ... </rotor>
<rotor> ... </rotor>
</rotors>
</plugin>
The cf
and ct
elements specify the coefficients that map the square of
the rotational speed in rev/s (Hz) to force (cf
) and torque (ct
) in Newtons
(N).
The vfxy
, vfz
, vtxy
and vtz
specify the amplitude of the structure
vibrations induced by the propellers, relative to the cf
and ct
parameters. A value of 1
means that the force (resp. torque) produced by the
vibrations is equal to the thurst (resp. torque) produced by the propellers.
The heuristic model is a radial sinusoid with the same period as the propeller
and an axial one with doubled period, applied on each rotor joint. This
reproduces the observed behaviour on a real robot.
Artificial noise
Random Gaussian noise can be added to the rotors direction with the <noise>
tag. It’s value is the desired noise standard deviation, in radians:
<plugin name="mrsim" filename="mrsim-gazebo.so">
<rotors>
<noise>0.03</noise>
<rotor> ... </rotor>
<rotor> ... </rotor>
</rotors>
</plugin>
Explicit allocation matrix
Instead of using the model’s geometry to compute the total wrench generated by all rotors, an explicit allocation matrix can be supplied:
<plugin name="mrsim" filename="mrsim-gazebo.so">
<link>base</link>
<allocation> <!-- sample quadrotor allocation matrix -->
0. 0. 0. 0.
0. 0. 0. 0.
6.5e-4 6.5e-4 6.5e-4 6.5e-4
0. 0.00015 0. -0.00015
-0.00015 0. 0.00015 0.
0.00001 -0.00001 0.00001 -0.00001
</allocation>
</plugin>
It describes a matrix G
that, when multiplied by the vector of squared
rotational speeds in rev/s (Hz) of all propellers, provides the total wrench
vector (x, y, z
force and x, y, z
torque) applied to the base link in it’s
local frame of reference. The size of the G
matrix is thus 6 rows and as many
columns as the number of rotors. It is entered as a flat list, in row-major
mode.
When this option is chosen, the rotors tag is just used for visual effect and
rotors generate no force. It is thus possible to not specify any rotors
tag
if the visual effect is deemed useless.
Motors simulation period
The update rate of the dynamics of the motors is controlled by the period
element. By default, it is 0.001s
, or 1kHz
and this is the recommended
value. Note that this settings is not related to and independant of the physics
simulation engine of gazebo.
<plugin name="mrsim" filename="mrsim-gazebo.so">
<link>base</link>
<period>0.001</period>
</plugin>