GSoC’25 Gazebo Plugin Model of a Motor

1. Introduction
Hi ArduPilot community :waving_hand:.
My name is Bhajneet Singh Bedi, a robotics software engineer from India. I am thrilled to announce that this year my proposal “Gazebo Plug-in Model of a Motor” has been accepted for GSOC 2025.
First of all I would like to thank my mentors @NDev @rhys for giving me the opportunity to contribute this year. I am feeling very excited to go through this journey of developing something which would help the community, which I always wanted to do.

2. The Project
The main objective of this project is to make a plugin based electro-mechanical model of a motor in gazebo. The idea is to create a model such that it mimics a real life motor. The plugin would help identify the stats of the motor at runtime. This also provides a standardised way to test motor behaviour under various conditions before real-world deployment of the project.

3. Why is this important?

  • It bridges the gap between hardware testing and simulation.
  • Makes motor outputs more realistic under varying load.
  • Will allow researchers and developers to simulate motor performance under different conditions.

4. Overview
In the current implementation, PWM signals are mapped directly to joint control commands using one of three modes: velocity, position, or effort. A PID controller is applied to reduce the error between the commanded and actual values, and the resulting force is applied to the joint.

While this approach is straightforward and works well for high-level control and simple simulations, it abstracts away the physical characteristics of real motors — such as torque generation based on current, voltage dynamics, and rotor inertia. As a result, this model does not capture the subtleties of how motors respond to load changes, battery sag, or transient behaviours, which are critical in dynamic flight scenarios.

To address these limitations, the project proposes a physics-based motor model plugin that simulates motor response by incorporating electrical and mechanical dynamics directly in the simulation loop.

The electro-mechanical model is described as below:


Fig: Circuit of an Electric Motor


Fig: Nomenclature

The motor model I implemented is based on the theory described in “Motor and Propeller Models for Flight Dynamics Simulations” by Mark Drela (MIT). This model captures the electrical and mechanical behavior of brushless DC motors in a physically realistic way — making it ideal for improving the fidelity of drone simulations in Gazebo.

:high_voltage: 4.1 Electrical Model

The motor is treated as an electrical system, where the input is voltage VVV (derived from PWM and battery) and the output is torque.

The relationship is:
image

Where:

  • I = motor current [A]
  • V = applied voltage [V]
  • Ω = angular velocity [rad/s]
  • Kv = motor velocity constant [rpm/v]
  • R = internal resistance of the motor [Ω]

This reflects back-EMF: at higher speeds, the motor resists current flow due to the voltage generated by rotation.

:cyclone: 4.2. Torque Generation

The torque generated is proportional to the current:
torque_eqn

The torque constant can be simply assumed to be the same as KV .

image

So the torque depends on:

  • Motor Kv rating
  • Current flowing through the motor

This torque is then applied to the propeller via the joint.

5. Implementation outline

  • ArduPilot SITL transmits FDM (Flight Dynamics Model) data over the local network(127.0.0.1) on port 9002.
  • The FDM also consists of pwm signals (16 or 32 channel) based on the configuration.
  • If the control type is set to “COMMAND” and a topic is provided in cmd_topic then the ArduPilotPlugin publishes the pwm values on the given topic.

This is what the MotorPlugin will subscribe to and calculate the output force which will be then be given in respective joints in gazebo using JointForceCmd

6. Call for Collaborations

As this project evolves, I’d love the involvement of the ArduPilot community in shaping and testing the motor model. Your feedback, ideas, and even small contributions can make a big difference in refining its accuracy and usability.

If you’re interested in:

  • Testing the plugin with your own motor/propeller configurations.
  • Comparing simulated vs real flight data.
  • Suggesting improvements to the model.
  • Helping integrate the plugin more tightly with ArduPilot SITL.

— I’d be happy to collaborate!

More Updates will be coming - Don’t miss out

GitHub links:

GitHub - Bhajneet-Singh-Bedi/ardupilot_gazebo at template_plugin

8 Likes

Mid term Update

Here’s a quick mid-term update on the motor plugin I’ve been working on.
So far, I’ve implemented a basic electromechanical motor model that receives a desired angular velocity from the ArduPilotPlugin. The model calculates the target force by comparing the desired and current rotor velocities using a PID controller. It then estimates the motor current using a simplified BLDC motor equation, and from this, computes the resulting torque. This motor model has been tested on the Iris quadcopter model.
This torque is applied to the rotor in Gazebo, allowing the physics engine to simulate the motor’s acceleration and spin-up behavior more realistically. The result is a more accurate motor response in simulation, which is especially valuable for testing flight dynamics and control algorithms.

1. Challenges Faced:

Initially the challenge was to understand the current tech stack and how it has been integrated between ArduPilot and Gazebo. So the current ArduPilot plugin supports a great amount of features. The task was to first understand the communication between ArduPilot and Gazebo. ArduPilot sends JSON data over the network which is then received and decoded by the existing ArduPilot Plugin and uses that data to command joints in Gazebo. It also broadcasts the mapped velocity data over a Gazebo topic for other plugins to use. This came into a lot of help. The newly added Motor Plugin subscribes to the topic and uses that data.
Then comes the problem of using the simple first order equations of the motor model to control the joint. In the real world the motor applies resistive force due to internal resistance of course and environmental factors. But in Gazebo these conditions need to be simulated.
Because of that the motor model would result in extremely high values of current (in the hundreds of amps) which isn’t correct.

This is where advice from @rhys helped, which was to decrease the damping in the model. In Gazebo is used to simulate the real world damping which could be produced by numerous factors. Because of high damping the joint was not able to rotate at it’s fullest and hence the output current was as high as hundreds of amps.

2. Current Implementation

The below block diagram explains the data flow of motor model.

The process flow goes like this. When the type is set to COMMAND in SDF file (COMMAND) for ArduPilotPlugin in the control channel then the commanded signal is mapped to velocity. This is then published on a topic either specified by the user is <cmd_topic>topic_name</cmd_topic> or a default topic. That topic is then subscribed by MotorPlugin which calculates torque required for the joint using the model equations and also publishes the calculated current on a topic for future use.

The parameters required from the user are listed below:-

1. maxVolts:- This represents the voltage of the battery. It’s currently being set to a constant value but will be updated in the future to support reading battery state.
2. velocityConstant:- This is the Kv rating of the motor.
3. coilResistance:- This represents the internal resistance of the motor.
4. noLoadCurrent:- This represents the current consumed by the motor when no load is applied.

3. Results

The above image is the output of the current being published on a gz topic.
The above images show the stall current of the motor which the motor can withstand. This model only contains the characteristics of a motor now and does not account for propeller dynamics. The rapid, fine ripples come from the ESC firing thousands of pulses per second to spin the motor typical of how brushless motors work. On top of that, the slower waves reflect the flight controller’s constant tweaks to keep the drone stable. Together, they show the motor balancing raw power and precise control in real-time.

** 4. Public Repositories:**

This link below is the PR submitted to ArduPilot_Gazebo repository.

This is the development repository. For trying out the plugin:-

  1. Clone this branch.
  2. Make a build folder and build it.
  3. Run the Iris_runway.sdf file.
  4. Run ArduPilot with SITL.

The Iris_runway already consists of motor plugin. A python script has been provided in the scripts/ folder which converts gz topic to ros2 topic which can then be visualized on plotjuggler.

2 Likes