Home

Awesome

Gazebo-ROS battery plugin

This repository contains a generic battery plugin for Gazebo to be used in ROS robot simulations. It implements two operation modes, a simple linear charge/discharge model and a parametric nonlinear dynamic discharge model. For the parameter tuning of the latter we provide a visualization tool of the discharge curves under various temperatures and current loads.

Battery models

Discharge characteristics of chemical batteries is represented by the graph below. The first section - exponential area - shows the exponential voltage drop starting from a fully charged state. ( The width of this section depends on the battery type. ) The second section - nominal area - represents the charge that can be extracted from the battery until the voltage drops below the battery nominal voltage. The last section shows the total discharge of the battery, when the voltage drops rapidly.

Simple linear model

In this mode of operation the charge drops in a linear fashion respect to the current drawn from the virtual battery without taking temperature into consideration.

Where

Generic dynamic model

Nonlinear dynamic discharge model is formulated as

where

with the impact of temperature on the model parameters

where

How to use the plugin

For convenience we have provided a xacro to include the nonlinear model that reads the parameters from a yaml file. If you would like to use the linear model, include it as you would with any other gazebo plugin.

  <xacro:include filename="$(find gazebo_ros_battery)/xacro/battery.xacro"/>
  <xacro:battery sensor_name="battery" frame_id="battery_link" 
                 params_yaml="$(find gazebo_ros_battery)/params/G24B4.yaml"/>

When loaded it will publish noetic Battery State messages on every state update. To attach consumers to the virtual battery, just provide the number of channels ( any dynamic and static consumers ) and the plugin is going to create numbered std_msgs::Float32 topic subscribers under the prefix of consumer_topic.

When the virtual battery is fully discharged, or the simulated electronic protection cuts off the voltage, you can call either the Reset service or the setCharge service to restore its charge state.

Ambient temperature can be set through the setTemperature service, internal temperature of the battery is then calculated to change in accordance with the temperature_response_tau parameter.

Parameters

Mode of operation is chosen through the use_nonlinear_model parameter. ( Defaults to True )

Common parameters

Linear model parameters

Nonlinear model parameters

Model tuning

Usually some parameters and a discharge curve is provided by battery manufacturers. In order to properly simulate the discharge of an unknown battery it is best to plot the voltage drop against a fixed current at a given temperature. Either way there has to be a plot that can be compared against the expected runoff of the model.

  1. Acquire the discharge curve of the given battery.
  2. Create a parameter file ( duplicate the one provided ).
  3. Use the battery_config.py tool in the params folder to visualize the models curve.
  4. Adjust the parameters in the yaml file until the fit is acceptable.
  5. Load the same parameter file with the xacro to run your battery simulation.

Model configuration script

~/gazebo_ros_battery/params$ ./battery_config.py G24B4.yaml

Authors: Marton Juhasz - nilseuropa, Gergely Gyebroszki - gyebro

Sources: https://www.mathworks.com/help/physmod/sps/powersys/ref/battery.html