├── 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