├── srv ├── Reset.srv ├── SetCharge.srv └── SetTemperature.srv ├── doc ├── config_tool.png ├── temp_effect.png ├── generic_model.png ├── linear_model.png ├── characteristics.png └── linear_discharge.png ├── launch ├── rqt.launch └── simulation.launch ├── params ├── G24B4.yaml └── battery_config.py ├── package.xml ├── urdf └── test.xacro ├── CMakeLists.txt ├── include └── gazebo_ros_battery │ └── gazebo_ros_battery.h ├── xacro └── battery.xacro ├── README.md ├── src └── gazebo_ros_battery.cpp └── config └── dashboard.perspective /srv/Reset.srv: -------------------------------------------------------------------------------- 1 | std_msgs/Bool reset 2 | --- 3 | std_msgs/Bool state 4 | -------------------------------------------------------------------------------- /srv/SetCharge.srv: -------------------------------------------------------------------------------- 1 | std_msgs/Float32 charge 2 | --- 3 | std_msgs/Bool set 4 | -------------------------------------------------------------------------------- /srv/SetTemperature.srv: -------------------------------------------------------------------------------- 1 | std_msgs/Float32 temperature 2 | --- 3 | std_msgs/Float32 temperature 4 | -------------------------------------------------------------------------------- /doc/config_tool.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/nilseuropa/gazebo_ros_battery/HEAD/doc/config_tool.png -------------------------------------------------------------------------------- /doc/temp_effect.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/nilseuropa/gazebo_ros_battery/HEAD/doc/temp_effect.png -------------------------------------------------------------------------------- /doc/generic_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/nilseuropa/gazebo_ros_battery/HEAD/doc/generic_model.png -------------------------------------------------------------------------------- /doc/linear_model.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/nilseuropa/gazebo_ros_battery/HEAD/doc/linear_model.png -------------------------------------------------------------------------------- /doc/characteristics.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/nilseuropa/gazebo_ros_battery/HEAD/doc/characteristics.png -------------------------------------------------------------------------------- /doc/linear_discharge.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/nilseuropa/gazebo_ros_battery/HEAD/doc/linear_discharge.png -------------------------------------------------------------------------------- /launch/rqt.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /params/G24B4.yaml: -------------------------------------------------------------------------------- 1 | num_of_consumers: 2 2 | publish_voltage: True 3 | technology: 2 4 | design_capacity: 4.0 5 | number_of_cells: 6 6 | nominal_voltage: 24 7 | full_charge_voltage: 25.2 8 | cut_off_voltage: 18.0 9 | internal_resistance: 0.11 10 | current_filter_tau: 1 11 | polarization_constant: 0.07 12 | exponential_voltage: 0.7 13 | exponential_capacity: 3.0 14 | characteristic_time: 420 15 | reversible_voltage_temp: 0.05 16 | arrhenius_rate_polarization: 850 17 | capacity_temp_coeff: 0.01 18 | design_temperature: 25 19 | temperature_response_tau: 0.5 20 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | gazebo_ros_battery 4 | 1.0.0 5 | General nonlinear battery simulation plugin 6 | 7 | Marton Juhasz 8 | Gergely Gyebroszki 9 | Marton Juhasz 10 | 11 | GNU 12 | 13 | catkin 14 | gazebo_dev 15 | message_generation 16 | 17 | roscpp 18 | gazebo_msgs 19 | sensor_msgs 20 | std_srvs 21 | std_msgs 22 | nodelet 23 | urdf 24 | rosconsole 25 | 26 | gazebo 27 | message_runtime 28 | 29 | 30 | -------------------------------------------------------------------------------- /launch/simulation.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /urdf/test.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(gazebo_ros_battery) 3 | 4 | find_package(catkin REQUIRED COMPONENTS 5 | gazebo_dev 6 | message_generation 7 | gazebo_msgs 8 | roscpp 9 | nodelet 10 | std_srvs 11 | sensor_msgs 12 | rosconsole 13 | std_msgs 14 | ) 15 | 16 | find_package(Boost REQUIRED COMPONENTS thread) 17 | 18 | include_directories(include 19 | ${catkin_INCLUDE_DIRS} 20 | ${Boost_INCLUDE_DIRS} 21 | ) 22 | 23 | link_directories( 24 | ${catkin_LIBRARY_DIRS} 25 | ) 26 | 27 | add_service_files( 28 | FILES 29 | Reset.srv 30 | SetCharge.srv 31 | SetTemperature.srv 32 | ) 33 | 34 | generate_messages( 35 | DEPENDENCIES std_msgs 36 | ) 37 | 38 | catkin_package( 39 | INCLUDE_DIRS include 40 | LIBRARIES 41 | CATKIN_DEPENDS 42 | message_runtime 43 | gazebo_msgs 44 | roscpp 45 | nodelet 46 | std_srvs 47 | sensor_msgs 48 | rosconsole 49 | std_msgs 50 | ) 51 | 52 | ########### 53 | ## Build ## 54 | ########### 55 | 56 | add_library(gazebo_ros_battery src/gazebo_ros_battery.cpp) 57 | target_link_libraries(gazebo_ros_battery gazebo_ros_utils ${GAZEBO_LIBRARIES} ${catkin_LIBRARIES} ${Boost_LIBRARIES}) 58 | add_dependencies(gazebo_ros_battery ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) 59 | 60 | ############# 61 | ## Install ## 62 | ############# 63 | 64 | install(DIRECTORY include/${PROJECT_NAME}/ 65 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} 66 | FILES_MATCHING PATTERN "*.h" 67 | PATTERN ".svn" EXCLUDE 68 | ) 69 | 70 | install(TARGETS 71 | gazebo_ros_battery 72 | ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 73 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 74 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} 75 | ) 76 | 77 | install(DIRECTORY xacro 78 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 79 | ) 80 | -------------------------------------------------------------------------------- /params/battery_config.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | # coding=UTF-8 3 | import numpy as np 4 | import matplotlib.pyplot as plt 5 | from matplotlib.pyplot import figure 6 | import sys 7 | import yaml 8 | 9 | if (len(sys.argv)==2): 10 | with open(sys.argv[1]) as file: 11 | parameter = yaml.load(file, Loader=yaml.FullLoader) 12 | 13 | K = parameter['polarization_constant'] 14 | Q = parameter['design_capacity'] 15 | E0 = parameter['full_charge_voltage'] 16 | A = parameter['exponential_voltage'] 17 | B = parameter['exponential_capacity'] 18 | Vcutoff = parameter['cut_off_voltage'] 19 | Ctime = parameter['characteristic_time'] 20 | Tshift = parameter['reversible_voltage_temp'] 21 | Kalpha = parameter['arrhenius_rate_polarization'] 22 | dQdT = parameter['capacity_temp_coeff'] 23 | T0 = parameter['design_temperature'] 24 | print('Parameters loaded.') 25 | 26 | def V(it,i,T): 27 | t = T+273.15 28 | t0 = T0+273.15 29 | QT = Q + dQdT*(t-t0) 30 | KT = K * np.exp(Kalpha*(1/t-1/t0)) 31 | E0T = E0 + Tshift*(t-t0) 32 | return E0T - KT*QT/(QT-it)*(i*Ctime/3600.0+it) + A*np.exp(-B*it) 33 | 34 | def Vc(it): 35 | return Vcutoff + 0*it 36 | 37 | figure(num=None, figsize=(16, 8), dpi=80, facecolor='w', edgecolor='k') 38 | 39 | plt.subplot(1, 2, 1) 40 | xx = np.arange(start = 0, stop = Q, step = 0.05) 41 | plt.plot(xx, V(xx,0.1*Q,T0 ), 'g-') 42 | xx = np.arange(start = 0, stop = Q+dQdT*(T0/2-T0), step = 0.05) 43 | plt.plot(xx, V(xx,0.1*Q,T0/2), 'c-') 44 | xx = np.arange(start = 0, stop = Q+dQdT*(0-T0), step = 0.05) 45 | plt.plot(xx, V(xx,0.1*Q,0 ), 'b-') 46 | xx = np.arange(start = 0, stop = Q+dQdT*(-10-T0), step = 0.05) 47 | plt.plot(xx, V(xx,0.1*Q,-10 ), 'm-') 48 | xx = np.arange(start = 0, stop = Q+dQdT*(-20-T0), step = 0.05) 49 | plt.plot(xx, V(xx,0.1*Q,-20 ), 'r-') 50 | xx = np.arange(start = 0, stop = Q, step = 0.05) 51 | plt.plot(xx, Vc(xx), 'k-') 52 | plt.axis([0, Q, 0, E0+A+1]) 53 | plt.xlabel('SOC [Ah]') 54 | plt.ylabel('Voltage [V]') 55 | plt.legend([ 'T = T_0 °C', 'T = T_0/2 °C', 'T = 0 °C', 'T = -10 °C', 'T = -20 °C']) 56 | plt.title('Discharge characteristics versus Temperature (at 0.1C)'); 57 | 58 | xx = np.arange(start = 0, stop = Q, step = 0.05) 59 | plt.subplot(1, 2, 2) 60 | plt.plot(xx, V(xx,0.1*Q,T0), 'g-') 61 | plt.plot(xx, V(xx,0.5*Q,T0), 'c-') 62 | plt.plot(xx, V(xx,1*Q,T0 ), 'b-') 63 | plt.plot(xx, V(xx,5*Q,T0 ), 'm-') 64 | plt.plot(xx, V(xx,10*Q,T0 ), 'r-') 65 | plt.plot(xx, Vc(xx), 'k-') 66 | plt.axis([0, Q, 0, E0+A+1]) 67 | plt.xlabel('SOC [Ah]') 68 | plt.ylabel('Voltage [V]') 69 | plt.legend([ '0.1C', '0.5C', '1C', '5C', '10C']) 70 | plt.title('Discharge characteristics versus discharge rate (at T=T0)'); 71 | 72 | plt.tight_layout() 73 | plt.show() 74 | 75 | else: 76 | print('Please provide the name of the parameter file.') 77 | -------------------------------------------------------------------------------- /include/gazebo_ros_battery/gazebo_ros_battery.h: -------------------------------------------------------------------------------- 1 | #ifndef _MOTOR_PLUGIN_H_ 2 | #define _MOTOR_PLUGIN_H_ 3 | 4 | #include 5 | 6 | // Gazebo 7 | #include 8 | #include 9 | #include 10 | 11 | // ROS 12 | #include 13 | #include 14 | 15 | // Custom Callback Queue 16 | #include 17 | #include 18 | 19 | // Boost 20 | #include 21 | #include 22 | 23 | // Services 24 | #include 25 | #include 26 | #include 27 | 28 | namespace gazebo { 29 | 30 | class Joint; 31 | class Entity; 32 | 33 | class GazeboRosBattery : public ModelPlugin { 34 | 35 | public: 36 | 37 | GazeboRosBattery(); 38 | ~GazeboRosBattery(); 39 | void Load(physics::ModelPtr _parent, sdf::ElementPtr _sdf); 40 | void Reset(); 41 | 42 | protected: 43 | 44 | virtual void UpdateChild(); 45 | virtual void FiniChild(); 46 | ros::ServiceServer set_temperature; 47 | ros::ServiceServer set_charge_state; 48 | ros::ServiceServer reset_model; 49 | boost::mutex service_lock; 50 | 51 | private: 52 | 53 | GazeboRosPtr gazebo_ros_; 54 | event::ConnectionPtr update_connection_; 55 | physics::ModelPtr parent; 56 | ros::Publisher battery_state_publisher_; 57 | ros::Publisher battery_voltage_publisher_; 58 | std::vector current_draw_subscribers_; 59 | sensor_msgs::BatteryState battery_state_; 60 | common::Time last_update_time_; 61 | std::string battery_topic_; 62 | std::string consumer_topic_; 63 | std::string battery_voltage_topic_; 64 | std::string frame_id_; 65 | std::string plugin_name_; 66 | std::vector drawn_currents_; 67 | // common parameters 68 | bool publish_voltage_; 69 | int technology_; 70 | int num_of_consumers_; 71 | int cell_count_; 72 | double update_rate_; 73 | double update_period_; 74 | double design_capacity_; 75 | double current_drawn_; 76 | double nominal_voltage_; 77 | double constant_voltage_; 78 | double cut_off_voltage_; 79 | double internal_resistance_; 80 | double lpf_tau_; 81 | // linear model params 82 | double lin_discharge_coeff_; 83 | bool use_nonlinear_model_; 84 | // nonlinear model params 85 | double polarization_constant_; // polarization constant [V/Ah] or pol. resistance [Ohm] 86 | double exponential_voltage_; // exponential voltage [V] 87 | double exponential_capacity_; // exponential capacity [1/(Ah)] 88 | double characteristic_time_; // characteristic time [s] for charge-dependence 89 | double design_temperature_; // Design temperature where pol. const is unchanged and voltages are nominal. 90 | double arrhenius_rate_polarization_; // Arrhenius rate of polarization constant [K] 91 | double capacity_temp_coeff_; // Temperature dependence of capacity [Ah/K] 92 | double reversible_voltage_temp_; // Linear temperature dependant voltage shift [V/K] 93 | // internal variables 94 | bool model_initialised_; 95 | bool internal_cutt_off_; 96 | bool battery_empty_; 97 | double voltage_; 98 | double charge_; 99 | double charge_memory_; 100 | double current_; 101 | double discharge_; 102 | double capacity_; 103 | double temperature_; 104 | double temp_set_; 105 | double temp_lpf_tau_; 106 | double current_lpf_; 107 | 108 | // model update 109 | void linear_discharge_voltage_update(); 110 | void nonlinear_discharge_voltage_update(); 111 | 112 | // Services 113 | bool SetCharge(gazebo_ros_battery::SetCharge::Request& req, 114 | gazebo_ros_battery::SetCharge::Response& res); 115 | 116 | bool ResetModel(gazebo_ros_battery::Reset::Request& req, 117 | gazebo_ros_battery::Reset::Response& res); 118 | 119 | bool SetTemperature(gazebo_ros_battery::SetTemperature::Request& req, 120 | gazebo_ros_battery::SetTemperature::Response& res); 121 | // Callback Queue 122 | ros::CallbackQueue queue_; 123 | std::thread callback_queue_thread_; 124 | boost::mutex lock_; 125 | void QueueThread(); 126 | void currentCallback(const std_msgs::Float32::ConstPtr& current, int consumer_id); 127 | }; 128 | 129 | } 130 | 131 | #endif 132 | -------------------------------------------------------------------------------- /xacro/battery.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | ${frame_id} 19 | ${sensor_name}/status 20 | ${sensor_name}/consumer 21 | ${sensor_name}/voltage 22 | ${battery_param['publish_voltage']} 23 | ${battery_param['num_of_consumers']} 24 | ${battery_param['technology']} 25 | ${battery_param['design_capacity']} 26 | ${battery_param['number_of_cells']} 27 | ${battery_param['nominal_voltage']} 28 | ${battery_param['full_charge_voltage']} 29 | ${battery_param['cut_off_voltage']} 30 | ${battery_param['internal_resistance']} 31 | ${battery_param['current_filter_tau']} 32 | ${battery_param['polarization_constant']} 33 | ${battery_param['exponential_voltage']} 34 | ${battery_param['exponential_capacity']} 35 | ${battery_param['characteristic_time']} 36 | ${battery_param['reversible_voltage_temp']} 37 | ${battery_param['arrhenius_rate_polarization']} 38 | ${battery_param['capacity_temp_coeff']} 39 | ${battery_param['design_temperature']} 40 | ${battery_param['temperature_response_tau']} 41 | True 42 | 10.0 43 | Debug 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | ${frame_id} 53 | ${num_of_consumers} 54 | ${sensor_name}/status 55 | ${sensor_name}/consumer 56 | True 57 | ${sensor_name}/voltage 58 | POWER_SUPPLY_TECHNOLOGY_LION 59 | 4.0 60 | 6 61 | 24 62 | 25.2 63 | 18.0 64 | 0.11 65 | 1 66 | True 67 | 0.07 68 | 0.7 69 | 3.0 70 | 220.0 71 | 0.05 72 | 800.0 73 | 0.01 74 | 0.5 75 | 10.0 76 | Debug 77 | 78 | 79 | 80 | 81 | 82 | 83 | 84 | 85 | ${frame_id} 86 | ${num_of_consumers} 87 | ${sensor_name}/status 88 | ${sensor_name}/consumer 89 | True 90 | ${sensor_name}/voltage 91 | POWER_SUPPLY_TECHNOLOGY_VRLA 92 | 9.0 93 | 6 94 | 12 95 | 13.8 96 | 0.0 97 | 0.018 98 | 1 99 | False 100 | -1 101 | 10.0 102 | Debug 103 | 104 | 105 | 106 | 107 | 108 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Gazebo-ROS battery plugin 2 | 3 | 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. 4 | 5 | ## Battery models 6 | 7 | **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. 8 | 9 | ![](doc/characteristics.png) 10 | 11 | 12 | 13 | ### Simple linear model 14 | 15 | 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. 16 | 17 | ![](doc/linear_model.png) 18 | 19 | Where 20 | 21 | * **V** is the current voltage [V], 22 | 23 | * **V0** is the voltage of the battery when fully charged [V], 24 | * **α** is the linear discharge coefficient, 25 | * **it** is the accumulated discharge [Ah], 26 | * **Q** is the design capacity of the battery [Ah], 27 | * **R** is the internal resistance of the battery [Ohm], 28 | * and **i** is the current drawn. *( after processed by a low-pass filter )* [A] 29 | 30 | 31 | 32 | ### Generic dynamic model 33 | 34 | Nonlinear dynamic discharge model is formulated as 35 | 36 | ![](doc/generic_model.png) 37 | 38 | where 39 | 40 | * ***A*** is the exponential voltage [V], 41 | * ***B*** is the exponential capacity [1/Ah], 42 | * **T** is the temperature of the battery [C], 43 | * **Ta** is the ambient temperature [C], 44 | 45 | with the impact of temperature on the model parameters 46 | 47 | ![](doc/temp_effect.png) 48 | 49 | where 50 | 51 | * **K** is the polarization constant [V/Ah] 52 | 53 | * **Tref** is the reference or design temperature [C], 54 | 55 | * **α** is the Arrhenius rate constant for the polarization resistance. 56 | 57 | 58 | 59 | ## How to use the plugin 60 | 61 | 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._ 62 | 63 | ```xml 64 | 65 | 67 | ``` 68 | 69 | 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`. 70 | 71 | 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. 72 | 73 | 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. 74 | 75 | ### Parameters 76 | 77 | Mode of operation is chosen through the `use_nonlinear_model` parameter. *( Defaults to True )* 78 | 79 | #### Common parameters 80 | 81 | - `current_filter_tau` - is the coefficient for the low pass filter on the drawn current 82 | - `temperature_response_tau` - is the coefficient for the internal battery temperature filter 83 | - `update_rate` - is the fixed frequency of the model update function [Hz] 84 | - `rosDebugLevel` - sets the plugin log level, debug by default 85 | - `num_of_consumers` - number of load subscribers to instantiate 86 | - `consumer_topic` - topic prefix of the numbered load subscribers ( `/battery/consumer/0` ) 87 | - `frame_id` - the transformation frame associated with the battery in the URDF 88 | - `battery_topic` - battery state message topic name 89 | - `publish_voltage` - whether to publish battery voltage as `std_msgs::Float32` alongside the status messages ( *[gazebo_ros_motors](https://github.com/nilseuropa/gazebo_ros_motors)* compatibility ) 90 | - `battery_voltage_topic` - name of the battery voltage topic if enabled 91 | 92 | #### Linear model parameters 93 | 94 | * `linear_discharge_coeff` - or **α **as described in the model section - is a weight that sets how much the actual charge is considered in the calculation of the discharge curve steepness. 95 | 96 | #### Nonlinear model parameters 97 | 98 | * `polarization_constant `- or **K** - is the polarization constant [V/Ah] 99 | * `exponential_voltage` - or **A** - [V] is the voltage at the end of the exponential area 100 | * `exponential_capacity` - or **B** - [1/Ah] is the capacity at the end of the exponential area 101 | * `characteristic_time` - characteristic time [s] of **i*** 102 | * `design_temperature`- or **Tref**- Design temperature where polarization constant is unchanged 103 | * `arrhenius_rate_polarization` - or **α** - Arrhenius rate of polarization constant [K] 104 | * `capacity_temp_coeff` - Temperature dependence of capacity [Ah/K] 105 | * `reversible_voltage_temp` - Linear temperature dependent voltage shift [V/K] 106 | 107 | ### Model tuning 108 | 109 | 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. 110 | 111 | 1. Acquire the discharge curve of the given battery. 112 | 2. Create a parameter file ( duplicate the one provided ). 113 | 3. Use the `battery_config.py` tool in the `params` folder to visualize the models curve. 114 | 4. Adjust the parameters in the `yaml` file until the fit is acceptable. 115 | 5. Load the same parameter file with the `xacro` to run your battery simulation. 116 | 117 | #### Model configuration script 118 | 119 | `~/gazebo_ros_battery/params$ ./battery_config.py G24B4.yaml` 120 | 121 | ![](doc/config_tool.png) 122 | 123 | 124 | 125 | **Authors:** Marton Juhasz - [nilseuropa](https://github.com/nilseuropa), Gergely Gyebroszki - [gyebro](https://github.com/gyebro) 126 | 127 | **Sources:** https://www.mathworks.com/help/physmod/sps/powersys/ref/battery.html 128 | 129 | -------------------------------------------------------------------------------- /src/gazebo_ros_battery.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include 3 | #include 4 | #include 5 | 6 | #include "gazebo_ros_battery/gazebo_ros_battery.h" 7 | 8 | namespace gazebo { 9 | 10 | // Constructor 11 | GazeboRosBattery::GazeboRosBattery() { 12 | } 13 | 14 | // Destructor 15 | GazeboRosBattery::~GazeboRosBattery() { 16 | FiniChild(); 17 | } 18 | 19 | // Load the controller 20 | void GazeboRosBattery::Load ( physics::ModelPtr _parent, sdf::ElementPtr _sdf ) 21 | { 22 | this->parent = _parent; 23 | this->plugin_name_ = _sdf->GetAttribute("name")->GetAsString(); 24 | 25 | gazebo_ros_ = GazeboRosPtr ( new GazeboRos ( _parent, _sdf, plugin_name_ ) ); 26 | gazebo_ros_->isInitialized(); 27 | 28 | // topic params 29 | gazebo_ros_->getParameter ( num_of_consumers_, "num_of_consumers", 2 ); 30 | 31 | gazebo_ros_->getParameter ( consumer_topic_, "consumer_topic", "/battery/consumer" ); 32 | gazebo_ros_->getParameter ( frame_id_, "frame_id", "battery" ); 33 | gazebo_ros_->getParameter ( battery_topic_, "battery_topic", "/battery/status" ); 34 | 35 | gazebo_ros_->getParameter ( publish_voltage_, "publish_voltage", true ); 36 | if (publish_voltage_){ 37 | gazebo_ros_->getParameter ( battery_voltage_topic_, "battery_voltage_topic", "/battery/voltage" ); 38 | } 39 | 40 | // common parameters 41 | gazebo_ros_->getParameter ( technology_, "technology", sensor_msgs::BatteryState::POWER_SUPPLY_TECHNOLOGY_LION ); 42 | gazebo_ros_->getParameter ( cell_count_, "number_of_cells", 8 ); 43 | gazebo_ros_->getParameter ( update_rate_, "update_rate", 10.0 ); 44 | gazebo_ros_->getParameter ( design_capacity_, "design_capacity", 4.0 ); 45 | gazebo_ros_->getParameter ( nominal_voltage_, "nominal_voltage", 24.0 ); 46 | gazebo_ros_->getParameter ( cut_off_voltage_, "cut_off_voltage", 18.0 ); 47 | gazebo_ros_->getParameter ( constant_voltage_, "full_charge_voltage", 24.2 ); 48 | gazebo_ros_->getParameter ( lpf_tau_, "current_filter_tau", 1.0 ); 49 | gazebo_ros_->getParameter ( temp_lpf_tau_, "temperature_response_tau", 0.5 ); 50 | gazebo_ros_->getParameter ( internal_resistance_, "internal_resistance", 0.05 ); 51 | 52 | // model specific params 53 | gazebo_ros_->getParameter ( use_nonlinear_model_, "use_nonlinear_model", true ); 54 | if (!use_nonlinear_model_) { 55 | gazebo_ros_->getParameter ( lin_discharge_coeff_, "linear_discharge_coeff", -1.0 ); 56 | } 57 | else { 58 | gazebo_ros_->getParameter ( polarization_constant_, "polarization_constant", 0.07 ); 59 | gazebo_ros_->getParameter ( exponential_voltage_, "exponential_voltage", 0.7 ); 60 | gazebo_ros_->getParameter ( exponential_capacity_, "exponential_capacity", 3.0 ); 61 | gazebo_ros_->getParameter ( characteristic_time_, "characteristic_time", 200.0 ); 62 | gazebo_ros_->getParameter ( design_temperature_, "design_temperature", 25.0 ); 63 | gazebo_ros_->getParameter ( arrhenius_rate_polarization_, "arrhenius_rate_polarization", 500.0 ); 64 | gazebo_ros_->getParameter ( reversible_voltage_temp_, "reversible_voltage_temp", 0.05 ); 65 | gazebo_ros_->getParameter ( capacity_temp_coeff_, "capacity_temp_coeff", 0.01 ); 66 | } 67 | 68 | battery_state_.header.frame_id = frame_id_; 69 | battery_state_.power_supply_technology = technology_; 70 | battery_state_.power_supply_health = sensor_msgs::BatteryState::POWER_SUPPLY_HEALTH_GOOD; 71 | battery_state_.power_supply_status = sensor_msgs::BatteryState::POWER_SUPPLY_STATUS_UNKNOWN; 72 | battery_state_.design_capacity = design_capacity_; 73 | battery_state_.capacity = design_capacity_; 74 | // battery_state_.capacity = last_full_capacity_; 75 | battery_state_.present = true; 76 | battery_state_.temperature = temperature_ = design_temperature_; 77 | 78 | // start 79 | if ( this->update_rate_ > 0.0 ) this->update_period_ = 1.0 / this->update_rate_; else this->update_period_ = 0.0; 80 | last_update_time_ = parent->GetWorld()->SimTime(); 81 | 82 | // subscribers 83 | std::vector subscribe_options; 84 | ROS_INFO_NAMED(plugin_name_, "%s: Creating %d consumer subscribers:", gazebo_ros_->info(), num_of_consumers_); 85 | for (int i=0; i ( 88 | consumer_topic_+"/"+std::to_string(i), 89 | 1, 90 | boost::bind(&GazeboRosBattery::currentCallback, this, _1, i), 91 | ros::VoidPtr(), 92 | &queue_ 93 | )); 94 | ROS_INFO_NAMED(plugin_name_, "%s: Listening to consumer on: %s", gazebo_ros_->info(), (consumer_topic_+"/"+std::to_string(i)).c_str()); 95 | current_draw_subscribers_.push_back(gazebo_ros_->node()->subscribe(subscribe_options[i])); 96 | drawn_currents_.push_back(0); 97 | } 98 | 99 | // publishers 100 | battery_state_publisher_ = gazebo_ros_->node()->advertise(battery_topic_, 1); 101 | ROS_INFO_NAMED(plugin_name_, "%s: Advertising battery state on %s ", gazebo_ros_->info(), battery_topic_.c_str()); 102 | if (publish_voltage_){ 103 | battery_voltage_publisher_ = gazebo_ros_->node()->advertise(battery_voltage_topic_, 1); 104 | ROS_INFO_NAMED(plugin_name_, "%s: Advertising battery voltage on %s ", gazebo_ros_->info(), battery_voltage_topic_.c_str()); 105 | } 106 | 107 | // start custom queue 108 | this->callback_queue_thread_ = std::thread ( std::bind ( &GazeboRosBattery::QueueThread, this ) ); 109 | 110 | // listen to the update event (broadcast every simulation iteration) 111 | this->update_connection_ = event::Events::ConnectWorldUpdateBegin ( boost::bind ( &GazeboRosBattery::UpdateChild, this ) ); 112 | 113 | // services 114 | this->set_charge_state = gazebo_ros_->node()->advertiseService(plugin_name_ + "/set_charge", &GazeboRosBattery::SetCharge, this); 115 | this->set_temperature = gazebo_ros_->node()->advertiseService(plugin_name_ + "/set_temperature", &GazeboRosBattery::SetTemperature, this); 116 | this->reset_model = gazebo_ros_->node()->advertiseService(plugin_name_ + "/reset", &GazeboRosBattery::ResetModel, this); 117 | 118 | this->model_initialised_ = false; 119 | Reset(); 120 | } 121 | 122 | bool GazeboRosBattery::SetTemperature(gazebo_ros_battery::SetTemperature::Request& req, gazebo_ros_battery::SetTemperature::Response& res) 123 | { 124 | service_lock.lock(); 125 | temp_set_ = req.temperature.data; 126 | ROS_WARN_NAMED(plugin_name_, "%s: Temperature set: %f", gazebo_ros_->info(), temp_set_); 127 | service_lock.unlock(); 128 | return true; 129 | } 130 | 131 | bool GazeboRosBattery::SetCharge(gazebo_ros_battery::SetCharge::Request &req, gazebo_ros_battery::SetCharge::Response &res) 132 | { 133 | service_lock.lock(); 134 | discharge_ = req.charge.data; 135 | ROS_WARN_NAMED(plugin_name_, "%s: Charge set: %f", gazebo_ros_->info(), design_capacity_ + discharge_); 136 | service_lock.unlock(); 137 | return true; 138 | } 139 | 140 | bool GazeboRosBattery::ResetModel(gazebo_ros_battery::Reset::Request& req, gazebo_ros_battery::Reset::Response& res) 141 | { 142 | service_lock.lock(); 143 | Reset(); 144 | service_lock.unlock(); 145 | return true; 146 | } 147 | 148 | void GazeboRosBattery::Reset() { 149 | last_update_time_ = parent->GetWorld()->SimTime(); 150 | charge_ = design_capacity_; 151 | voltage_ = constant_voltage_; 152 | temperature_ = design_temperature_; 153 | temp_set_ = design_temperature_; 154 | discharge_ = 0; 155 | current_drawn_ = 0; 156 | battery_empty_ = false; 157 | internal_cutt_off_ = false; 158 | model_initialised_ = true; 159 | ROS_WARN_NAMED(plugin_name_, "%s: Battery model reset.", gazebo_ros_->info()); 160 | } 161 | 162 | // simple linear discharge model 163 | void GazeboRosBattery::linear_discharge_voltage_update() { 164 | voltage_ = constant_voltage_ + lin_discharge_coeff_ * (1 - discharge_ / design_capacity_) - internal_resistance_ * current_lpf_; 165 | } 166 | 167 | // Temperature dependent parameters: 168 | // QT = Q + dQdT*(t-t0) 169 | // KT = K * np.exp(Kalpha*(1/t-1/t0)) 170 | // E0T = E0 + Tshift*(t-t0) 171 | // v(i) = E0T - KT*QT/(QT-it)*(i*Ctime/3600.0+it) + A*np.exp(-B*it) 172 | // 173 | // where 174 | // E0: constant voltage [V] 175 | // K: polarization constant [V/Ah] or pol. resistance [Ohm] 176 | // Q: maximum capacity [Ah] 177 | // A: exponential voltage [V] 178 | // B: exponential capacity [A/h] 179 | // it: already extracted capacity [Ah] (= - discharge) 180 | // id: current * characteristic time [Ah] 181 | // i: battery current [A] 182 | // T0: design temperature [Celsius] 183 | // Tpol: name of the Vulkan first officer aboard Enterprise NX-01 [Celsius] 184 | // Tshift: temperature offset [Celsius] 185 | 186 | void GazeboRosBattery::nonlinear_discharge_voltage_update() { 187 | double t = temperature_+273.15; 188 | double t0 = design_temperature_+273.15; 189 | double E0T = constant_voltage_ + reversible_voltage_temp_*(t-t0); // TODO: Don't increase for t>t0 ? 190 | double QT = design_capacity_ + capacity_temp_coeff_*(t-t0); // TODO: Don't increase for t>t0 ? 191 | double KT = polarization_constant_ * exp(arrhenius_rate_polarization_*(1/t-1/t0)); 192 | voltage_ = E0T 193 | - KT * QT/(QT + discharge_) * (current_lpf_*(characteristic_time_/3600.0) - discharge_) 194 | + exponential_voltage_*exp(-exponential_capacity_*-discharge_); 195 | } 196 | 197 | // Plugin update function 198 | void GazeboRosBattery::UpdateChild() { 199 | common::Time current_time = parent->GetWorld()->SimTime(); 200 | double dt = ( current_time - last_update_time_ ).Double(); 201 | 202 | if ( dt > update_period_ && model_initialised_ ) { 203 | 204 | double n = dt / temp_lpf_tau_; 205 | temperature_ = temperature_ + n * (temp_set_ - temperature_); 206 | 207 | if (!battery_empty_) { 208 | // LPF filter on current 209 | double k = dt / lpf_tau_; 210 | current_lpf_ = current_lpf_ + k * (current_drawn_ - current_lpf_); 211 | // Accumulate discharge (negative: 0 to design capacity) 212 | discharge_ = discharge_ - GZ_SEC_TO_HOUR(dt * current_lpf_); 213 | if (!internal_cutt_off_) { 214 | if (use_nonlinear_model_){ 215 | nonlinear_discharge_voltage_update(); 216 | } 217 | else { 218 | linear_discharge_voltage_update(); 219 | } 220 | charge_ = design_capacity_ + discharge_; // discharge is negative 221 | charge_memory_ = charge_; 222 | } 223 | if (voltage_<=cut_off_voltage_ && !internal_cutt_off_) { 224 | discharge_ = 0; 225 | voltage_ = 0; 226 | internal_cutt_off_ = true; 227 | charge_ = charge_memory_; 228 | ROS_WARN_NAMED(plugin_name_, "%s: Battery voltage cut off.", gazebo_ros_->info()); 229 | } 230 | } 231 | 232 | if (!battery_empty_ && charge_<=0) { 233 | discharge_ = 0; 234 | current_lpf_ = 0; 235 | voltage_ = 0; 236 | battery_empty_ = true; 237 | ROS_WARN_NAMED(plugin_name_, "%s: Battery discharged.", gazebo_ros_->info()); 238 | } 239 | // state update 240 | battery_state_.header.stamp = ros::Time::now(); 241 | battery_state_.voltage = voltage_; 242 | battery_state_.current = current_lpf_; 243 | battery_state_.charge = charge_; 244 | battery_state_.percentage = (charge_/design_capacity_)*100; 245 | battery_state_.temperature = temperature_; 246 | battery_state_publisher_.publish( battery_state_ ); 247 | std_msgs::Float32 battery_voltage_; 248 | battery_voltage_.data = voltage_; 249 | if (publish_voltage_) battery_voltage_publisher_.publish( battery_voltage_ ); 250 | last_update_time_+= common::Time ( update_period_ ); 251 | } 252 | } 253 | 254 | // Finalize the controller 255 | void GazeboRosBattery::FiniChild() { 256 | gazebo_ros_->node()->shutdown(); 257 | } 258 | 259 | void GazeboRosBattery::currentCallback(const std_msgs::Float32::ConstPtr& current, int consumer_id) { 260 | 261 | current_drawn_ = 0; 262 | drawn_currents_[consumer_id]=current->data; 263 | for (int i=0; inode()->ok() ) { 280 | queue_.callAvailable ( ros::WallDuration ( timeout ) ); 281 | } 282 | } 283 | 284 | GZ_REGISTER_MODEL_PLUGIN ( GazeboRosBattery ) 285 | // eof_ns 286 | } 287 | -------------------------------------------------------------------------------- /config/dashboard.perspective: -------------------------------------------------------------------------------- 1 | { 2 | "keys": {}, 3 | "groups": { 4 | "mainwindow": { 5 | "keys": { 6 | "geometry": { 7 | "repr(QByteArray.hex)": "QtCore.QByteArray(b'01d9d0cb0003000000000000000000000000077f00000437000000000000001c0000077f0000043700000002000000000780000000000000001c0000077f00000437')", 8 | "type": "repr(QByteArray.hex)", 9 | "pretty-print": " 7 7 7" 10 | }, 11 | "state": { 12 | "repr(QByteArray.hex)": "QtCore.QByteArray(b'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')", 13 | "type": "repr(QByteArray.hex)", 14 | "pretty-print": " Zrqt_image_view__ImageView__1__ImageViewWidget jrqt_robot_steering__RobotSteering__1__RobotSteeringUi Lrqt_tf_tree__RosTfTree__1__RosTfTreeUi brqt_virtual_joy__My Plugin__1__virtualJoyPluginUi - 3 - Brqt_plot__Plot__2__DataPlotWidget Brqt_plot__Plot__1__DataPlotWidget - x k U " 15 | } 16 | }, 17 | "groups": { 18 | "toolbar_areas": { 19 | "keys": { 20 | "MinimizedDockWidgetsToolbar": { 21 | "repr": "8", 22 | "type": "repr" 23 | } 24 | }, 25 | "groups": {} 26 | } 27 | } 28 | }, 29 | "pluginmanager": { 30 | "keys": { 31 | "running-plugins": { 32 | "repr": "{'rqt_plot/Plot': [1], 'rqt_publisher/Publisher': [1], 'rqt_service_caller/ServiceCaller': [1]}", 33 | "type": "repr" 34 | } 35 | }, 36 | "groups": { 37 | "plugin__bag_to_dls__RosBagToDataset__1": { 38 | "keys": {}, 39 | "groups": { 40 | "dock_widget__RosBagToDatasetUi": { 41 | "keys": { 42 | "dock_widget_title": { 43 | "repr": "'BAG to Dataset'", 44 | "type": "repr" 45 | }, 46 | "dockable": { 47 | "repr": "'true'", 48 | "type": "repr" 49 | }, 50 | "parent": { 51 | "repr": "None", 52 | "type": "repr" 53 | } 54 | }, 55 | "groups": {} 56 | }, 57 | "plugin": { 58 | "keys": { 59 | "auto_fit_graph_check_box_state": { 60 | "repr": "'false'", 61 | "type": "repr" 62 | }, 63 | "highlight_connections_check_box_state": { 64 | "repr": "'false'", 65 | "type": "repr" 66 | } 67 | }, 68 | "groups": {} 69 | } 70 | } 71 | }, 72 | "plugin__nowtech_neural_tools__RosBagToDataset__1": { 73 | "keys": {}, 74 | "groups": { 75 | "dock_widget__RosBagToDatasetUi": { 76 | "keys": { 77 | "dock_widget_title": { 78 | "repr": "'BAG to Dataset'", 79 | "type": "repr" 80 | }, 81 | "dockable": { 82 | "repr": "'true'", 83 | "type": "repr" 84 | }, 85 | "parent": { 86 | "repr": "None", 87 | "type": "repr" 88 | } 89 | }, 90 | "groups": {} 91 | } 92 | } 93 | }, 94 | "plugin__rqt_bag__Bag__1": { 95 | "keys": {}, 96 | "groups": { 97 | "dock_widget__BagWidget": { 98 | "keys": { 99 | "dock_widget_title": { 100 | "repr": "'Bag'", 101 | "type": "repr" 102 | }, 103 | "dockable": { 104 | "repr": "'true'", 105 | "type": "repr" 106 | }, 107 | "parent": { 108 | "repr": "None", 109 | "type": "repr" 110 | } 111 | }, 112 | "groups": {} 113 | } 114 | } 115 | }, 116 | "plugin__rqt_bag_to_dataset__RosBagToDataset__1": { 117 | "keys": {}, 118 | "groups": { 119 | "dock_widget__RosBagToDatasetUi": { 120 | "keys": { 121 | "dock_widget_title": { 122 | "repr": "'BAG to Dataset'", 123 | "type": "repr" 124 | }, 125 | "dockable": { 126 | "repr": "'true'", 127 | "type": "repr" 128 | }, 129 | "parent": { 130 | "repr": "None", 131 | "type": "repr" 132 | } 133 | }, 134 | "groups": {} 135 | } 136 | } 137 | }, 138 | "plugin__rqt_console__Console__1": { 139 | "keys": {}, 140 | "groups": { 141 | "dock_widget__ConsoleWidget": { 142 | "keys": { 143 | "dock_widget_title": { 144 | "repr": "'Console'", 145 | "type": "repr" 146 | }, 147 | "dockable": { 148 | "repr": "'true'", 149 | "type": "repr" 150 | }, 151 | "parent": { 152 | "repr": "None", 153 | "type": "repr" 154 | } 155 | }, 156 | "groups": {} 157 | }, 158 | "plugin": { 159 | "keys": { 160 | "exclude_filters": { 161 | "repr": "'severity'", 162 | "type": "repr" 163 | }, 164 | "filter_splitter": { 165 | "repr(QByteArray.hex)": "QtCore.QByteArray(b'000000ff000000010000000200000071000000710100000009010000000200')", 166 | "type": "repr(QByteArray.hex)", 167 | "pretty-print": " q q " 168 | }, 169 | "highlight_filters": { 170 | "repr": "'message'", 171 | "type": "repr" 172 | }, 173 | "message_limit": { 174 | "repr": "'20000'", 175 | "type": "repr" 176 | }, 177 | "paused": { 178 | "repr": "'false'", 179 | "type": "repr" 180 | }, 181 | "settings_exist": { 182 | "repr": "'true'", 183 | "type": "repr" 184 | }, 185 | "show_highlighted_only": { 186 | "repr": "'false'", 187 | "type": "repr" 188 | }, 189 | "table_splitter": { 190 | "repr(QByteArray.hex)": "QtCore.QByteArray(b'000000ff000000010000000200000222000000000100000009010000000200')", 191 | "type": "repr(QByteArray.hex)", 192 | "pretty-print": " \" " 193 | } 194 | }, 195 | "groups": { 196 | "exclude_filter_0": { 197 | "keys": { 198 | "enabled": { 199 | "repr": "'true'", 200 | "type": "repr" 201 | }, 202 | "itemlist": { 203 | "repr": "''", 204 | "type": "repr" 205 | } 206 | }, 207 | "groups": {} 208 | }, 209 | "highlight_filter_0": { 210 | "keys": { 211 | "enabled": { 212 | "repr": "'true'", 213 | "type": "repr" 214 | }, 215 | "regex": { 216 | "repr": "'false'", 217 | "type": "repr" 218 | }, 219 | "text": { 220 | "repr": "''", 221 | "type": "repr" 222 | } 223 | }, 224 | "groups": {} 225 | } 226 | } 227 | } 228 | } 229 | }, 230 | "plugin__rqt_graph__RosGraph__1": { 231 | "keys": {}, 232 | "groups": { 233 | "dock_widget__RosGraphUi": { 234 | "keys": { 235 | "dock_widget_title": { 236 | "repr": "'Node Graph'", 237 | "type": "repr" 238 | }, 239 | "dockable": { 240 | "repr": "'true'", 241 | "type": "repr" 242 | }, 243 | "parent": { 244 | "repr": "None", 245 | "type": "repr" 246 | } 247 | }, 248 | "groups": {} 249 | }, 250 | "plugin": { 251 | "keys": { 252 | "actionlib_check_box_state": { 253 | "repr": "'false'", 254 | "type": "repr" 255 | }, 256 | "auto_fit_graph_check_box_state": { 257 | "repr": "'true'", 258 | "type": "repr" 259 | }, 260 | "dead_sinks_check_box_state": { 261 | "repr": "'true'", 262 | "type": "repr" 263 | }, 264 | "filter_line_edit_text": { 265 | "repr": "'/'", 266 | "type": "repr" 267 | }, 268 | "graph_type_combo_box_index": { 269 | "repr": "'2'", 270 | "type": "repr" 271 | }, 272 | "group_image_check_box_state": { 273 | "repr": "'false'", 274 | "type": "repr" 275 | }, 276 | "group_tf_check_box_state": { 277 | "repr": "'false'", 278 | "type": "repr" 279 | }, 280 | "hide_dynamic_reconfigure_check_box_state": { 281 | "repr": "'false'", 282 | "type": "repr" 283 | }, 284 | "hide_tf_nodes_check_box_state": { 285 | "repr": "'true'", 286 | "type": "repr" 287 | }, 288 | "highlight_connections_check_box_state": { 289 | "repr": "'false'", 290 | "type": "repr" 291 | }, 292 | "leaf_topics_check_box_state": { 293 | "repr": "'true'", 294 | "type": "repr" 295 | }, 296 | "namespace_cluster_spin_box_value": { 297 | "repr": "'1'", 298 | "type": "repr" 299 | }, 300 | "quiet_check_box_state": { 301 | "repr": "'true'", 302 | "type": "repr" 303 | }, 304 | "topic_filter_line_edit_text": { 305 | "repr": "'/'", 306 | "type": "repr" 307 | }, 308 | "unreachable_check_box_state": { 309 | "repr": "'false'", 310 | "type": "repr" 311 | } 312 | }, 313 | "groups": {} 314 | } 315 | } 316 | }, 317 | "plugin__rqt_image_view__ImageView__1": { 318 | "keys": {}, 319 | "groups": { 320 | "dock_widget__ImageViewWidget": { 321 | "keys": { 322 | "dock_widget_title": { 323 | "repr": "'Image View'", 324 | "type": "repr" 325 | }, 326 | "dockable": { 327 | "repr": "'true'", 328 | "type": "repr" 329 | }, 330 | "parent": { 331 | "repr": "None", 332 | "type": "repr" 333 | } 334 | }, 335 | "groups": {} 336 | }, 337 | "plugin": { 338 | "keys": { 339 | "dynamic_range": { 340 | "repr": "'false'", 341 | "type": "repr" 342 | }, 343 | "max_range": { 344 | "repr": "'10'", 345 | "type": "repr" 346 | }, 347 | "mouse_pub_topic": { 348 | "repr": "''", 349 | "type": "repr" 350 | }, 351 | "num_gridlines": { 352 | "repr": "'0'", 353 | "type": "repr" 354 | }, 355 | "publish_click_location": { 356 | "repr": "'false'", 357 | "type": "repr" 358 | }, 359 | "rotate": { 360 | "repr": "'0'", 361 | "type": "repr" 362 | }, 363 | "smooth_image": { 364 | "repr": "'false'", 365 | "type": "repr" 366 | }, 367 | "toolbar_hidden": { 368 | "repr": "'false'", 369 | "type": "repr" 370 | }, 371 | "topic": { 372 | "repr": "''", 373 | "type": "repr" 374 | }, 375 | "zoom1": { 376 | "repr": "'false'", 377 | "type": "repr" 378 | } 379 | }, 380 | "groups": {} 381 | } 382 | } 383 | }, 384 | "plugin__rqt_image_view__ImageView__2": { 385 | "keys": {}, 386 | "groups": { 387 | "dock_widget__ImageViewWidget": { 388 | "keys": { 389 | "dock_widget_title": { 390 | "repr": "'Image View (2)'", 391 | "type": "repr" 392 | }, 393 | "dockable": { 394 | "repr": "'true'", 395 | "type": "repr" 396 | }, 397 | "parent": { 398 | "repr": "None", 399 | "type": "repr" 400 | } 401 | }, 402 | "groups": {} 403 | }, 404 | "plugin": { 405 | "keys": { 406 | "dynamic_range": { 407 | "repr": "'false'", 408 | "type": "repr" 409 | }, 410 | "max_range": { 411 | "repr": "'10'", 412 | "type": "repr" 413 | }, 414 | "mouse_pub_topic": { 415 | "repr": "'/left_eye/image_raw_mouse_left'", 416 | "type": "repr" 417 | }, 418 | "num_gridlines": { 419 | "repr": "'0'", 420 | "type": "repr" 421 | }, 422 | "publish_click_location": { 423 | "repr": "'false'", 424 | "type": "repr" 425 | }, 426 | "rotate": { 427 | "repr": "'0'", 428 | "type": "repr" 429 | }, 430 | "smooth_image": { 431 | "repr": "'false'", 432 | "type": "repr" 433 | }, 434 | "toolbar_hidden": { 435 | "repr": "'false'", 436 | "type": "repr" 437 | }, 438 | "topic": { 439 | "repr": "'/left_eye/image_raw'", 440 | "type": "repr" 441 | }, 442 | "zoom1": { 443 | "repr": "'false'", 444 | "type": "repr" 445 | } 446 | }, 447 | "groups": {} 448 | } 449 | } 450 | }, 451 | "plugin__rqt_msg__Messages__1": { 452 | "keys": {}, 453 | "groups": { 454 | "dock_widget__messages.ui": { 455 | "keys": { 456 | "dock_widget_title": { 457 | "repr": "'Message Type Browser'", 458 | "type": "repr" 459 | }, 460 | "dockable": { 461 | "repr": "'true'", 462 | "type": "repr" 463 | }, 464 | "parent": { 465 | "repr": "None", 466 | "type": "repr" 467 | } 468 | }, 469 | "groups": {} 470 | } 471 | } 472 | }, 473 | "plugin__rqt_mypkg__My Plugin__1": { 474 | "keys": {}, 475 | "groups": { 476 | "dock_widget__MyPluginUi": { 477 | "keys": { 478 | "dock_widget_title": { 479 | "repr": "'Form'", 480 | "type": "repr" 481 | }, 482 | "dockable": { 483 | "repr": "'true'", 484 | "type": "repr" 485 | }, 486 | "parent": { 487 | "repr": "None", 488 | "type": "repr" 489 | } 490 | }, 491 | "groups": {} 492 | } 493 | } 494 | }, 495 | "plugin__rqt_plot__Plot__1": { 496 | "keys": {}, 497 | "groups": { 498 | "dock_widget__DataPlotWidget": { 499 | "keys": { 500 | "dock_widget_title": { 501 | "repr": "'MatPlot'", 502 | "type": "repr" 503 | }, 504 | "dockable": { 505 | "repr": "True", 506 | "type": "repr" 507 | }, 508 | "parent": { 509 | "repr": "None", 510 | "type": "repr" 511 | } 512 | }, 513 | "groups": {} 514 | }, 515 | "plugin": { 516 | "keys": { 517 | "autoscroll": { 518 | "repr": "True", 519 | "type": "repr" 520 | }, 521 | "plot_type": { 522 | "repr": "1", 523 | "type": "repr" 524 | }, 525 | "topics": { 526 | "repr": "['/battery/status/voltage', '/battery/status/charge', '/battery/status/temperature']", 527 | "type": "repr" 528 | }, 529 | "x_limits": { 530 | "repr": "[-407.3181882379339, 18.490999999999985]", 531 | "type": "repr" 532 | }, 533 | "y_limits": { 534 | "repr": "[-3.1894767741205556, 27.326295110492115]", 535 | "type": "repr" 536 | } 537 | }, 538 | "groups": {} 539 | } 540 | } 541 | }, 542 | "plugin__rqt_plot__Plot__2": { 543 | "keys": {}, 544 | "groups": { 545 | "dock_widget__DataPlotWidget": { 546 | "keys": { 547 | "dock_widget_title": { 548 | "repr": "'MatPlot (2)'", 549 | "type": "repr" 550 | }, 551 | "dockable": { 552 | "repr": "'true'", 553 | "type": "repr" 554 | }, 555 | "parent": { 556 | "repr": "None", 557 | "type": "repr" 558 | } 559 | }, 560 | "groups": {} 561 | }, 562 | "plugin": { 563 | "keys": { 564 | "autoscroll": { 565 | "repr": "'true'", 566 | "type": "repr" 567 | }, 568 | "plot_type": { 569 | "repr": "'1'", 570 | "type": "repr" 571 | }, 572 | "topics": { 573 | "repr": "['/lipo_battery/status/voltage', '/lipo_battery/status/charge', '/lipo_battery/status/capacity', '/lipo_battery/status/design_capacity']", 574 | "type": "repr" 575 | }, 576 | "x_limits": { 577 | "repr": "['-142.30525900389586', '35.278000000000006']", 578 | "type": "repr" 579 | }, 580 | "y_limits": { 581 | "repr": "['-29.720795323590018', '1']", 582 | "type": "repr" 583 | } 584 | }, 585 | "groups": {} 586 | } 587 | } 588 | }, 589 | "plugin__rqt_plot__Plot__3": { 590 | "keys": {}, 591 | "groups": { 592 | "dock_widget__DataPlotWidget": { 593 | "keys": { 594 | "dock_widget_title": { 595 | "repr": "'MatPlot (3)'", 596 | "type": "repr" 597 | }, 598 | "dockable": { 599 | "repr": "'true'", 600 | "type": "repr" 601 | }, 602 | "parent": { 603 | "repr": "None", 604 | "type": "repr" 605 | } 606 | }, 607 | "groups": {} 608 | }, 609 | "plugin": { 610 | "keys": { 611 | "autoscroll": { 612 | "repr": "'true'", 613 | "type": "repr" 614 | }, 615 | "plot_type": { 616 | "repr": "'1'", 617 | "type": "repr" 618 | }, 619 | "topics": { 620 | "repr": "'/battery/voltage/data'", 621 | "type": "repr" 622 | }, 623 | "x_limits": { 624 | "repr": "['163.55380871264225', '182.5345947961397']", 625 | "type": "repr" 626 | }, 627 | "y_limits": { 628 | "repr": "['18.10967426621898', '25.941047642807977']", 629 | "type": "repr" 630 | } 631 | }, 632 | "groups": {} 633 | } 634 | } 635 | }, 636 | "plugin__rqt_publisher__Publisher__1": { 637 | "keys": {}, 638 | "groups": { 639 | "dock_widget__PublisherWidget": { 640 | "keys": { 641 | "dock_widget_title": { 642 | "repr": "'Message Publisher'", 643 | "type": "repr" 644 | }, 645 | "dockable": { 646 | "repr": "True", 647 | "type": "repr" 648 | }, 649 | "parent": { 650 | "repr": "None", 651 | "type": "repr" 652 | } 653 | }, 654 | "groups": {} 655 | }, 656 | "plugin": { 657 | "keys": { 658 | "publishers": { 659 | "repr": "\"[{'topic_name': '/battery/consumer/0', 'type_name': 'std_msgs/Float32', 'rate': 1.0, 'enabled': False, 'publisher_id': 0, 'counter': 0, 'expressions': {'/battery/consumer/0/data': '50'}}, {'topic_name': '/battery/consumer/1', 'type_name': 'std_msgs/Float32', 'rate': 1.0, 'enabled': False, 'publisher_id': 1, 'counter': 0, 'expressions': {'/battery/consumer/1/data': '500'}}]\"", 660 | "type": "repr" 661 | } 662 | }, 663 | "groups": {} 664 | } 665 | } 666 | }, 667 | "plugin__rqt_reconfigure__Param__1": { 668 | "keys": {}, 669 | "groups": { 670 | "dock_widget___plugincontainer_top_widget": { 671 | "keys": { 672 | "dock_widget_title": { 673 | "repr": "'Dynamic Reconfigure'", 674 | "type": "repr" 675 | }, 676 | "dockable": { 677 | "repr": "'true'", 678 | "type": "repr" 679 | }, 680 | "parent": { 681 | "repr": "None", 682 | "type": "repr" 683 | } 684 | }, 685 | "groups": {} 686 | }, 687 | "plugin": { 688 | "keys": { 689 | "_splitter": { 690 | "repr(QByteArray.hex)": "QtCore.QByteArray(b'000000ff0000000100000002000001c1000000000100000009010000000200')", 691 | "type": "repr(QByteArray.hex)", 692 | "pretty-print": " " 693 | }, 694 | "expanded_nodes": { 695 | "repr": "None", 696 | "type": "repr" 697 | }, 698 | "selected_nodes": { 699 | "repr": "['/left_motor', '/right_motor']", 700 | "type": "repr" 701 | }, 702 | "splitter": { 703 | "repr(QByteArray.hex)": "QtCore.QByteArray(b'000000ff0000000100000002000000df000003b801ffffffff010000000100')", 704 | "type": "repr(QByteArray.hex)", 705 | "pretty-print": " " 706 | }, 707 | "text": { 708 | "repr": "''", 709 | "type": "repr" 710 | } 711 | }, 712 | "groups": {} 713 | } 714 | } 715 | }, 716 | "plugin__rqt_robot_steering__RobotSteering__1": { 717 | "keys": {}, 718 | "groups": { 719 | "dock_widget__RobotSteeringUi": { 720 | "keys": { 721 | "dock_widget_title": { 722 | "repr": "'Robot Steering'", 723 | "type": "repr" 724 | }, 725 | "dockable": { 726 | "repr": "'true'", 727 | "type": "repr" 728 | }, 729 | "parent": { 730 | "repr": "None", 731 | "type": "repr" 732 | } 733 | }, 734 | "groups": {} 735 | }, 736 | "plugin": { 737 | "keys": { 738 | "topic": { 739 | "repr": "'/cmd_vel'", 740 | "type": "repr" 741 | }, 742 | "vw_max": { 743 | "repr": "'3'", 744 | "type": "repr" 745 | }, 746 | "vw_min": { 747 | "repr": "'-3'", 748 | "type": "repr" 749 | }, 750 | "vx_max": { 751 | "repr": "'1'", 752 | "type": "repr" 753 | }, 754 | "vx_min": { 755 | "repr": "'-1'", 756 | "type": "repr" 757 | } 758 | }, 759 | "groups": {} 760 | } 761 | } 762 | }, 763 | "plugin__rqt_service_caller__ServiceCaller__1": { 764 | "keys": {}, 765 | "groups": { 766 | "dock_widget__ServiceCallerWidget": { 767 | "keys": { 768 | "dock_widget_title": { 769 | "repr": "'Service Caller'", 770 | "type": "repr" 771 | }, 772 | "dockable": { 773 | "repr": "True", 774 | "type": "repr" 775 | }, 776 | "parent": { 777 | "repr": "None", 778 | "type": "repr" 779 | } 780 | }, 781 | "groups": {} 782 | }, 783 | "plugin": { 784 | "keys": { 785 | "current_service_name": { 786 | "repr": "'/battery/set_temperature'", 787 | "type": "repr" 788 | }, 789 | "splitter_orientation": { 790 | "repr": "2", 791 | "type": "repr" 792 | } 793 | }, 794 | "groups": {} 795 | } 796 | } 797 | }, 798 | "plugin__rqt_tf_tree__RosTfTree__1": { 799 | "keys": {}, 800 | "groups": { 801 | "dock_widget__RosTfTreeUi": { 802 | "keys": { 803 | "dock_widget_title": { 804 | "repr": "'TF Tree'", 805 | "type": "repr" 806 | }, 807 | "dockable": { 808 | "repr": "'true'", 809 | "type": "repr" 810 | }, 811 | "parent": { 812 | "repr": "None", 813 | "type": "repr" 814 | } 815 | }, 816 | "groups": {} 817 | }, 818 | "plugin": { 819 | "keys": { 820 | "auto_fit_graph_check_box_state": { 821 | "repr": "'true'", 822 | "type": "repr" 823 | }, 824 | "highlight_connections_check_box_state": { 825 | "repr": "'true'", 826 | "type": "repr" 827 | } 828 | }, 829 | "groups": {} 830 | } 831 | } 832 | }, 833 | "plugin__rqt_topic__TopicPlugin__1": { 834 | "keys": {}, 835 | "groups": { 836 | "dock_widget__TopicWidget": { 837 | "keys": { 838 | "dock_widget_title": { 839 | "repr": "'Topic Monitor'", 840 | "type": "repr" 841 | }, 842 | "dockable": { 843 | "repr": "'true'", 844 | "type": "repr" 845 | }, 846 | "parent": { 847 | "repr": "None", 848 | "type": "repr" 849 | } 850 | }, 851 | "groups": {} 852 | }, 853 | "plugin": { 854 | "keys": { 855 | "tree_widget_header_state": { 856 | "repr(QByteArray.hex)": "QtCore.QByteArray(b'000000ff000000000000000100000000000000000100000000000000000000000000000000000002d4000000050101000100000000000000000500000064ffffffff000000810000000300000005000000ef0000000100000003000000f200000001000000030000005d0000000100000003000000320000000100000003000000640000000100000003000003e80000000064')", 857 | "type": "repr(QByteArray.hex)", 858 | "pretty-print": " d ] 2 d " 859 | } 860 | }, 861 | "groups": {} 862 | } 863 | } 864 | }, 865 | "plugin__rqt_virtual_joy__My Plugin__1": { 866 | "keys": {}, 867 | "groups": { 868 | "dock_widget__virtualJoyPluginUi": { 869 | "keys": { 870 | "dock_widget_title": { 871 | "repr": "'Virtual Joystick'", 872 | "type": "repr" 873 | }, 874 | "dockable": { 875 | "repr": "'false'", 876 | "type": "repr" 877 | }, 878 | "parent": { 879 | "repr": "None", 880 | "type": "repr" 881 | } 882 | }, 883 | "groups": {} 884 | } 885 | } 886 | } 887 | } 888 | } 889 | } 890 | } --------------------------------------------------------------------------------