diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb
index 373794b2..48f1ac79 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb
@@ -36,6 +36,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
wheelSlip = ""
trackControllers = ""
trackLinks = ""
+ power_draining_topics = ""
for track in tracks
if useWheels
@@ -61,6 +62,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
HEREDOC
trackLinks += "<#{track}_track>#{track}_track#{track}_track>"
+ power_draining_topics += "/model/#{_name}/link/#{track}_track/track_cmd_vel"
end
for flipper in flippersOfTrack[track]
if useWheels
@@ -86,6 +88,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
HEREDOC
trackLinks += "<#{track}_track>#{flipper}_flipper#{track}_track>"
+ power_draining_topics += "/model/#{_name}/link/#{flipper}_flipper/track_cmd_vel"
end
end
end
@@ -177,6 +180,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
1.9499
4.95
true
+ #{power_draining_topics}
0
for wheel_num in 1..num_wheels
# we only want odometry from the first diffdrive
@@ -71,6 +72,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
HEREDOC
trackLinks += "<#{track}_track>#{flipper}_flipper#{track}_track>"
+ power_draining_topics += "/model/#{_name}/link/#{flipper}_flipper/track_cmd_vel"
end
end
trackedVehicle += <<-HEREDOC
@@ -131,6 +133,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
1.9499
9.9
true
+ #{power_draining_topics}