diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/config/common.yaml b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/config/common.yaml
index 18777307..bec5074d 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/config/common.yaml
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/config/common.yaml
@@ -1,5 +1,8 @@
revision: 2014 # 2014 for TRADR robot, 2021 for upgraded robot
+wheels_instead_of_tracks: False
+track_mu: 10
+
big_collision_box_on_top: False
big_collision_box_height: 0.5
big_collision_box_width: 0.5
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 c4544cbf..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
@@ -1,4 +1,16 @@
def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _additionalSDF, _max_velocity=0.4, _max_acceleration=3)
+ # read robot configuration from the config/ dir to access robot geometry information
+ require 'yaml'
+ confdir = File.join(__dir__, '..', 'config')
+ config_yamls = [ File.join(confdir, 'common.yaml'), File.join(confdir, 'sdf.yaml') ]
+ config = Hash.new
+ for config_yaml in config_yamls
+ conf = YAML.load_file(config_yaml)
+ config.merge!(conf)
+ end
+
+ useWheels = config["wheels_instead_of_tracks"]
+
numTrackWheels = 8
numFlipperWheels = 5
@@ -22,53 +34,109 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
diffdriveJoints[i] = ""
end
wheelSlip = ""
+ trackControllers = ""
+ trackLinks = ""
+ power_draining_topics = ""
for track in tracks
- for wheel in 1..numTrackWheels
- diffdriveJoints[0] += "<#{track}_joint>#{track}_track_wheel#{wheel}_j#{track}_joint>\n"
- wheelSlip += <<-HEREDOC
-
- #{slipCompliance}
- 0
- #{wheelNormalForce}
- #{wheelRadiuses[0]}
-
- HEREDOC
+ if useWheels
+ for wheel in 1..numTrackWheels
+ diffdriveJoints[0] += "<#{track}_joint>#{track}_track_wheel#{wheel}_j#{track}_joint>\n"
+ wheelSlip += <<-HEREDOC
+
+ #{slipCompliance}
+ 0
+ #{wheelNormalForce}
+ #{wheelRadiuses[0]}
+
+ HEREDOC
+ end
+ else
+ trackControllers += <<-HEREDOC
+
+ #{track}_track
+ -#{_max_velocity}
+ #{_max_velocity}
+ -#{_max_acceleration}
+ #{_max_acceleration}
+
+ 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]
- for wheel in 1..numFlipperWheels
- diffdriveJoints[wheel-1] += "<#{track}_joint>#{flipper}_flipper_wheel#{wheel}_j#{track}_joint>\n"
- wheelSlip += <<-HEREDOC
-
- #{slipCompliance}
- 0
- #{wheelNormalForce}
- #{wheelRadiuses[wheel-1]}
-
+ if useWheels
+ for wheel in 1..numFlipperWheels
+ diffdriveJoints[wheel-1] += "<#{track}_joint>#{flipper}_flipper_wheel#{wheel}_j#{track}_joint>\n"
+ wheelSlip += <<-HEREDOC
+
+ #{slipCompliance}
+ 0
+ #{wheelNormalForce}
+ #{wheelRadiuses[wheel-1]}
+
+ HEREDOC
+ end
+ else
+ trackControllers += <<-HEREDOC
+
+ #{flipper}_flipper
+ -#{_max_velocity}
+ #{_max_velocity}
+ -#{_max_acceleration}
+ #{_max_acceleration}
+
HEREDOC
+ trackLinks += "<#{track}_track>#{flipper}_flipper#{track}_track>"
+ power_draining_topics += "/model/#{_name}/link/#{flipper}_flipper/track_cmd_vel"
end
end
end
diffDrive = ""
- for wheel in 0...numFlipperWheels
- # we only want odometry from the first diffdrive
- no_odom = ""
- if wheel > 0
- no_odom = "unused_odom\n"
- end
- diffDrive += <<-HEREDOC
-
- #{diffdriveJoints[wheel]}
- #{wheelSeparation}
- #{wheelRadiuses[wheel]}
- /model/#{_name}/cmd_vel_relay
- -#{_max_velocity}
- #{_max_velocity}
- -#{_max_acceleration}
- #{_max_acceleration}
- #{no_odom}
-
+ trackedVehicle = ""
+ wheelSlipPlugin = ""
+ if useWheels
+ for wheel in 0...numFlipperWheels
+ # we only want odometry from the first diffdrive
+ no_odom = ""
+ if wheel > 0
+ no_odom = "unused_odom\n"
+ end
+ diffDrive += <<-HEREDOC
+
+ #{diffdriveJoints[wheel]}
+ #{wheelSeparation}
+ #{wheelRadiuses[wheel]}
+ /model/#{_name}/cmd_vel_relay
+ -#{_max_velocity}
+ #{_max_velocity}
+ -#{_max_acceleration}
+ #{_max_acceleration}
+ #{no_odom}
+
+ HEREDOC
+ end
+ wheelSlipPlugin = <<-HEREDOC
+
+ #{wheelSlip}
+
+ HEREDOC
+ else
+ trackedVehicle += <<-HEREDOC
+
+ #{trackLinks}
+ #{wheelSeparation}
+ 0.18094
+ 0.5
+ /model/#{_name}/cmd_vel_relay
+
+ -#{_max_velocity}
+ #{_max_velocity}
+ -#{_max_acceleration}
+ #{_max_acceleration}
+
+
HEREDOC
end
@@ -85,6 +153,8 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
#{_modelURI}
#{diffDrive}
+ #{trackedVehicle}
+ #{trackControllers}
@@ -110,6 +180,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
1.9499
4.95
true
+ #{power_draining_topics}
gas
-
- #{wheelSlip}
-
+ #{wheelSlipPlugin}
#{_additionalSDF}
diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/model.sdf b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/model.sdf
index e0ed7dab..3bff28f4 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/model.sdf
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/model.sdf
@@ -407,7 +407,6 @@
1
50
- 0
@@ -478,6 +477,7 @@
+ 0
0 0 0.15 -3.1415926535897931 -0 0
@@ -850,26 +850,64 @@
0 0.1985 0 0 -0 0
- 1e-05
+ 0 0 0.0141 0 -0 0
+ 6.06
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.002731
+ 0
+ 0
+ 0.032554
+ 1.5e-05
+ 0.031391
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
- 0.01 0.01 0.01
+ 0.097 0.178 0.5
- 0.7
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 -0.015 0.01855 1.5707963267948966 -0 0
+
+
+ 0.112
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
+
+
+ 0.097
+ 0.089
+
+
+
+
+
+ 10
150
0 0 1
@@ -921,26 +959,98 @@
0.25 0.272 0.0195 0 0.193732 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 0.75
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.33 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.029
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 0.0325 0 0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 -0.0325 0 -0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.166 0 0.004 0 -0.02 0
- 0.01 0.01 0.01
+ 0.2 0.04981 0.07
- 0.7
+ 10
150
0 0 1
@@ -984,11 +1094,11 @@
-
- 0.25 0.272 0.0195 0 0.193732 0
+
+ -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
0.08 0 0 0 -0 0
- 0.15
+ 0.75
0.0017491
2.8512e-07
@@ -998,7 +1108,7 @@
0.010941
-
+
0 0 0 1.5707963267948966 -0 0
@@ -1007,146 +1117,103 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel1
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 0.272 0.003617 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.33 0 0 1.5707963267948966 -0 0
0.04981
- 0.074
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ 0.165 0 0.0325 0 0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 0.272 -0.012266 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 -0.0325 0 -0.184162 0
-
- 0.04981
- 0.059
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ 0.166 0 0.004 0 -0.02 0
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 1.5707963267948966
+
+
+ meshes/flipper.dae
+
+
+
-
- front_left_flipper_wheel3
- front_left_flipper
+
+ rear_left_flipper
+ left_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -1154,251 +1221,68 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- 0.49287 0.272 -0.028149 0 0.193732 0
+
+ 0 -0.1985 0 0 -0 0
- 0.08 0 0 0 -0 0
- 0.15
+ 0 0 0.0141 0 -0 0
+ 6.06
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 0.002731
+ 0
+ 0
+ 0.032554
+ 1.5e-05
+ 0.031391
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
-
- 0.04981
- 0.044
-
+
+ 0.097 0.178 0.5
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ 0.25 0.015 0.01855 1.5707963267948966 -0 0
+
+
+ 0.112
+ 0.089
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 0.272 -0.044032 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_left_flipper_wheel5
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 -0.015 0 1.5707963267948966 -0 0
-
-
- 0.112
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel1
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel2
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.107143 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
0.097
@@ -1406,89 +1290,34 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- left_track_wheel3
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
-
- 0.097
- 0.089
-
+
+ meshes/bogie.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
-
- left_track_wheel4
- left_track
+
+ right_track
+ base_link
0 1 0
- -1e+16
- 1e+16
+ 0
+ 0
+ 0
+ 4
0
@@ -1496,1636 +1325,142 @@
0
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ 1
+ 0
+ 0.95
+
+
-
- -0.035714 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel5
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.107143 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel6
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel7
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel8
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 1.5707963267948966
-
-
- meshes/flipper.dae
-
-
-
-
-
- rear_left_flipper
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 0.272 0.003617 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 0.272 -0.012266 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.49287 0.272 -0.028149 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.573827 0.272 -0.044032 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0 -0.1985 0 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
-
-
- meshes/bogie.dae
-
-
-
-
-
- right_track
- base_link
-
- 0 1 0
-
- 0
- 0
- 0
- 4
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 1
- 0
- 0.95
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
-
-
- meshes/flipper.dae
-
-
-
-
-
- front_right_flipper
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel1
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 -0.272 0.003617 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 -0.272 -0.012266 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 -0.272 -0.028149 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 -0.272 -0.044032 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel5
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.272 0.0195 0 -0.193732 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
-
-
- meshes/flipper.dae
-
-
-
-
-
- rear_right_flipper
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.25 -0.272 0.0195 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel1
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 -0.272 0.003617 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel2
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 -0.272 -0.012266 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel3
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.49287 -0.272 -0.028149 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.573827 -0.272 -0.044032 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel5
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.25 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0.015 0 1.5707963267948966 -0 0
-
-
- 0.112
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- right_track_wheel1
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- right_track_wheel2
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.107143 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+
+ 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
+
+ -0.08 0 0 0 -0 0
+ 0.75
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel3
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel4
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ meshes/flipper.dae
+
+
+
-
- right_track_wheel5
+
+ front_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3133,170 +1468,137 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 -0.1985 0.01855 0 -0 0
+
+ -0.25 -0.272 0.0195 0 -0.193732 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ -0.08 0 0 0 -0 0
+ 0.75
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel6
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel7
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ meshes/flipper.dae
+
+
+
-
- right_track_wheel8
+
+ rear_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3304,6 +1606,16 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
front_left_flipper_j
diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/nifti_robot.xacro b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/nifti_robot.xacro
index 5bd60a65..c192b192 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/nifti_robot.xacro
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/nifti_robot.xacro
@@ -2,12 +2,12 @@
-
+
-
+
-
+
@@ -317,8 +317,9 @@
-
+
+
@@ -357,7 +358,7 @@
-
+
@@ -946,13 +947,45 @@
-
-
+
+
+
+
+
+
+
+
+
+
+
+
-
+
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -966,15 +999,17 @@
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
@@ -983,10 +1018,10 @@
-
+
-
+
@@ -994,7 +1029,7 @@
-
+
@@ -1012,7 +1047,7 @@
-
+
@@ -1045,13 +1080,57 @@
filename="package://ctu_cras_norlab_absolem_sensor_config_1/meshes/flipper.dae"/>
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
-
+
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -1074,12 +1153,14 @@
-
-
-
-
-
-
+
+
+
+
+
+
+
+
@@ -1088,7 +1169,7 @@
-
+
@@ -1279,7 +1360,7 @@
-
+
@@ -1418,7 +1499,7 @@
1.618994
-
+
@@ -1428,7 +1509,7 @@
rear_left_flipper_j
rear_right_flipper_j
-
+
laser_j
@@ -1539,22 +1620,24 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -1562,26 +1645,28 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
@@ -1922,6 +2007,7 @@
1
50
+ 0
diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_3/model.sdf b/submitted_models/ctu_cras_norlab_absolem_sensor_config_3/model.sdf
index 980b893f..cfec35a1 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_3/model.sdf
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_3/model.sdf
@@ -352,7 +352,6 @@
1
50
- 0
@@ -423,6 +422,7 @@
+ 0
0 0 0.15 -3.1415926535897931 -0 0
@@ -664,26 +664,64 @@
0 0.1985 0 0 -0 0
- 1e-05
+ 0 0 0.0141 0 -0 0
+ 6.06
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.002731
+ 0
+ 0
+ 0.032554
+ 1.5e-05
+ 0.031391
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
- 0.01 0.01 0.01
+ 0.097 0.178 0.5
- 0.7
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 -0.015 0.01855 1.5707963267948966 -0 0
+
+
+ 0.112
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
+
+
+ 0.097
+ 0.089
+
+
+
+
+
+ 10
150
0 0 1
@@ -735,26 +773,98 @@
0.25 0.272 0.0195 0 0.193732 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 0.75
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.33 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.029
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 0.0325 0 0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 -0.0325 0 -0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.166 0 0.004 0 -0.02 0
- 0.01 0.01 0.01
+ 0.2 0.04981 0.07
- 0.7
+ 10
150
0 0 1
@@ -798,11 +908,11 @@
-
- 0.25 0.272 0.0195 0 0.193732 0
+
+ -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
0.08 0 0 0 -0 0
- 0.15
+ 0.75
0.0017491
2.8512e-07
@@ -812,7 +922,7 @@
0.010941
-
+
0 0 0 1.5707963267948966 -0 0
@@ -821,317 +931,103 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel1
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 0.272 0.003617 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.33 0 0 1.5707963267948966 -0 0
0.04981
- 0.074
+ 0.029
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 0.272 -0.012266 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 0.0325 0 0.184162 0
-
- 0.04981
- 0.059
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 0.272 -0.028149 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 -0.0325 0 -0.184162 0
-
- 0.04981
- 0.044
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 0.272 -0.044032 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.166 0 0.004 0 -0.02 0
-
- 0.04981
- 0.029
-
+
+ 0.2 0.04981 0.07
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- front_left_flipper_wheel5
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 -0.015 0 1.5707963267948966 -0 0
-
-
- 0.112
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel1
- left_track
+
+ rear_left_flipper
+ left_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -1139,1669 +1035,182 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- 0.178571 0.1985 0.01855 0 -0 0
+
+ 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.097
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- left_track_wheel2
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.107143 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
-
- 0.097
- 0.089
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- left_track_wheel3
- left_track
+
+ cliff_sensor_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- 0.035714 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel4
- left_track
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.035714 0.1985 0.01855 0 -0 0
+
+ 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel5
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.107143 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel6
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel7
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel8
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- rear_left_flipper
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 0.272 0.003617 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 0.272 -0.012266 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.49287 0.272 -0.028149 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.573827 0.272 -0.044032 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.1615 0 0.39 0 0.25 0
-
- 0 0 0.03675 0 -0 0
- 0.5
-
- 0.000461625
- 0
- 0
- 0.000461625
- 0
- 0.000473063
-
-
-
- 0 0 0.03675 0 -0 0
-
-
- 0.0735
- 0.0435
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
-
-
-
-
- 0 0 0.035925 0 -0 0
- 10
- 0
- 1
-
-
-
- 2048
- 1
- -3.1459
- 3.1459
-
-
- 128
- 1
- -0.785398
- 0.785398
-
-
-
- 0.1
- 50
- 0.01
-
-
- gaussian
- 0
- 0.01
-
-
-
-
-
- laser
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 -0.1985 0 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
-
-
-
-
-
- right_track
- base_link
-
- 0 1 0
-
- 0
- 0
- 0
- 4
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 1
- 0
- 0.95
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- front_right_flipper
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel1
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 -0.272 0.003617 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 -0.272 -0.012266 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 -0.272 -0.028149 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 -0.272 -0.044032 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel5
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.272 0.0195 0 -0.193732 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 7.8325e-07
+ 0
+ 1.666e-06
-
+
+ 0.0105 0 0.00925 0 -0 0
- 0.01 0.01 0.01
+ 0.021 0.035 0.0185
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper
- right_track
+
+ cliff_sensor_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -2809,296 +1218,270 @@
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper_wheel1
- rear_right_flipper
+
+ cliff_sensor_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.330957 -0.272 0.003617 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel2
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.411913 -0.272 -0.012266 0 -0.193732 0
+
+ -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.04981
- 0.059
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
+
+ cliff_sensor_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.49287 -0.272 -0.028149 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.573827 -0.272 -0.044032 0 -0.193732 0
+
+ 0.1615 0 0.39 0 0.25 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0 0 0.03675 0 -0 0
+ 0.5
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 0.000461625
+ 0
+ 0
+ 0.000461625
+ 0
+ 0.000473063
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.03675 0 -0 0
- 0.04981
- 0.029
+ 0.0735
+ 0.0435
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
+
+
+
+
+ 0 0 0.035925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 2048
+ 1
+ -3.1459
+ 3.1459
+
+
+ 128
+ 1
+ -0.785398
+ 0.785398
+
+
+
+ 0.1
+ 50
+ 0.01
+
+
+ gaussian
+ 0
+ 0.01
+
+
+
-
- rear_right_flipper_wheel5
- rear_right_flipper
+
+ laser
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.25 -0.1985 0.01855 0 -0 0
+
+ 0 -0.1985 0 0 -0 0
0 0 0.0141 0 -0 0
- 0.7575
+ 6.06
0.002731
0
@@ -3108,8 +1491,25 @@
0.031391
-
- 0 0.015 0 1.5707963267948966 -0 0
+
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
+
+
+ 0.097 0.178 0.5
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 0.015 0.01855 1.5707963267948966 -0 0
0.112
@@ -3117,56 +1517,17 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel1
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
0.097
@@ -3174,32 +1535,34 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
+
+
+
-
- right_track_wheel2
- right_track
+
+ right_track
+ base_link
0 1 0
- -1e+16
- 1e+16
+ 0
+ 0
+ 0
+ 4
0
@@ -3207,170 +1570,142 @@
0
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ 1
+ 0
+ 0.95
+
+
-
- 0.107143 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+
+ 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
+
+ -0.08 0 0 0 -0 0
+ 0.75
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel3
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel4
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel5
+
+ front_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3378,170 +1713,137 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 -0.1985 0.01855 0 -0 0
+
+ -0.25 -0.272 0.0195 0 -0.193732 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ -0.08 0 0 0 -0 0
+ 0.75
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel6
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel7
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel8
+
+ rear_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3549,6 +1851,16 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
front_left_flipper_j
diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_4/model.sdf b/submitted_models/ctu_cras_norlab_absolem_sensor_config_4/model.sdf
index 322a20ea..6596307f 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_4/model.sdf
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_4/model.sdf
@@ -368,7 +368,6 @@
1
50
- 0
@@ -439,6 +438,7 @@
+ 0
0 0 0.15 -3.1415926535897931 -0 0
@@ -680,26 +680,64 @@
0 0.1985 0 0 -0 0
- 1e-05
+ 0 0 0.0141 0 -0 0
+ 6.06
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.002731
+ 0
+ 0
+ 0.032554
+ 1.5e-05
+ 0.031391
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
- 0.01 0.01 0.01
+ 0.097 0.178 0.5
- 0.7
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 -0.015 0.01855 1.5707963267948966 -0 0
+
+
+ 0.112
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
+
+
+ 0.097
+ 0.089
+
+
+
+
+
+ 10
150
0 0 1
@@ -751,26 +789,98 @@
0.25 0.272 0.0195 0 0.193732 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 0.75
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.33 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.029
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 0.0325 0 0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 -0.0325 0 -0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.166 0 0.004 0 -0.02 0
- 0.01 0.01 0.01
+ 0.2 0.04981 0.07
- 0.7
+ 10
150
0 0 1
@@ -814,11 +924,11 @@
-
- 0.25 0.272 0.0195 0 0.193732 0
+
+ -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
0.08 0 0 0 -0 0
- 0.15
+ 0.75
0.0017491
2.8512e-07
@@ -828,7 +938,7 @@
0.010941
-
+
0 0 0 1.5707963267948966 -0 0
@@ -837,317 +947,103 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel1
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 0.272 0.003617 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.33 0 0 1.5707963267948966 -0 0
0.04981
- 0.074
+ 0.029
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 0.272 -0.012266 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 0.0325 0 0.184162 0
-
- 0.04981
- 0.059
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 0.272 -0.028149 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 -0.0325 0 -0.184162 0
-
- 0.04981
- 0.044
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 0.272 -0.044032 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.166 0 0.004 0 -0.02 0
-
- 0.04981
- 0.029
-
+
+ 0.2 0.04981 0.07
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- front_left_flipper_wheel5
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 -0.015 0 1.5707963267948966 -0 0
-
-
- 0.112
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel1
- left_track
+
+ rear_left_flipper
+ left_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -1155,1669 +1051,182 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- 0.178571 0.1985 0.01855 0 -0 0
+
+ 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.097
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- left_track_wheel2
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.107143 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
-
- 0.097
- 0.089
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- left_track_wheel3
- left_track
+
+ cliff_sensor_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- 0.035714 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel4
- left_track
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.035714 0.1985 0.01855 0 -0 0
+
+ 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel5
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.107143 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel6
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel7
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel8
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- rear_left_flipper
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 0.272 0.003617 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 0.272 -0.012266 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.49287 0.272 -0.028149 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.573827 0.272 -0.044032 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.1615 0 0.39 0 0.25 0
-
- 0 0 0.03675 0 -0 0
- 0.5
-
- 0.000461625
- 0
- 0
- 0.000461625
- 0
- 0.000473063
-
-
-
- 0 0 0.03675 0 -0 0
-
-
- 0.0735
- 0.0435
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
-
-
-
-
- 0 0 0.035925 0 -0 0
- 10
- 0
- 1
-
-
-
- 2048
- 1
- -3.1459
- 3.1459
-
-
- 128
- 1
- -0.785398
- 0.785398
-
-
-
- 0.1
- 50
- 0.01
-
-
- gaussian
- 0
- 0.01
-
-
-
-
-
- laser
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 -0.1985 0 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
-
-
-
-
-
- right_track
- base_link
-
- 0 1 0
-
- 0
- 0
- 0
- 4
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 1
- 0
- 0.95
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- front_right_flipper
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel1
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 -0.272 0.003617 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 -0.272 -0.012266 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 -0.272 -0.028149 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 -0.272 -0.044032 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel5
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.272 0.0195 0 -0.193732 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 7.8325e-07
+ 0
+ 1.666e-06
-
+
+ 0.0105 0 0.00925 0 -0 0
- 0.01 0.01 0.01
+ 0.021 0.035 0.0185
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper
- right_track
+
+ cliff_sensor_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -2825,296 +1234,270 @@
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper_wheel1
- rear_right_flipper
+
+ cliff_sensor_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.330957 -0.272 0.003617 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel2
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.411913 -0.272 -0.012266 0 -0.193732 0
+
+ -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.04981
- 0.059
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
+
+ cliff_sensor_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.49287 -0.272 -0.028149 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.573827 -0.272 -0.044032 0 -0.193732 0
+
+ 0.1615 0 0.39 0 0.25 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0 0 0.03675 0 -0 0
+ 0.5
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 0.000461625
+ 0
+ 0
+ 0.000461625
+ 0
+ 0.000473063
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.03675 0 -0 0
- 0.04981
- 0.029
+ 0.0735
+ 0.0435
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
+
+
+
+
+ 0 0 0.035925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 2048
+ 1
+ -3.1459
+ 3.1459
+
+
+ 128
+ 1
+ -0.785398
+ 0.785398
+
+
+
+ 0.1
+ 50
+ 0.01
+
+
+ gaussian
+ 0
+ 0.01
+
+
+
-
- rear_right_flipper_wheel5
- rear_right_flipper
+
+ laser
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.25 -0.1985 0.01855 0 -0 0
+
+ 0 -0.1985 0 0 -0 0
0 0 0.0141 0 -0 0
- 0.7575
+ 6.06
0.002731
0
@@ -3124,8 +1507,25 @@
0.031391
-
- 0 0.015 0 1.5707963267948966 -0 0
+
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
+
+
+ 0.097 0.178 0.5
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 0.015 0.01855 1.5707963267948966 -0 0
0.112
@@ -3133,56 +1533,17 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel1
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
0.097
@@ -3190,32 +1551,34 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
+
+
+
-
- right_track_wheel2
- right_track
+
+ right_track
+ base_link
0 1 0
- -1e+16
- 1e+16
+ 0
+ 0
+ 0
+ 4
0
@@ -3223,170 +1586,142 @@
0
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ 1
+ 0
+ 0.95
+
+
-
- 0.107143 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+
+ 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
+
+ -0.08 0 0 0 -0 0
+ 0.75
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel3
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel4
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel5
+
+ front_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3394,170 +1729,137 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 -0.1985 0.01855 0 -0 0
+
+ -0.25 -0.272 0.0195 0 -0.193732 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ -0.08 0 0 0 -0 0
+ 0.75
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel6
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel7
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel8
+
+ rear_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3565,6 +1867,16 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
front_left_flipper_j
diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_5/model.sdf b/submitted_models/ctu_cras_norlab_absolem_sensor_config_5/model.sdf
index ee777177..83b42d8c 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_5/model.sdf
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_5/model.sdf
@@ -368,7 +368,6 @@
1
50
- 0
@@ -439,6 +438,7 @@
+ 0
0 0 0.15 -3.1415926535897931 -0 0
@@ -680,26 +680,64 @@
0 0.1985 0 0 -0 0
- 1e-05
+ 0 0 0.0141 0 -0 0
+ 6.06
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.002731
+ 0
+ 0
+ 0.032554
+ 1.5e-05
+ 0.031391
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
- 0.01 0.01 0.01
+ 0.097 0.178 0.5
- 0.7
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 -0.015 0.01855 1.5707963267948966 -0 0
+
+
+ 0.112
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
+
+
+ 0.097
+ 0.089
+
+
+
+
+
+ 10
150
0 0 1
@@ -751,26 +789,98 @@
0.25 0.272 0.0195 0 0.193732 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 0.75
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.33 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.029
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 0.0325 0 0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 -0.0325 0 -0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.166 0 0.004 0 -0.02 0
- 0.01 0.01 0.01
+ 0.2 0.04981 0.07
- 0.7
+ 10
150
0 0 1
@@ -814,11 +924,11 @@
-
- 0.25 0.272 0.0195 0 0.193732 0
+
+ -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
0.08 0 0 0 -0 0
- 0.15
+ 0.75
0.0017491
2.8512e-07
@@ -828,7 +938,7 @@
0.010941
-
+
0 0 0 1.5707963267948966 -0 0
@@ -837,260 +947,103 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel1
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 0.272 0.003617 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.33 0 0 1.5707963267948966 -0 0
0.04981
- 0.074
+ 0.029
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 0.272 -0.012266 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 0.0325 0 0.184162 0
-
- 0.04981
- 0.059
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 0.272 -0.028149 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 -0.0325 0 -0.184162 0
-
- 0.04981
- 0.044
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 0.272 -0.044032 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.166 0 0.004 0 -0.02 0
-
- 0.04981
- 0.029
-
+
+ 0.2 0.04981 0.07
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- front_left_flipper_wheel5
- front_left_flipper
+
+ rear_left_flipper
+ left_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -1098,1815 +1051,268 @@
0
-
-
- 0.25 0.1985 0.01855 0 -0 0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
+
+
+ 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 -0.015 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.112
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- left_track_wheel1
- left_track
+
+ cliff_sensor_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- 0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel2
- left_track
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.107143 0.1985 0.01855 0 -0 0
+
+ 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.097
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- left_track_wheel3
- left_track
+
+ cliff_sensor_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.035714 0.1985 0.01855 0 -0 0
+
+ -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel4
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.035714 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel5
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.107143 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel6
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel7
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel8
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- rear_left_flipper
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 0.272 0.003617 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 0.272 -0.012266 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.49287 0.272 -0.028149 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.573827 0.272 -0.044032 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.225 -0.000465 0.185 0 -0 0
-
- 0.0155 0 0 0 -0 0
- 0.024
-
- 1.764e-06
- 0
- 0
- 4.58e-06
- 0
- 4.58e-06
-
-
-
- 0.0155 0 0 0 -0 0
-
-
- 0.043 0.021 0.021
-
-
-
-
- 0 0 0.0105 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flir_boson.dae
-
-
-
-
- 0.03 0 0 0 -0 0
- 1
- 8.6
- 0
-
- 1.6057
-
-
- 154.51
- 154.51
- 160.5
- 128.5
- 0
-
- stereographic
- 1
-
-
- 320
- 256
- L8
-
-
- 0.6
- 50
-
-
-
- 253.15
- 673.15
- 1.6
-
-
-
-
- thermocam
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.1615 0 0.39 0 0.25 0
-
- 0 0 0.03675 0 -0 0
- 0.5
-
- 0.000461625
- 0
- 0
- 0.000461625
- 0
- 0.000473063
-
-
-
- 0 0 0.03675 0 -0 0
-
-
- 0.0735
- 0.0435
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
-
-
-
-
- 0 0 0.035925 0 -0 0
- 10
- 0
- 1
-
-
-
- 2048
- 1
- -3.1459
- 3.1459
-
-
- 128
- 1
- -0.785398
- 0.785398
-
-
-
- 0.1
- 50
- 0.01
-
-
- gaussian
- 0
- 0.01
-
-
-
-
-
- laser
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 -0.1985 0 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
-
-
-
-
-
- right_track
- base_link
-
- 0 1 0
-
- 0
- 0
- 0
- 4
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 1
- 0
- 0.95
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- front_right_flipper
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel1
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 -0.272 0.003617 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 -0.272 -0.012266 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 -0.272 -0.028149 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 -0.272 -0.044032 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel5
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.272 0.0195 0 -0.193732 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
+
+ 0.0105 0 0.00925 0 -0 0
- 0.01 0.01 0.01
+ 0.021 0.035 0.0185
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper
- right_track
+
+ cliff_sensor_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -2914,296 +1320,273 @@
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper_wheel1
- rear_right_flipper
+
+ cliff_sensor_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.330957 -0.272 0.003617 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel2
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.411913 -0.272 -0.012266 0 -0.193732 0
+
+ 0.225 -0.000465 0.185 0 -0 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.0155 0 0 0 -0 0
+ 0.024
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.764e-06
+ 0
+ 0
+ 4.58e-06
+ 0
+ 4.58e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0155 0 0 0 -0 0
-
- 0.04981
- 0.059
-
+
+ 0.043 0.021 0.021
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0105 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flir_boson.dae
+
+
+
+
+ 0.03 0 0 0 -0 0
+ 1
+ 8.6
+ 0
+
+ 1.6057
+
+
+ 154.51
+ 154.51
+ 160.5
+ 128.5
+ 0
+
+ stereographic
+ 1
+
+
+ 320
+ 256
+ L8
+
+
+ 0.6
+ 50
+
+
+
+ 253.15
+ 673.15
+ 1.6
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
+
+ thermocam
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.49287 -0.272 -0.028149 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.573827 -0.272 -0.044032 0 -0.193732 0
+
+ 0.1615 0 0.39 0 0.25 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0 0 0.03675 0 -0 0
+ 0.5
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 0.000461625
+ 0
+ 0
+ 0.000461625
+ 0
+ 0.000473063
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.03675 0 -0 0
- 0.04981
- 0.029
+ 0.0735
+ 0.0435
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
+
+
+
+
+ 0 0 0.035925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 2048
+ 1
+ -3.1459
+ 3.1459
+
+
+ 128
+ 1
+ -0.785398
+ 0.785398
+
+
+
+ 0.1
+ 50
+ 0.01
+
+
+ gaussian
+ 0
+ 0.01
+
+
+
-
- rear_right_flipper_wheel5
- rear_right_flipper
+
+ laser
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.25 -0.1985 0.01855 0 -0 0
+
+ 0 -0.1985 0 0 -0 0
0 0 0.0141 0 -0 0
- 0.7575
+ 6.06
0.002731
0
@@ -3213,8 +1596,25 @@
0.031391
-
- 0 0.015 0 1.5707963267948966 -0 0
+
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
+
+
+ 0.097 0.178 0.5
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 0.015 0.01855 1.5707963267948966 -0 0
0.112
@@ -3222,56 +1622,17 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel1
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
0.097
@@ -3279,32 +1640,34 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
+
+
+
-
- right_track_wheel2
- right_track
+
+ right_track
+ base_link
0 1 0
- -1e+16
- 1e+16
+ 0
+ 0
+ 0
+ 4
0
@@ -3312,170 +1675,142 @@
0
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ 1
+ 0
+ 0.95
+
+
-
- 0.107143 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+
+ 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
+
+ -0.08 0 0 0 -0 0
+ 0.75
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel3
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel4
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel5
+
+ front_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3483,170 +1818,137 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 -0.1985 0.01855 0 -0 0
+
+ -0.25 -0.272 0.0195 0 -0.193732 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ -0.08 0 0 0 -0 0
+ 0.75
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel6
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel7
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel8
+
+ rear_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3654,6 +1956,16 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
front_left_flipper_j
diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_6/model.sdf b/submitted_models/ctu_cras_norlab_absolem_sensor_config_6/model.sdf
index 04921230..3d63a844 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_6/model.sdf
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_6/model.sdf
@@ -347,7 +347,6 @@
1
50
- 0
@@ -418,6 +417,7 @@
+ 0
0 0 0.15 -3.1415926535897931 -0 0
@@ -442,26 +442,64 @@
0 0.1985 0 0 -0 0
- 1e-05
+ 0 0 0.0141 0 -0 0
+ 6.06
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.002731
+ 0
+ 0
+ 0.032554
+ 1.5e-05
+ 0.031391
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
- 0.01 0.01 0.01
+ 0.097 0.178 0.5
- 0.7
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 -0.015 0.01855 1.5707963267948966 -0 0
+
+
+ 0.112
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
+
+
+ 0.097
+ 0.089
+
+
+
+
+
+ 10
150
0 0 1
@@ -513,26 +551,98 @@
0.25 0.272 0.0195 0 0.193732 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 0.75
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.33 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.029
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 0.0325 0 0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 -0.0325 0 -0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.166 0 0.004 0 -0.02 0
- 0.01 0.01 0.01
+ 0.2 0.04981 0.07
- 0.7
+ 10
150
0 0 1
@@ -576,11 +686,11 @@
-
- 0.25 0.272 0.0195 0 0.193732 0
+
+ -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
0.08 0 0 0 -0 0
- 0.15
+ 0.75
0.0017491
2.8512e-07
@@ -590,7 +700,7 @@
0.010941
-
+
0 0 0 1.5707963267948966 -0 0
@@ -599,260 +709,103 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel1
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 0.272 0.003617 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.33 0 0 1.5707963267948966 -0 0
0.04981
- 0.074
+ 0.029
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 0.272 -0.012266 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 0.0325 0 0.184162 0
-
- 0.04981
- 0.059
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 0.272 -0.028149 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 -0.0325 0 -0.184162 0
-
- 0.04981
- 0.044
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 0.272 -0.044032 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.166 0 0.004 0 -0.02 0
-
- 0.04981
- 0.029
-
+
+ 0.2 0.04981 0.07
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- front_left_flipper_wheel5
- front_left_flipper
+
+ rear_left_flipper
+ left_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -860,522 +813,610 @@
0
-
-
- 0.25 0.1985 0.01855 0 -0 0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
+
+
+ 0.185 0 0.195 0 -0 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 -0.015 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.112
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.02 0 -0.005 0 -0 0
+
+
+ 0.04 0.025 0.01
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel1
- left_track
+
+ camera_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.178571 0.1985 0.01855 0 -0 0
+
+ -0.02 -0.037465 0.185 0 0 -1.5707963267948966
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel2
- left_track
+
+ camera_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.107143 0.1985 0.01855 0 -0 0
+
+ -0.245 0 0.185 0 -0 3.1415926535897931
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0.0555 0.029 0.029
+
+
-
-
- left_track_wheel3
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel4
- left_track
+
+ camera_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.035714 0.1985 0.01855 0 -0 0
+
+ -0.02 0.037465 0.185 0 -0 1.5707963267948966
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel5
- left_track
+
+ camera_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 0.1985 0.01855 0 -0 0
+
+ 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.097
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- left_track_wheel6
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
-
- 0.097
- 0.089
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- left_track_wheel7
- left_track
+
+ cliff_sensor_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel8
- left_track
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
+
+ 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
+
+ 0.0105 0 0.00925 0 -0 0
- 0.01 0.01 0.01
+ 0.021 0.035 0.0185
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 1.5707963267948966
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_left_flipper
- left_track
+
+ cliff_sensor_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -1383,1736 +1424,171 @@
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
+
+ -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0.08 0 0 0 -0 0
- 0.15
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 0.272 0.003617 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 0.272 -0.012266 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.49287 0.272 -0.028149 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.573827 0.272 -0.044032 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.185 0 0.195 0 -0 0
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
- 0.02 0 -0.005 0 -0 0
-
-
- 0.04 0.025 0.01
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
+
+ 0.021 0 0.00925 0 -0 0
+ 10
0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.02 -0.037465 0.185 0 0 -1.5707963267948966
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.245 0 0.185 0 -0 3.1415926535897931
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.02 0.037465 0.185 0 -0 1.5707963267948966
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.0435 -0.0145 0.26752 -1.5707963267948966 -1.5707963267948966 0
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_4
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.1415 0 0.365 0 0.18 0
-
- 0 0 0.03675 0 -0 0
- 0.5
-
- 0.000461625
- 0
- 0
- 0.000461625
- 0
- 0.000473063
-
-
-
- 0 0 0.03675 0 -0 0
-
-
- 0.0735
- 0.0435
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
-
-
-
-
- 0 0 0.035925 0 -0 0
- 10
- 0
- 1
-
-
-
- 2048
- 1
- -3.1459
- 3.1459
-
-
- 128
- 1
- -0.785398
- 0.785398
-
-
-
- 0.1
- 50
- 0.01
-
-
- gaussian
- 0
- 0.01
-
-
-
-
-
- laser
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 -0.1985 0 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
-
-
-
-
-
- right_track
- base_link
-
- 0 1 0
-
- 0
- 0
- 0
- 4
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 1
- 0
- 0.95
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- front_right_flipper
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel1
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 -0.272 0.003617 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 -0.272 -0.012266 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 -0.272 -0.028149 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 -0.272 -0.044032 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- front_right_flipper_wheel5
- front_right_flipper
+
+ cliff_sensor_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
+
+ 0.0105 0 0.00925 0 -0 0
- 0.01 0.01 0.01
+ 0.021 0.035 0.0185
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper
- right_track
+
+ cliff_sensor_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -3120,296 +1596,203 @@
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ 0.0435 -0.0145 0.26752 -1.5707963267948966 -1.5707963267948966 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 3.25187e-05
+ 0
+ 0
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.0555 0.029 0.029
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_right_flipper_wheel1
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 -0.272 0.003617 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.04981
- 0.074
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_right_flipper_wheel2
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 -0.272 -0.012266 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.0145 0 -0 0
-
- 0.04981
- 0.059
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
+
+ camera_4
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.49287 -0.272 -0.028149 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.573827 -0.272 -0.044032 0 -0.193732 0
+
+ 0.1415 0 0.365 0 0.18 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0 0 0.03675 0 -0 0
+ 0.5
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 0.000461625
+ 0
+ 0
+ 0.000461625
+ 0
+ 0.000473063
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.03675 0 -0 0
- 0.04981
- 0.029
+ 0.0735
+ 0.0435
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
+
+
+
+
+ 0 0 0.035925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 2048
+ 1
+ -3.1459
+ 3.1459
+
+
+ 128
+ 1
+ -0.785398
+ 0.785398
+
+
+
+ 0.1
+ 50
+ 0.01
+
+
+ gaussian
+ 0
+ 0.01
+
+
+
-
- rear_right_flipper_wheel5
- rear_right_flipper
+
+ laser
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.25 -0.1985 0.01855 0 -0 0
+
+ 0 -0.1985 0 0 -0 0
0 0 0.0141 0 -0 0
- 0.7575
+ 6.06
0.002731
0
@@ -3419,8 +1802,25 @@
0.031391
-
- 0 0.015 0 1.5707963267948966 -0 0
+
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
+
+
+ 0.097 0.178 0.5
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 0.015 0.01855 1.5707963267948966 -0 0
0.112
@@ -3428,56 +1828,17 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel1
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
0.097
@@ -3485,32 +1846,34 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
+
+
+
-
- right_track_wheel2
- right_track
+
+ right_track
+ base_link
0 1 0
- -1e+16
- 1e+16
+ 0
+ 0
+ 0
+ 4
0
@@ -3518,170 +1881,142 @@
0
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ 1
+ 0
+ 0.95
+
+
-
- 0.107143 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+
+ 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
+
+ -0.08 0 0 0 -0 0
+ 0.75
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel3
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel4
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel5
+
+ front_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3689,170 +2024,137 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 -0.1985 0.01855 0 -0 0
+
+ -0.25 -0.272 0.0195 0 -0.193732 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ -0.08 0 0 0 -0 0
+ 0.75
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel6
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel7
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel8
+
+ rear_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3860,6 +2162,16 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
front_left_flipper_j
diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_7/model.sdf b/submitted_models/ctu_cras_norlab_absolem_sensor_config_7/model.sdf
index d435b4d0..15d6c305 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_7/model.sdf
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_7/model.sdf
@@ -363,7 +363,6 @@
1
50
- 0
@@ -434,6 +433,7 @@
+ 0
0 0 0.15 -3.1415926535897931 -0 0
@@ -458,26 +458,64 @@
0 0.1985 0 0 -0 0
- 1e-05
+ 0 0 0.0141 0 -0 0
+ 6.06
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.002731
+ 0
+ 0
+ 0.032554
+ 1.5e-05
+ 0.031391
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
- 0.01 0.01 0.01
+ 0.097 0.178 0.5
- 0.7
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 -0.015 0.01855 1.5707963267948966 -0 0
+
+
+ 0.112
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
+
+
+ 0.097
+ 0.089
+
+
+
+
+
+ 10
150
0 0 1
@@ -529,26 +567,98 @@
0.25 0.272 0.0195 0 0.193732 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 0.75
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.33 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.029
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 0.0325 0 0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 -0.0325 0 -0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.166 0 0.004 0 -0.02 0
- 0.01 0.01 0.01
+ 0.2 0.04981 0.07
- 0.7
+ 10
150
0 0 1
@@ -592,11 +702,11 @@
-
- 0.25 0.272 0.0195 0 0.193732 0
+
+ -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
0.08 0 0 0 -0 0
- 0.15
+ 0.75
0.0017491
2.8512e-07
@@ -606,7 +716,7 @@
0.010941
-
+
0 0 0 1.5707963267948966 -0 0
@@ -615,260 +725,103 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel1
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 0.272 0.003617 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.33 0 0 1.5707963267948966 -0 0
0.04981
- 0.074
+ 0.029
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 0.272 -0.012266 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 0.0325 0 0.184162 0
-
- 0.04981
- 0.059
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 0.272 -0.028149 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 -0.0325 0 -0.184162 0
-
- 0.04981
- 0.044
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 0.272 -0.044032 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.166 0 0.004 0 -0.02 0
-
- 0.04981
- 0.029
-
+
+ 0.2 0.04981 0.07
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- front_left_flipper_wheel5
- front_left_flipper
+
+ rear_left_flipper
+ left_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -876,522 +829,610 @@
0
-
-
- 0.25 0.1985 0.01855 0 -0 0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
+
+
+ 0.185 0 0.195 0 -0 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 -0.015 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.112
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.02 0 -0.005 0 -0 0
+
+
+ 0.04 0.025 0.01
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel1
- left_track
+
+ camera_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.178571 0.1985 0.01855 0 -0 0
+
+ -0.02 -0.037465 0.185 0 0 -1.5707963267948966
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel2
- left_track
+
+ camera_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.107143 0.1985 0.01855 0 -0 0
+
+ -0.245 0 0.185 0 -0 3.1415926535897931
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0.0555 0.029 0.029
+
+
-
-
- left_track_wheel3
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel4
- left_track
+
+ camera_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.035714 0.1985 0.01855 0 -0 0
+
+ -0.02 0.037465 0.185 0 -0 1.5707963267948966
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel5
- left_track
+
+ camera_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 0.1985 0.01855 0 -0 0
+
+ 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.097
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- left_track_wheel6
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
-
- 0.097
- 0.089
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- left_track_wheel7
- left_track
+
+ cliff_sensor_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel8
- left_track
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
+
+ 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
+
+ 0.0105 0 0.00925 0 -0 0
- 0.01 0.01 0.01
+ 0.021 0.035 0.0185
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 1.5707963267948966
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_left_flipper
- left_track
+
+ cliff_sensor_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -1399,1736 +1440,171 @@
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
+
+ -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0.08 0 0 0 -0 0
- 0.15
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 0.272 0.003617 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 0.272 -0.012266 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.49287 0.272 -0.028149 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.573827 0.272 -0.044032 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.185 0 0.195 0 -0 0
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
- 0.02 0 -0.005 0 -0 0
-
-
- 0.04 0.025 0.01
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
+
+ 0.021 0 0.00925 0 -0 0
+ 10
0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.02 -0.037465 0.185 0 0 -1.5707963267948966
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.245 0 0.185 0 -0 3.1415926535897931
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.02 0.037465 0.185 0 -0 1.5707963267948966
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.0435 -0.0145 0.26752 -1.5707963267948966 -1.5707963267948966 0
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_4
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.1415 0 0.365 0 0.18 0
-
- 0 0 0.03675 0 -0 0
- 0.5
-
- 0.000461625
- 0
- 0
- 0.000461625
- 0
- 0.000473063
-
-
-
- 0 0 0.03675 0 -0 0
-
-
- 0.0735
- 0.0435
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
-
-
-
-
- 0 0 0.035925 0 -0 0
- 10
- 0
- 1
-
-
-
- 2048
- 1
- -3.1459
- 3.1459
-
-
- 128
- 1
- -0.785398
- 0.785398
-
-
-
- 0.1
- 50
- 0.01
-
-
- gaussian
- 0
- 0.01
-
-
-
-
-
- laser
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 -0.1985 0 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
-
-
-
-
-
- right_track
- base_link
-
- 0 1 0
-
- 0
- 0
- 0
- 4
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 1
- 0
- 0.95
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- front_right_flipper
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel1
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 -0.272 0.003617 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 -0.272 -0.012266 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 -0.272 -0.028149 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 -0.272 -0.044032 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- front_right_flipper_wheel5
- front_right_flipper
+
+ cliff_sensor_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
+
+ 0.0105 0 0.00925 0 -0 0
- 0.01 0.01 0.01
+ 0.021 0.035 0.0185
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper
- right_track
+
+ cliff_sensor_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -3136,296 +1612,203 @@
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ 0.0435 -0.0145 0.26752 -1.5707963267948966 -1.5707963267948966 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 3.25187e-05
+ 0
+ 0
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.0555 0.029 0.029
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_right_flipper_wheel1
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 -0.272 0.003617 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.04981
- 0.074
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_right_flipper_wheel2
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 -0.272 -0.012266 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.0145 0 -0 0
-
- 0.04981
- 0.059
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
+
+ camera_4
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.49287 -0.272 -0.028149 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.573827 -0.272 -0.044032 0 -0.193732 0
+
+ 0.1415 0 0.365 0 0.18 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0 0 0.03675 0 -0 0
+ 0.5
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 0.000461625
+ 0
+ 0
+ 0.000461625
+ 0
+ 0.000473063
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.03675 0 -0 0
- 0.04981
- 0.029
+ 0.0735
+ 0.0435
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
+
+
+
+
+ 0 0 0.035925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 2048
+ 1
+ -3.1459
+ 3.1459
+
+
+ 128
+ 1
+ -0.785398
+ 0.785398
+
+
+
+ 0.1
+ 50
+ 0.01
+
+
+ gaussian
+ 0
+ 0.01
+
+
+
-
- rear_right_flipper_wheel5
- rear_right_flipper
+
+ laser
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.25 -0.1985 0.01855 0 -0 0
+
+ 0 -0.1985 0 0 -0 0
0 0 0.0141 0 -0 0
- 0.7575
+ 6.06
0.002731
0
@@ -3435,8 +1818,25 @@
0.031391
-
- 0 0.015 0 1.5707963267948966 -0 0
+
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
+
+
+ 0.097 0.178 0.5
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 0.015 0.01855 1.5707963267948966 -0 0
0.112
@@ -3444,56 +1844,17 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel1
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
0.097
@@ -3501,32 +1862,34 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
+
+
+
-
- right_track_wheel2
- right_track
+
+ right_track
+ base_link
0 1 0
- -1e+16
- 1e+16
+ 0
+ 0
+ 0
+ 4
0
@@ -3534,170 +1897,142 @@
0
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ 1
+ 0
+ 0.95
+
+
-
- 0.107143 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+
+ 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
+
+ -0.08 0 0 0 -0 0
+ 0.75
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel3
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel4
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel5
+
+ front_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3705,170 +2040,137 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 -0.1985 0.01855 0 -0 0
+
+ -0.25 -0.272 0.0195 0 -0.193732 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ -0.08 0 0 0 -0 0
+ 0.75
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel6
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel7
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel8
+
+ rear_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3876,6 +2178,16 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
front_left_flipper_j
diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_8/model.sdf b/submitted_models/ctu_cras_norlab_absolem_sensor_config_8/model.sdf
index 1158d51c..266eff93 100644
--- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_8/model.sdf
+++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_8/model.sdf
@@ -363,7 +363,6 @@
1
50
- 0
@@ -434,6 +433,7 @@
+ 0
0 0 0.15 -3.1415926535897931 -0 0
@@ -458,26 +458,64 @@
0 0.1985 0 0 -0 0
- 1e-05
+ 0 0 0.0141 0 -0 0
+ 6.06
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.002731
+ 0
+ 0
+ 0.032554
+ 1.5e-05
+ 0.031391
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
- 0.01 0.01 0.01
+ 0.097 0.178 0.5
- 0.7
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 -0.015 0.01855 1.5707963267948966 -0 0
+
+
+ 0.112
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
+
+
+ 0.097
+ 0.089
+
+
+
+
+
+ 10
150
0 0 1
@@ -529,26 +567,98 @@
0.25 0.272 0.0195 0 0.193732 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 0.75
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.089
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.33 0 0 1.5707963267948966 -0 0
+
+
+ 0.04981
+ 0.029
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 0.0325 0 0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.165 0 -0.0325 0 -0.184162 0
+
+
+ 0.33 0.04981 0.055
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.166 0 0.004 0 -0.02 0
- 0.01 0.01 0.01
+ 0.2 0.04981 0.07
- 0.7
+ 10
150
0 0 1
@@ -592,11 +702,11 @@
-
- 0.25 0.272 0.0195 0 0.193732 0
+
+ -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
0.08 0 0 0 -0 0
- 0.15
+ 0.75
0.0017491
2.8512e-07
@@ -606,7 +716,7 @@
0.010941
-
+
0 0 0 1.5707963267948966 -0 0
@@ -615,260 +725,103 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel1
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 0.272 0.003617 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.33 0 0 1.5707963267948966 -0 0
0.04981
- 0.074
+ 0.029
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 0.272 -0.012266 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 0.0325 0 0.184162 0
-
- 0.04981
- 0.059
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 0.272 -0.028149 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.165 0 -0.0325 0 -0.184162 0
-
- 0.04981
- 0.044
-
+
+ 0.33 0.04981 0.055
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 0.272 -0.044032 0 0.193732 0
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.166 0 0.004 0 -0.02 0
-
- 0.04981
- 0.029
-
+
+ 0.2 0.04981 0.07
+
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- front_left_flipper_wheel5
- front_left_flipper
+
+ rear_left_flipper
+ left_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -876,522 +829,610 @@
0
-
-
- 0.25 0.1985 0.01855 0 -0 0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
+
+
+ 0.185 0 0.195 0 -0 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 -0.015 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.112
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.02 0 -0.005 0 -0 0
+
+
+ 0.04 0.025 0.01
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel1
- left_track
+
+ camera_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.178571 0.1985 0.01855 0 -0 0
+
+ -0.02 -0.037465 0.185 0 0 -1.5707963267948966
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel2
- left_track
+
+ camera_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.107143 0.1985 0.01855 0 -0 0
+
+ -0.245 0 0.185 0 -0 3.1415926535897931
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0.0555 0.029 0.029
+
+
-
-
- left_track_wheel3
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel4
- left_track
+
+ camera_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.035714 0.1985 0.01855 0 -0 0
+
+ -0.02 0.037465 0.185 0 -0 1.5707963267948966
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.002731
+ 3.25187e-05
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
+
+
+ 0.0555 0.029 0.029
+
+
+
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.097
- 0.089
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- left_track_wheel5
- left_track
+
+ camera_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 0.1985 0.01855 0 -0 0
+
+ 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.002731
+ 1.56725e-06
0
0
- 0.032554
- 1.5e-05
- 0.031391
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.097
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- left_track_wheel6
- left_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
-
- 0.097
- 0.089
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- left_track_wheel7
- left_track
+
+ cliff_sensor_0
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.25 0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.097
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- left_track_wheel8
- left_track
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
+
+ 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
+
+ 0.0105 0 0.00925 0 -0 0
- 0.01 0.01 0.01
+ 0.021 0.035 0.0185
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 1.5707963267948966
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_left_flipper
- left_track
+
+ cliff_sensor_1
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -1399,1825 +1440,260 @@
-
- -0.25 0.272 0.0195 3.1415926535897931 0.193732 3.1415926535897931
+
+ -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
- 0.08 0 0 0 -0 0
- 0.15
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.021 0.035 0.0185
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 0.272 0.003617 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 0.272 -0.012266 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.49287 0.272 -0.028149 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
-
- 0.04981
- 0.044
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_left_flipper_wheel4
- rear_left_flipper
+
+ cliff_sensor_2
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.573827 0.272 -0.044032 3.1415926535897931 0.193732 3.1415926535897931
-
- 0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.185 0 0.195 0 -0 0
+
+ -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
- 0.039802 0 0.0145 0 -0 0
- 0.232
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 3.25187e-05
+ 1.56725e-06
0
0
- 0.000158598
+ 7.8325e-07
0
- 0.000158598
+ 1.666e-06
-
- 0.02465 0 0.0145 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
- 0.0555 0.029 0.029
+ 0.021 0.035 0.0185
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.02 0 -0.005 0 -0 0
-
-
- 0.04 0.025 0.01
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.02 -0.037465 0.185 0 0 -1.5707963267948966
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
+
+ 0.021 0 0.00925 0 -0 0
+ 10
0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.245 0 0.185 0 -0 3.1415926535897931
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.02 0.037465 0.185 0 -0 1.5707963267948966
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_0
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_1
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_2
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 -0.120465 0.2035 1.5707963267948966 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_3
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.225 -0.040465 0.185 0 -0 0
-
- 0.0155 0 0 0 -0 0
- 0.024
-
- 1.764e-06
- 0
- 0
- 4.58e-06
- 0
- 4.58e-06
-
-
-
- 0.0155 0 0 0 -0 0
-
-
- 0.043 0.021 0.021
-
-
-
-
- 0 0 0.0105 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flir_boson.dae
-
-
-
-
- 0.03 0 0 0 -0 0
- 1
- 8.6
- 0
-
- 1.6057
-
-
- 154.51
- 154.51
- 160.5
- 128.5
- 0
-
- stereographic
- 1
-
-
- 320
- 256
- L8
-
-
- 0.6
- 50
-
-
-
- 253.15
- 673.15
- 1.6
-
-
-
-
- thermocam
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.0435 -0.0145 0.26752 -1.5707963267948966 -1.5707963267948966 0
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_4
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.1415 0 0.365 0 0.18 0
-
- 0 0 0.03675 0 -0 0
- 0.5
-
- 0.000461625
- 0
- 0
- 0.000461625
- 0
- 0.000473063
-
-
-
- 0 0 0.03675 0 -0 0
-
-
- 0.0735
- 0.0435
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
-
-
-
-
- 0 0 0.035925 0 -0 0
- 10
- 0
- 1
-
-
-
- 2048
- 1
- -3.1459
- 3.1459
-
-
- 128
- 1
- -0.785398
- 0.785398
-
-
-
- 0.1
- 50
- 0.01
-
-
- gaussian
- 0
- 0.01
-
-
-
-
-
- laser
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 -0.1985 0 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
-
-
-
-
-
- right_track
- base_link
-
- 0 1 0
-
- 0
- 0
- 0
- 4
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 1
- 0
- 0.95
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- 0.01 0.01 0.01
-
-
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
-
-
-
-
-
- front_right_flipper
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel1
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.330957 -0.272 0.003617 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.074
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.411913 -0.272 -0.012266 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.059
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.49287 -0.272 -0.028149 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.573827 -0.272 -0.044032 3.1415926535897931 -0.193732 3.1415926535897931
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.029
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+ gaussian
+ 0
+ 0.015
+
+
+
-
- front_right_flipper_wheel5
- front_right_flipper
+
+ cliff_sensor_3
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ 0.225 -0.040465 0.185 0 -0 0
- 1e-05
+ 0.0155 0 0 0 -0 0
+ 0.024
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.764e-06
+ 0
+ 0
+ 4.58e-06
+ 0
+ 4.58e-06
-
+
+ 0.0155 0 0 0 -0 0
- 0.01 0.01 0.01
+ 0.043 0.021 0.021
-
-
-
- 0.7
- 150
- 0 0 1
-
-
-
-
- 0 0 0 -2.95743 -0 -1.5707963267948966
+
+ 0 0 0.0105 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flir_boson.dae
+
+ 0.03 0 0 0 -0 0
+ 1
+ 8.6
+ 0
+
+ 1.6057
+
+
+ 154.51
+ 154.51
+ 160.5
+ 128.5
+ 0
+
+ stereographic
+ 1
+
+
+ 320
+ 256
+ L8
+
+
+ 0.6
+ 50
+
+
+
+ 253.15
+ 673.15
+ 1.6
+
+
-
- rear_right_flipper
- right_track
+
+ thermocam
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- 20
- 0.785398
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -3225,296 +1701,203 @@
-
- -0.25 -0.272 0.0195 0 -0.193732 0
+
+ 0.0435 -0.0145 0.26752 -1.5707963267948966 -1.5707963267948966 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 3.25187e-05
+ 0
+ 0
+ 0.000158598
+ 0
+ 0.000158598
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
-
- 0.04981
- 0.089
-
+
+ 0.0555 0.029 0.029
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_right_flipper_wheel1
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.330957 -0.272 0.003617 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.04981
- 0.074
+ 0.03974
+ 0.0125
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
- rear_right_flipper_wheel2
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.411913 -0.272 -0.012266 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.0145 0 -0 0
-
- 0.04981
- 0.059
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
+
+ camera_4
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
-
-
-
- -0.49287 -0.272 -0.028149 0 -0.193732 0
-
- -0.08 0 0 0 -0 0
- 0.15
-
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.04981
- 0.044
-
-
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
-
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-1e+16
1e+16
-
- 0
- 0
-
- 0
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.573827 -0.272 -0.044032 0 -0.193732 0
+
+ 0.1415 0 0.365 0 0.18 0
- -0.08 0 0 0 -0 0
- 0.15
+ 0 0 0.03675 0 -0 0
+ 0.5
- 0.0017491
- 2.8512e-07
- 0.0018277
- 0.012277
- -3.6288e-07
- 0.010941
+ 0.000461625
+ 0
+ 0
+ 0.000461625
+ 0
+ 0.000473063
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.03675 0 -0 0
- 0.04981
- 0.029
+ 0.0735
+ 0.0435
-
-
-
- 1e+07
- 1
-
-
-
-
- 0.5
- 1
- 0.00092
- 0
- 0 0 1
-
-
-
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/ouster-os0.dae
+
+
+
+
+ 0 0 0.035925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 2048
+ 1
+ -3.1459
+ 3.1459
+
+
+ 128
+ 1
+ -0.785398
+ 0.785398
+
+
+
+ 0.1
+ 50
+ 0.01
+
+
+ gaussian
+ 0
+ 0.01
+
+
+
-
- rear_right_flipper_wheel5
- rear_right_flipper
+
+ laser
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.25 -0.1985 0.01855 0 -0 0
+
+ 0 -0.1985 0 0 -0 0
0 0 0.0141 0 -0 0
- 0.7575
+ 6.06
0.002731
0
@@ -3524,8 +1907,25 @@
0.031391
-
- 0 0.015 0 1.5707963267948966 -0 0
+
+ 0 0 0.01855 1.5707963267948966 -0 1.5707963267948966
+
+
+ 0.097 0.178 0.5
+
+
+
+
+
+ 10
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.25 0.015 0.01855 1.5707963267948966 -0 0
0.112
@@ -3533,56 +1933,17 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel1
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.25 0 0.01855 1.5707963267948966 -0 0
0.097
@@ -3590,32 +1951,34 @@
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 -0.0705 1.5707963267948966 0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/bogie.dae
+
+
+
-
- right_track_wheel2
- right_track
+
+ right_track
+ base_link
0 1 0
- -1e+16
- 1e+16
+ 0
+ 0
+ 0
+ 4
0
@@ -3623,170 +1986,142 @@
0
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ 1
+ 0
+ 0.95
+
+
-
- 0.107143 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+
+ 0.25 -0.272 0.0195 3.1415926535897931 -0.193732 3.1415926535897931
+
+ -0.08 0 0 0 -0 0
+ 0.75
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel3
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- 0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel4
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.035714 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel5
+
+ front_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3794,170 +2129,137 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.107143 -0.1985 0.01855 0 -0 0
+
+ -0.25 -0.272 0.0195 0 -0.193732 0
- 0 0 0.0141 0 -0 0
- 0.7575
+ -0.08 0 0 0 -0 0
+ 0.75
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
+
0 0 0 1.5707963267948966 -0 0
- 0.097
+ 0.04981
0.089
-
-
- 1e+07
- 1
-
-
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel6
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.178571 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.33 0 0 1.5707963267948966 -0 0
- 0.097
- 0.089
+ 0.04981
+ 0.029
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.165 0 0.0325 0 0.184162 -3.1415926535897931
+
+
+ 0.33 0.04981 0.055
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
-
-
- right_track_wheel7
- right_track
-
- 0 1 0
-
- -1e+16
- 1e+16
-
-
- 0
- 0
-
- 0
-
-
-
- -0.25 -0.1985 0.01855 0 -0 0
-
- 0 0 0.0141 0 -0 0
- 0.7575
-
- 0.002731
- 0
- 0
- 0.032554
- 1.5e-05
- 0.031391
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.165 0 -0.0325 0 -0.184162 -3.1415926535897931
-
- 0.097
- 0.089
-
+
+ 0.33 0.04981 0.055
+
-
+
- 1e+07
- 1
+ 10
+ 150
+ 0 0 1
-
+
+
+
+
+ -0.166 0 0.004 0 -0.02 -3.1415926535897931
+
+
+ 0.2 0.04981 0.07
+
+
+
- 0.5
- 1
- 0.00092
- 0
+ 10
+ 150
0 0 1
+
+ 0 0 0 -2.95743 -0 -1.5707963267948966
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_ABSOLEM_SENSOR_CONFIG_1/tip/files/meshes/flipper.dae
+
+
+
-
- right_track_wheel8
+
+ rear_right_flipper
right_track
0 1 0
-1e+16
1e+16
+ 20
+ 0.785398
0
@@ -3965,6 +2267,16 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
front_left_flipper_j
diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/config/sim.yaml b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/config/sim.yaml
index fb128d11..b7ccbc26 100644
--- a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/config/sim.yaml
+++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/config/sim.yaml
@@ -1,6 +1,6 @@
# Common simulation parameters
-num_wheels: 8 # Number of small wheels that approximate each flipper
+num_wheels: 0 # Number of small wheels that approximate each flipper
num_breadcrumbs: 0
# Which sensors to simulate (if False, they will be a part of the model but not producing data)
diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/launch/common.rb b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/launch/common.rb
index e2b8ae6d..0c6cfa81 100644
--- a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/launch/common.rb
+++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/launch/common.rb
@@ -22,32 +22,77 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
max_vel = config["rover_maxTrackSpeed"]
max_accel = config["rover_maxTrackAcceleration"]
+ tracks = ["left", "right"]
+ flippers = ["front_left", "front_right", "rear_left", "rear_right"]
+
+ flippersOfTrack = Hash.new
+ flippersOfTrack["left"] = ["front_left", "rear_left"]
+ flippersOfTrack["right"] = ["front_right", "rear_right"]
+
# generate a bunch of DiffDrive plugins (one for each simulated wheel size)
diff_drive = ""
- for wheel_num in 1..num_wheels
- # we only want odometry from the first diffdrive
- no_odom = ""
- if wheel_num > 1
- no_odom = "unused_odom\n"
+ trackControllers = ""
+ trackedVehicle = ""
+ power_draining_topics = ""
+ if num_wheels > 0
+ for wheel_num in 1..num_wheels
+ # we only want odometry from the first diffdrive
+ no_odom = ""
+ if wheel_num > 1
+ no_odom = "unused_odom\n"
+ end
+ diff_drive += "
+
+ front_left_flipper_wheel#{wheel_num}_j
+ rear_left_flipper_wheel#{wheel_num}_j
+ front_right_flipper_wheel#{wheel_num}_j
+ rear_right_flipper_wheel#{wheel_num}_j
+ #{wheel_separation}
+ #{small_wheel_radius + wheel_radius_increment * (num_wheels - wheel_num)}
+ /model/#{_name}/cmd_vel_relay
+ #{-max_vel}
+ #{max_vel}
+ #{-max_accel}
+ #{max_accel}
+ #{no_odom}
+ "
+ end
+ else
+ trackLinks = ""
+ for track in tracks
+ for flipper in flippersOfTrack[track]
+ trackControllers += <<-HEREDOC
+
+ #{flipper}_flipper
+ -#{max_vel}
+ #{max_vel}
+ -#{max_accel}
+ #{max_accel}
+
+ HEREDOC
+ trackLinks += "<#{track}_track>#{flipper}_flipper#{track}_track>"
+ power_draining_topics += "/model/#{_name}/link/#{flipper}_flipper/track_cmd_vel"
+ end
end
- diff_drive += "
-
- front_left_flipper_wheel#{wheel_num}_j
- rear_left_flipper_wheel#{wheel_num}_j
- front_right_flipper_wheel#{wheel_num}_j
- rear_right_flipper_wheel#{wheel_num}_j
- #{wheel_separation}
- #{small_wheel_radius + wheel_radius_increment * (num_wheels - wheel_num)}
- /model/#{_name}/cmd_vel_relay
- #{-max_vel}
- #{max_vel}
- #{-max_accel}
- #{max_accel}
- #{no_odom}
- "
+ trackedVehicle += <<-HEREDOC
+
+ #{trackLinks}
+ #{wheel_separation}
+ #{2 * wheel_radius_increment}
+ 0.5
+ /model/#{_name}/cmd_vel_relay
+
+ -#{max_vel}
+ #{max_vel}
+ -#{max_accel}
+ #{max_accel}
+
+
+ HEREDOC
end
+
<<-HEREDOC
#{_name}
@@ -61,6 +106,8 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
#{_modelURI}
#{diff_drive}
+ #{trackedVehicle}
+ #{trackControllers}
@@ -86,6 +133,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add
1.9499
9.9
true
+ #{power_draining_topics}
0.256 0.248 0 0 -0 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 3.659
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
+
+ 0.15175 0 0 0 -0 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 -0.05825 0 -0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.3035 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.1165
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
@@ -614,545 +702,145 @@
-
- 0.256 0.248 0 0 -0 0
+
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.22 -0.09 0.02 0 -0 0
+ 4.06
- 0.0017663
+ 0.0151492
0
0
- 0.0017663
+ 0.0129839
0
- 0.0031038
+ 0.0173903
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
- front_left_flipper_wheel1
- front_left_flipper
+
+ front_left_motor
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.299357 0.248 0 0 -0 0
+
+ 0.256 -0.248 0 3.1415926535897931 -0 -3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ -0.08 0 0 0 -0 0
+ 3.659
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0 0 -0 0
-
- 0.075
- 0.111
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 2
-
1
150
- 0.000580604
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- 0.342714 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0.05825 0 -0.126179 0
-
- 0.075
- 0.1055
-
+
+ 0.3035 0.075 0.078
+
-
+
- 1e+07
- 1
+ 1
+ 150
+ 0 0 1
- 4
-
+
+
+
+
+ -0.15175 0 -0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
1
150
- 0.000580604
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- 0.386071 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.1
+ 0.078
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000580604
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- 0.429429 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0945
+ 0.1165
-
-
- 1e+07
- 1
-
- 16
-
1
150
- 0.000580604
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel5
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- 0.472786 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel6
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- 0.516143 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel7
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- 0.5595 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel8
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0.22 -0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- front_left_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.256 -0.248 0 3.1415926535897931 -0 -3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
@@ -1289,1444 +977,138 @@
-
- 0.256 -0.248 0 3.1415926535897931 -0 3.1415926535897931
+
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.22 0.09 0.02 0 -0 0
+ 4.06
- 0.0017663
+ 0.0151492
0
0
- 0.0017663
+ 0.0129839
0
- 0.0031038
+ 0.0173903
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
- front_right_flipper_wheel1
- front_right_flipper
+
+ front_right_motor
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.299357 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
+
+ 0 0 0.15 -3.1415926535897931 0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.111
-
-
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- 0.342714 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1055
-
-
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- 0.386071 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1
-
-
-
-
-
- 1e+07
- 1
-
- 8
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- 0.429429 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0945
-
-
-
-
-
- 1e+07
- 1
-
- 16
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel5
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- 0.472786 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel6
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- 0.516143 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel7
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- 0.5595 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel8
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0.22 0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- front_right_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 0 0.15 -3.1415926535897931 0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
- 0
-
- 1
- 50
-
- 0
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
-
-
-
- imu
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.244 0 0.1321 0 0 -3.1415926535897931
-
- 0.019862 0 0.0145 0 -0 0
- 0.14
-
- 1.96233e-05
- 0
- 0
- 6.75088e-05
- 0
- 6.75088e-05
-
-
-
- 0.0117 0 0.0145 0 -0 0
-
-
- 0.054 0.029 0.029
-
-
-
-
- 0.042024 0 0.0145 0 1.5707963267948966 0
-
-
- 0.026
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- meshes/basler_ace.dae
-
-
-
-
- 0.029024 0 0.0145 0 -0 0
-
-
- meshes/evetar_fisheye_lens.dae
-
-
-
-
- 0.051574 0 0.0145 0 -0 0
- 15
- 0
-
- 2.40855
-
- 2048
- 1536
- R8G8B8
-
-
- 0.025
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 393.077
- 393.077
- 1023.5
- 767.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- rear_cam
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- meshes/big_wheel.dae
-
-
-
-
-
-
- -1 -1 1
- meshes/flipper_arm.dae
-
-
-
-
-
-
- meshes/belt.dae
-
-
-
-
- 0.3035 0 0 0 -0 0
-
-
- meshes/small_wheel.dae
-
-
-
- 1
-
-
- rear_left_flipper
- base_link
-
- 0 1 0
-
- -1e+16
- 1e+16
- 120
- 1
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
- rear_left_flipper_end_point_inflated
- rear_left_flipper
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
- rear_left_flipper_end_point
- rear_left_flipper
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.256 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.0017663
- 0
- 0
- 0.0017663
- 0
- 0.0031038
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
-
- 0
- 0
-
- 0
-
-
-
- -0.299357 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.111
-
-
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- -0.342714 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1055
-
-
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- -0.386071 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1
-
-
-
-
-
- 1e+07
- 1
-
- 8
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- -0.429429 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0945
-
-
-
-
-
- 1e+07
- 1
-
- 16
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- -0.472786 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel6
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- -0.516143 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel7
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- -0.5595 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel8
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- -0.22 -0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- rear_left_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.3 -0.18 0.1921 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
+ 0
+
+ 1
+ 50
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+ 0
+
+
-
- rear_right_box
+
+ imu
base_link
@@ -2749,66 +1131,66 @@
-
- 0.21 0 0.1921 0 -0 0
+
+ -0.244 0 0.1321 0 0 -3.1415926535897931
- 0.039802 0 0.0145 0 -0 0
- 0.232
+ 0.019862 0 0.0145 0 -0 0
+ 0.14
- 3.25187e-05
+ 1.96233e-05
0
0
- 0.000158598
+ 6.75088e-05
0
- 0.000158598
+ 6.75088e-05
-
- 0.02465 0 0.0145 0 -0 0
+
+ 0.0117 0 0.0145 0 -0 0
- 0.0555 0.029 0.029
+ 0.054 0.029 0.029
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
+
+ 0.042024 0 0.0145 0 1.5707963267948966 0
- 0.03974
+ 0.026
0.0125
-
+
0 0 0.0145 0 -0 0
- meshes/basler_ace2_pro.dae
+ meshes/basler_ace.dae
-
- 0.042964 0 0.0145 0 -0 0
+
+ 0.029024 0 0.0145 0 -0 0
- meshes/evetar_lens.dae
+ meshes/evetar_fisheye_lens.dae
-
- 0.072044 0 0.0145 0 -0 0
- 9
+
+ 0.051574 0 0.0145 0 -0 0
+ 15
0
- 1.50971
+ 2.40855
- 1920
- 1200
+ 2048
+ 1536
R8G8B8
- 0.011726
+ 0.025
300
@@ -2818,10 +1200,10 @@
- 1020.51
- 1020.51
- 959.5
- 599.5
+ 393.077
+ 393.077
+ 1023.5
+ 767.5
0
stereographic
@@ -2830,23 +1212,184 @@
-
- camera_0
- rear_right_box
+
+ rear_cam
+ base_link
+
+
+ 0
+ 0
+
+ 0 0 1
+ 0
+
+ -1e+16
+ 1e+16
+
+
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931
+
+ 0.08 0 0 0 -0 0
+ 3.659
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
+
+
+
+ 0.15175 0 0 0 -0 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 -0.05825 0 -0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.3035 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.1165
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+
+
+ meshes/big_wheel.dae
+
+
+
+
+
+
+ -1 -1 1
+ meshes/flipper_arm.dae
+
+
+
+
+
+
+ meshes/belt.dae
+
+
+
+
+ 0.3035 0 0 0 -0 0
+
+
+ meshes/small_wheel.dae
+
+
+
+ 1
+
+
+ rear_left_flipper
+ base_link
+ 0 1 0
+
+ -1e+16
+ 1e+16
+ 120
+ 1
+
0
0
- 0 0 1
0
-
- -1e+16
- 1e+16
-
+ 1
+ 1
0
0.2
@@ -2854,90 +1397,23 @@
-
- -0.21 0 0.1921 0 -0 3.1415926535897931
+
+ -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
- 0.039802 0 0.0145 0 -0 0
- 0.232
+ 1e-05
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
- camera_2
- rear_right_box
+
+ rear_left_flipper_end_point_inflated
+ rear_left_flipper
0
@@ -2959,71 +1435,23 @@
-
- 0.3 0.1445 0.2106 0 1.5707963267948966 0
+
+ -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ 1e-05
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
- cliff_sensor_front_left
- rear_right_box
+
+ rear_left_flipper_end_point
+ rear_left_flipper
0
@@ -3044,72 +1472,24 @@
-
-
- 0.3 -0.1445 0.2106 0 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
+
+
+
+ -0.22 -0.09 0.02 0 -0 0
+ 4.06
+
+ 0.0151492
+ 0
+ 0
+ 0.0129839
+ 0
+ 0.0173903
+
+
-
- cliff_sensor_front_right
- rear_right_box
+
+ rear_left_motor
+ base_link
0
@@ -3131,71 +1511,23 @@
-
- -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
+
+ -0.3 -0.18 0.1921 0 -0 0
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ 1e-05
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
- cliff_sensor_rear_left
- rear_right_box
+
+ rear_right_box
+ base_link
0
@@ -3217,70 +1549,89 @@
-
- -0.3 -0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
+
+ 0.21 0 0.1921 0 -0 0
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 1.56725e-06
+ 3.25187e-05
0
0
- 7.8325e-07
+ 0.000158598
0
- 1.666e-06
+ 0.000158598
-
- 0.0105 0 0.00925 0 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
- 0.021 0.035 0.0185
+ 0.0555 0.029 0.029
-
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
+
+
+ 0.03974
+ 0.0125
+
+
+
+
+ 0 0 0.0145 0 -0 0
- meshes/tfmini_plus_lidar.dae
+ meshes/basler_ace2_pro.dae
-
- 0.021 0 0.00925 0 -0 0
- 10
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
gaussian
0
- 0.015
+ 0.007
-
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
-
- cliff_sensor_rear_right
+
+ camera_0
rear_right_box
@@ -3303,38 +1654,89 @@
-
- -0.25 0.12 0.1921 0 -0 1.5707963267948966
+
+ -0.21 0 0.1921 0 -0 3.1415926535897931
- 0 0 0.0135 0 -0 0
- 0.168
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 8.687e-05
+ 3.25187e-05
0
0
- 0.000150206
+ 0.000158598
0
- 0.000216664
+ 0.000158598
-
- 0 0 0.0135 0 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
- 0.1 0.074 0.027
+ 0.0555 0.029 0.029
-
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
+
+
+ 0.03974
+ 0.0125
+
+
+
+
+ 0 0 0.0145 0 -0 0
- meshes/mobilicom.dae
+ meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ meshes/evetar_lens.dae
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- mobilicom
+
+ camera_2
rear_right_box
@@ -3357,42 +1759,71 @@
-
- -0.275 0.17 0.2056 -0.5 -0 1.5707963267948966
+
+ 0.3 0.1445 0.2106 0 1.5707963267948966 0
- 0 0 0.085 0 -0 0
- 0.03
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 7.3e-05
+ 1.56725e-06
0
0
- 7.3e-05
+ 7.8325e-07
0
- 1.5e-06
+ 1.666e-06
-
- 0 0 0.085 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.17
- 0.01
-
+
+ 0.021 0.035 0.0185
+
-
- 0 0 0.085 0 -0 0
+
-
- 0.17
- 0.01
-
+
+ meshes/tfmini_plus_lidar.dae
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- mobilicom_antenna_l
- mobilicom
+
+ cliff_sensor_front_left
+ rear_right_box
0
@@ -3414,42 +1845,71 @@
-
- -0.225 0.17 0.2056 0 -0 1.5707963267948966
+
+ 0.3 -0.1445 0.2106 0 1.5707963267948966 0
- 0 0 0.085 0 -0 0
- 0.03
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 7.3e-05
+ 1.56725e-06
0
0
- 7.3e-05
+ 7.8325e-07
0
- 1.5e-06
+ 1.666e-06
-
- 0 0 0.085 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.17
- 0.01
-
+
+ 0.021 0.035 0.0185
+
-
- 0 0 0.085 0 -0 0
+
-
- 0.17
- 0.01
-
+
+ meshes/tfmini_plus_lidar.dae
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- mobilicom_antenna_r
- mobilicom
+
+ cliff_sensor_front_right
+ rear_right_box
0
@@ -3471,72 +1931,85 @@
-
- -0.256 -0.248 0 0 -0 0
+
+ -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
-
-
- meshes/big_wheel.dae
-
-
-
-
-
-
- meshes/flipper_arm.dae
-
-
-
-
- 0 0 0 3.1415926535897931 -0 3.1415926535897931
+
+ 0.0105 0 0.00925 0 -0 0
-
- meshes/belt.dae
-
+
+ 0.021 0.035 0.0185
+
-
-
- -0.3035 0 0 0 -0 0
+
+
- meshes/small_wheel.dae
+ meshes/tfmini_plus_lidar.dae
- 1
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper
- base_link
+
+ cliff_sensor_rear_left
+ rear_right_box
- 0 1 0
-
- -1e+16
- 1e+16
- 120
- 1
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -3544,23 +2017,71 @@
-
- -0.6375 -0.248 0 0 -0 0
+
+ -0.3 -0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
+
+ 0.0105 0 0.00925 0 -0 0
+
+
+ 0.021 0.035 0.0185
+
+
+
+
+
+
+ meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper_end_point_inflated
- rear_right_flipper
+
+ cliff_sensor_rear_right
+ rear_right_box
0
@@ -3582,23 +2103,39 @@
-
- -0.6375 -0.248 0 0 -0 0
+
+ -0.25 0.12 0.1921 0 -0 1.5707963267948966
- 1e-05
+ 0 0 0.0135 0 -0 0
+ 0.168
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 8.687e-05
+ 0
+ 0
+ 0.000150206
+ 0
+ 0.000216664
+
+ 0 0 0.0135 0 -0 0
+
+
+ 0.1 0.074 0.027
+
+
+
+
+
+
+ meshes/mobilicom.dae
+
+
+
-
- rear_right_flipper_end_point
- rear_right_flipper
+
+ mobilicom
+ rear_right_box
0
@@ -3620,425 +2157,263 @@
-
- -0.256 -0.248 0 0 -0 0
+
+ -0.275 0.17 0.2056 -0.5 -0 1.5707963267948966
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0 0 0.085 0 -0 0
+ 0.03
- 0.0017663
+ 7.3e-05
0
0
- 0.0017663
+ 7.3e-05
0
- 0.0031038
+ 1.5e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.085 0 -0 0
- 0.075
- 0.1165
+ 0.17
+ 0.01
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
- 1
-
-
- rear_right_flipper_wheel1
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
-
- 0
- 0
-
- 0
-
-
-
- -0.299357 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.085 0 -0 0
- 0.075
- 0.111
+ 0.17
+ 0.01
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
+
-
- rear_right_flipper_wheel2
- rear_right_flipper
+
+ mobilicom_antenna_l
+ mobilicom
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.342714 -0.248 0 0 -0 0
+
+ -0.225 0.17 0.2056 0 -0 1.5707963267948966
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0 0 0.085 0 -0 0
+ 0.03
- 0.00148707
+ 7.3e-05
0
0
- 0.00148707
+ 7.3e-05
0
- 0.00254535
+ 1.5e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.085 0 -0 0
- 0.075
- 0.1055
+ 0.17
+ 0.01
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
- 1
+
+ 0 0 0.085 0 -0 0
+
+
+ 0.17
+ 0.01
+
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
+
+ mobilicom_antenna_r
+ mobilicom
+
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.386071 -0.248 0 0 -0 0
+
+ -0.256 -0.248 0 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ -0.08 0 0 0 -0 0
+ 3.659
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0 0 -0 0
-
- 0.075
- 0.1
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000580604
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- -0.429429 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0.05825 0 -0.126179 0
-
- 0.075
- 0.0945
-
+
+ 0.3035 0.075 0.078
+
-
+
- 1e+07
- 1
+ 1
+ 150
+ 0 0 1
- 16
-
+
+
+
+
+ -0.15175 0 -0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
1
150
- 0.000580604
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel5
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- -0.472786 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.089
+ 0.078
-
-
- 1e+07
- 1
-
- 32
-
1
150
- 0.000580604
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel6
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- -0.516143 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0835
+ 0.1165
-
-
- 1e+07
- 1
-
- 64
-
1
150
- 0.000580604
- 0
0 0 1
+
+
+
+ meshes/big_wheel.dae
+
+
+
+
+
+
+ meshes/flipper_arm.dae
+
+
+
+
+ 0 0 0 3.1415926535897931 -0 3.1415926535897931
+
+
+ meshes/belt.dae
+
+
+
+
+ -0.3035 0 0 0 -0 0
+
+
+ meshes/small_wheel.dae
+
+
+
1
-
- rear_right_flipper_wheel7
- rear_right_flipper
+
+ rear_right_flipper
+ base_link
0 1 0
-1e+16
1e+16
- -1
- 11.976
+ 120
+ 1
0
@@ -4046,67 +2421,92 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.5595 -0.248 0 0 -0 0
+
+ -0.6375 -0.248 0 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000580604
- 0
- 0 0 1
-
-
-
-
- 1
-
- rear_right_flipper_wheel8
+
+ rear_right_flipper_end_point_inflated
rear_right_flipper
- 0 1 0
+
+ 0
+ 0
+
+ 0 0 1
+ 0
-1e+16
1e+16
- -1
- 12.8205
+
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ -0.6375 -0.248 0 0 -0 0
+
+ 1e-05
+
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
+
+
+
+
+ rear_right_flipper_end_point
+ rear_right_flipper
+
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
@@ -4806,200 +3206,6 @@
rear_left_flipper_j
rear_right_flipper_j
-
-
- 0.0485
- 0
- 7.53525
- 0.078
-
-
- 0.0485
- 0
- 7.53525
- 0.0835
-
-
- 0.0485
- 0
- 7.53525
- 0.089
-
-
- 0.0485
- 0
- 7.53525
- 0.0945
-
-
- 0.0485
- 0
- 7.53525
- 0.1
-
-
- 0.0485
- 0
- 7.53525
- 0.1055
-
-
- 0.0485
- 0
- 7.53525
- 0.111
-
-
- 0.0485
- 0
- 7.53525
- 0.1165
-
-
- 0.0485
- 0
- 7.53525
- 0.078
-
-
- 0.0485
- 0
- 7.53525
- 0.0835
-
-
- 0.0485
- 0
- 7.53525
- 0.089
-
-
- 0.0485
- 0
- 7.53525
- 0.0945
-
-
- 0.0485
- 0
- 7.53525
- 0.1
-
-
- 0.0485
- 0
- 7.53525
- 0.1055
-
-
- 0.0485
- 0
- 7.53525
- 0.111
-
-
- 0.0485
- 0
- 7.53525
- 0.1165
-
-
- 0.0485
- 0
- 7.53525
- 0.078
-
-
- 0.0485
- 0
- 7.53525
- 0.0835
-
-
- 0.0485
- 0
- 7.53525
- 0.089
-
-
- 0.0485
- 0
- 7.53525
- 0.0945
-
-
- 0.0485
- 0
- 7.53525
- 0.1
-
-
- 0.0485
- 0
- 7.53525
- 0.1055
-
-
- 0.0485
- 0
- 7.53525
- 0.111
-
-
- 0.0485
- 0
- 7.53525
- 0.1165
-
-
- 0.0485
- 0
- 7.53525
- 0.078
-
-
- 0.0485
- 0
- 7.53525
- 0.0835
-
-
- 0.0485
- 0
- 7.53525
- 0.089
-
-
- 0.0485
- 0
- 7.53525
- 0.0945
-
-
- 0.0485
- 0
- 7.53525
- 0.1
-
-
- 0.0485
- 0
- 7.53525
- 0.1055
-
-
- 0.0485
- 0
- 7.53525
- 0.111
-
-
- 0.0485
- 0
- 7.53525
- 0.1165
-
-
diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/urdf/marv.xacro b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/urdf/marv.xacro
index 9513a806..38c5b813 100644
--- a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/urdf/marv.xacro
+++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/urdf/marv.xacro
@@ -437,7 +437,7 @@
-
+
@@ -474,7 +474,20 @@
-
+
+
+
+
+
+
+
+
+
+
@@ -749,7 +762,7 @@
-
+
@@ -843,6 +856,7 @@
1
50
+ 0
diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_2/model.sdf b/submitted_models/ctu_cras_norlab_marv_sensor_config_2/model.sdf
index 7fd5f654..b9c61e60 100644
--- a/submitted_models/ctu_cras_norlab_marv_sensor_config_2/model.sdf
+++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_2/model.sdf
@@ -468,16 +468,104 @@
0.256 0.248 0 0 -0 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 3.659
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
+
+ 0.15175 0 0 0 -0 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 -0.05825 0 -0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.3035 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.1165
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
@@ -614,545 +702,145 @@
-
- 0.256 0.248 0 0 -0 0
+
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.22 -0.09 0.02 0 -0 0
+ 4.06
- 0.0017663
+ 0.0151492
0
0
- 0.0017663
+ 0.0129839
0
- 0.0031038
+ 0.0173903
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
- front_left_flipper_wheel1
- front_left_flipper
+
+ front_left_motor
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.299357 0.248 0 0 -0 0
+
+ 0.256 -0.248 0 3.1415926535897931 -0 -3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ -0.08 0 0 0 -0 0
+ 3.659
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0 0 -0 0
-
- 0.075
- 0.111
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 2
-
1
150
- 0.000575828
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- 0.342714 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0.05825 0 -0.126179 0
-
- 0.075
- 0.1055
-
+
+ 0.3035 0.075 0.078
+
-
+
- 1e+07
- 1
+ 1
+ 150
+ 0 0 1
- 4
-
+
+
+
+
+ -0.15175 0 -0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
1
150
- 0.000575828
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- 0.386071 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.1
+ 0.078
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000575828
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- 0.429429 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0945
+ 0.1165
-
-
- 1e+07
- 1
-
- 16
-
1
150
- 0.000575828
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel5
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- 0.472786 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel6
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- 0.516143 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel7
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- 0.5595 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel8
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0.22 -0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- front_left_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.256 -0.248 0 3.1415926535897931 -0 -3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
@@ -1289,1444 +977,138 @@
-
- 0.256 -0.248 0 3.1415926535897931 -0 3.1415926535897931
+
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.22 0.09 0.02 0 -0 0
+ 4.06
- 0.0017663
+ 0.0151492
0
0
- 0.0017663
+ 0.0129839
0
- 0.0031038
+ 0.0173903
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
- front_right_flipper_wheel1
- front_right_flipper
+
+ front_right_motor
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.299357 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
+
+ 0 0 0.15 -3.1415926535897931 0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.111
-
-
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- 0.342714 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1055
-
-
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- 0.386071 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1
-
-
-
-
-
- 1e+07
- 1
-
- 8
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- 0.429429 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0945
-
-
-
-
-
- 1e+07
- 1
-
- 16
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel5
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- 0.472786 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel6
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- 0.516143 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel7
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- 0.5595 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel8
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0.22 0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- front_right_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 0 0.15 -3.1415926535897931 0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
- 0
-
- 1
- 50
-
- 0
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
-
-
-
- imu
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.244 0 0.1321 0 0 -3.1415926535897931
-
- 0.019862 0 0.0145 0 -0 0
- 0.14
-
- 1.96233e-05
- 0
- 0
- 6.75088e-05
- 0
- 6.75088e-05
-
-
-
- 0.0117 0 0.0145 0 -0 0
-
-
- 0.054 0.029 0.029
-
-
-
-
- 0.042024 0 0.0145 0 1.5707963267948966 0
-
-
- 0.026
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace.dae
-
-
-
-
- 0.029024 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_fisheye_lens.dae
-
-
-
-
- 0.051574 0 0.0145 0 -0 0
- 15
- 0
-
- 2.40855
-
- 2048
- 1536
- R8G8B8
-
-
- 0.025
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 393.077
- 393.077
- 1023.5
- 767.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- rear_cam
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
-
-
-
-
-
-
- -1 -1 1
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
-
-
-
-
- 0.3035 0 0 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
-
-
-
- 1
-
-
- rear_left_flipper
- base_link
-
- 0 1 0
-
- -1e+16
- 1e+16
- 120
- 1
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
- rear_left_flipper_end_point_inflated
- rear_left_flipper
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
- rear_left_flipper_end_point
- rear_left_flipper
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.256 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.0017663
- 0
- 0
- 0.0017663
- 0
- 0.0031038
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
-
- 0
- 0
-
- 0
-
-
-
- -0.299357 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.111
-
-
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- -0.342714 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1055
-
-
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- -0.386071 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1
-
-
-
-
-
- 1e+07
- 1
-
- 8
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- -0.429429 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0945
-
-
-
-
-
- 1e+07
- 1
-
- 16
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- -0.472786 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel6
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- -0.516143 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel7
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- -0.5595 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel8
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- -0.22 -0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- rear_left_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.3 -0.18 0.1921 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
+ 0
+
+ 1
+ 50
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+ 0
+
+
-
- rear_right_box
+
+ imu
base_link
@@ -2749,66 +1131,66 @@
-
- 0.21 0 0.1921 0 -0 0
+
+ -0.244 0 0.1321 0 0 -3.1415926535897931
- 0.039802 0 0.0145 0 -0 0
- 0.232
+ 0.019862 0 0.0145 0 -0 0
+ 0.14
- 3.25187e-05
+ 1.96233e-05
0
0
- 0.000158598
+ 6.75088e-05
0
- 0.000158598
+ 6.75088e-05
-
- 0.02465 0 0.0145 0 -0 0
+
+ 0.0117 0 0.0145 0 -0 0
- 0.0555 0.029 0.029
+ 0.054 0.029 0.029
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
+
+ 0.042024 0 0.0145 0 1.5707963267948966 0
- 0.03974
+ 0.026
0.0125
-
+
0 0 0.0145 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace.dae
-
- 0.042964 0 0.0145 0 -0 0
+
+ 0.029024 0 0.0145 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_fisheye_lens.dae
-
- 0.072044 0 0.0145 0 -0 0
- 9
+
+ 0.051574 0 0.0145 0 -0 0
+ 15
0
- 1.50971
+ 2.40855
- 1920
- 1200
+ 2048
+ 1536
R8G8B8
- 0.011726
+ 0.025
300
@@ -2818,10 +1200,10 @@
- 1020.51
- 1020.51
- 959.5
- 599.5
+ 393.077
+ 393.077
+ 1023.5
+ 767.5
0
stereographic
@@ -2830,23 +1212,184 @@
-
- camera_0
- rear_right_box
+
+ rear_cam
+ base_link
+
+
+ 0
+ 0
+
+ 0 0 1
+ 0
+
+ -1e+16
+ 1e+16
+
+
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931
+
+ 0.08 0 0 0 -0 0
+ 3.659
+
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
+
+
+
+ 0.15175 0 0 0 -0 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 -0.05825 0 -0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.3035 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.1165
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
+
+
+
+
+
+
+ -1 -1 1
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
+
+
+
+
+ 0.3035 0 0 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
+
+
+
+ 1
+
+
+ rear_left_flipper
+ base_link
+ 0 1 0
+
+ -1e+16
+ 1e+16
+ 120
+ 1
+
0
0
- 0 0 1
0
-
- -1e+16
- 1e+16
-
+ 1
+ 1
0
0.2
@@ -2854,90 +1397,23 @@
-
- -0.21 0 0.1921 0 -0 3.1415926535897931
+
+ -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
- 0.039802 0 0.0145 0 -0 0
- 0.232
+ 1e-05
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
- camera_2
- rear_right_box
+
+ rear_left_flipper_end_point_inflated
+ rear_left_flipper
0
@@ -2959,71 +1435,23 @@
-
- 0.3 0.1445 0.2106 0 1.5707963267948966 0
+
+ -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ 1e-05
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
- cliff_sensor_front_left
- rear_right_box
+
+ rear_left_flipper_end_point
+ rear_left_flipper
0
@@ -3045,71 +1473,23 @@
-
- 0.3 -0.1445 0.2106 0 1.5707963267948966 0
+
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ -0.22 -0.09 0.02 0 -0 0
+ 4.06
- 1.56725e-06
+ 0.0151492
0
0
- 7.8325e-07
+ 0.0129839
0
- 1.666e-06
+ 0.0173903
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
- cliff_sensor_front_right
- rear_right_box
+
+ rear_left_motor
+ base_link
0
@@ -3131,71 +1511,23 @@
-
- -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
+
+ -0.3 -0.18 0.1921 0 -0 0
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
+ 1e-05
+
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
- cliff_sensor_rear_left
- rear_right_box
+
+ rear_right_box
+ base_link
0
@@ -3217,70 +1549,89 @@
-
- -0.3 -0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
+
+ 0.21 0 0.1921 0 -0 0
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 1.56725e-06
+ 3.25187e-05
0
0
- 7.8325e-07
+ 0.000158598
0
- 1.666e-06
+ 0.000158598
-
- 0.0105 0 0.00925 0 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
- 0.021 0.035 0.0185
+ 0.0555 0.029 0.029
-
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
+
+
+ 0.03974
+ 0.0125
+
+
+
+
+ 0 0 0.0145 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
- 0.021 0 0.00925 0 -0 0
- 10
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
gaussian
0
- 0.015
+ 0.007
-
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
-
- cliff_sensor_rear_right
+
+ camera_0
rear_right_box
@@ -3303,38 +1654,89 @@
-
- -0.25 0.12 0.1921 0 -0 1.5707963267948966
+
+ -0.21 0 0.1921 0 -0 3.1415926535897931
- 0 0 0.0135 0 -0 0
- 0.168
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 8.687e-05
+ 3.25187e-05
0
0
- 0.000150206
+ 0.000158598
0
- 0.000216664
+ 0.000158598
-
- 0 0 0.0135 0 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
- 0.1 0.074 0.027
+ 0.0555 0.029 0.029
-
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
+
+
+ 0.03974
+ 0.0125
+
+
+
+
+ 0 0 0.0145 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mobilicom.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- mobilicom
+
+ camera_2
rear_right_box
@@ -3357,42 +1759,71 @@
-
- -0.275 0.17 0.2056 -0.5 -0 1.5707963267948966
+
+ 0.3 0.1445 0.2106 0 1.5707963267948966 0
- 0 0 0.085 0 -0 0
- 0.03
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 7.3e-05
+ 1.56725e-06
0
0
- 7.3e-05
+ 7.8325e-07
0
- 1.5e-06
+ 1.666e-06
-
- 0 0 0.085 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.17
- 0.01
-
+
+ 0.021 0.035 0.0185
+
-
- 0 0 0.085 0 -0 0
+
-
- 0.17
- 0.01
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- mobilicom_antenna_l
- mobilicom
+
+ cliff_sensor_front_left
+ rear_right_box
0
@@ -3414,42 +1845,71 @@
-
- -0.225 0.17 0.2056 0 -0 1.5707963267948966
+
+ 0.3 -0.1445 0.2106 0 1.5707963267948966 0
- 0 0 0.085 0 -0 0
- 0.03
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 7.3e-05
+ 1.56725e-06
0
0
- 7.3e-05
+ 7.8325e-07
0
- 1.5e-06
+ 1.666e-06
-
- 0 0 0.085 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.17
- 0.01
-
+
+ 0.021 0.035 0.0185
+
-
- 0 0 0.085 0 -0 0
+
-
- 0.17
- 0.01
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- mobilicom_antenna_r
- mobilicom
+
+ cliff_sensor_front_right
+ rear_right_box
0
@@ -3471,38 +1931,70 @@
-
- -0.24 -0.16 0.1821 0 0 -3.1415926535897931
+
+ -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
- 0.0845 -0.024 0.0655 0 -0 0
- 0.5
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.000931042
+ 1.56725e-06
0
0
- 0.00220342
+ 7.8325e-07
0
- 0.00170437
+ 1.666e-06
-
- 0.0845 -0.024 0.0655 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
- 0.189 0.072 0.131
+ 0.021 0.035 0.0185
-
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mote_deployer.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- mote_deployer
+
+ cliff_sensor_rear_left
rear_right_box
@@ -3525,72 +2017,85 @@
-
- -0.256 -0.248 0 0 -0 0
+
+ -0.3 -0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
-
-
-
-
- 0 0 0 3.1415926535897931 -0 3.1415926535897931
+
+ 0.0105 0 0.00925 0 -0 0
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
-
+
+ 0.021 0.035 0.0185
+
-
-
- -0.3035 0 0 0 -0 0
+
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
- 1
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper
- base_link
+
+ cliff_sensor_rear_right
+ rear_right_box
- 0 1 0
-
- -1e+16
- 1e+16
- 120
- 1
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -3598,23 +2103,39 @@
-
- -0.6375 -0.248 0 0 -0 0
+
+ -0.25 0.12 0.1921 0 -0 1.5707963267948966
- 1e-05
+ 0 0 0.0135 0 -0 0
+ 0.168
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 8.687e-05
+ 0
+ 0
+ 0.000150206
+ 0
+ 0.000216664
+
+ 0 0 0.0135 0 -0 0
+
+
+ 0.1 0.074 0.027
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mobilicom.dae
+
+
+
-
- rear_right_flipper_end_point_inflated
- rear_right_flipper
+
+ mobilicom
+ rear_right_box
0
@@ -3636,23 +2157,42 @@
-
- -0.6375 -0.248 0 0 -0 0
+
+ -0.275 0.17 0.2056 -0.5 -0 1.5707963267948966
- 1e-05
+ 0 0 0.085 0 -0 0
+ 0.03
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 7.3e-05
+ 0
+ 0
+ 7.3e-05
+ 0
+ 1.5e-06
+
+ 0 0 0.085 0 -0 0
+
+
+ 0.17
+ 0.01
+
+
+
+
+ 0 0 0.085 0 -0 0
+
+
+ 0.17
+ 0.01
+
+
+
-
- rear_right_flipper_end_point
- rear_right_flipper
+
+ mobilicom_antenna_l
+ mobilicom
0
@@ -3674,425 +2214,260 @@
-
- -0.256 -0.248 0 0 -0 0
+
+ -0.225 0.17 0.2056 0 -0 1.5707963267948966
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0 0 0.085 0 -0 0
+ 0.03
- 0.0017663
+ 7.3e-05
0
0
- 0.0017663
+ 7.3e-05
0
- 0.0031038
+ 1.5e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.085 0 -0 0
- 0.075
- 0.1165
+ 0.17
+ 0.01
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
- 1
-
-
- rear_right_flipper_wheel1
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
-
- 0
- 0
-
- 0
-
-
-
- -0.299357 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.085 0 -0 0
- 0.075
- 0.111
+ 0.17
+ 0.01
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
+
-
- rear_right_flipper_wheel2
- rear_right_flipper
+
+ mobilicom_antenna_r
+ mobilicom
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.342714 -0.248 0 0 -0 0
+
+ -0.24 -0.16 0.1821 0 0 -3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.0845 -0.024 0.0655 0 -0 0
+ 0.5
- 0.00148707
+ 0.000931042
0
0
- 0.00148707
+ 0.00220342
0
- 0.00254535
+ 0.00170437
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0845 -0.024 0.0655 0 -0 0
-
- 0.075
- 0.1055
-
+
+ 0.189 0.072 0.131
+
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
- 1
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mote_deployer.dae
+
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
+
+ mote_deployer
+ rear_right_box
+
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.386071 -0.248 0 0 -0 0
+
+ -0.256 -0.248 0 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ -0.08 0 0 0 -0 0
+ 3.659
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0 0 -0 0
-
- 0.075
- 0.1
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000575828
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- -0.429429 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0.05825 0 -0.126179 0
-
- 0.075
- 0.0945
-
+
+ 0.3035 0.075 0.078
+
-
+
- 1e+07
- 1
+ 1
+ 150
+ 0 0 1
- 16
-
+
+
+
+
+ -0.15175 0 -0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
1
150
- 0.000575828
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel5
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- -0.472786 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.089
+ 0.078
-
-
- 1e+07
- 1
-
- 32
-
1
150
- 0.000575828
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel6
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- -0.516143 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0835
+ 0.1165
-
-
- 1e+07
- 1
-
- 64
-
1
150
- 0.000575828
- 0
0 0 1
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
+
+
+
+
+ 0 0 0 3.1415926535897931 -0 3.1415926535897931
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
+
+
+
+
+ -0.3035 0 0 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
+
+
+
1
-
- rear_right_flipper_wheel7
- rear_right_flipper
+
+ rear_right_flipper
+ base_link
0 1 0
-1e+16
1e+16
- -1
- 11.976
+ 120
+ 1
0
@@ -4100,67 +2475,92 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.5595 -0.248 0 0 -0 0
+
+ -0.6375 -0.248 0 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000575828
- 0
- 0 0 1
-
-
-
-
- 1
-
- rear_right_flipper_wheel8
+
+ rear_right_flipper_end_point_inflated
rear_right_flipper
- 0 1 0
+
+ 0
+ 0
+
+ 0 0 1
+ 0
-1e+16
1e+16
- -1
- 12.8205
+
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ -0.6375 -0.248 0 0 -0 0
+
+ 1e-05
+
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
+
+
+
+
+ rear_right_flipper_end_point
+ rear_right_flipper
+
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
@@ -4860,200 +3260,6 @@
rear_left_flipper_j
rear_right_flipper_j
-
-
- 0.0485
- 0
- 7.59775
- 0.078
-
-
- 0.0485
- 0
- 7.59775
- 0.0835
-
-
- 0.0485
- 0
- 7.59775
- 0.089
-
-
- 0.0485
- 0
- 7.59775
- 0.0945
-
-
- 0.0485
- 0
- 7.59775
- 0.1
-
-
- 0.0485
- 0
- 7.59775
- 0.1055
-
-
- 0.0485
- 0
- 7.59775
- 0.111
-
-
- 0.0485
- 0
- 7.59775
- 0.1165
-
-
- 0.0485
- 0
- 7.59775
- 0.078
-
-
- 0.0485
- 0
- 7.59775
- 0.0835
-
-
- 0.0485
- 0
- 7.59775
- 0.089
-
-
- 0.0485
- 0
- 7.59775
- 0.0945
-
-
- 0.0485
- 0
- 7.59775
- 0.1
-
-
- 0.0485
- 0
- 7.59775
- 0.1055
-
-
- 0.0485
- 0
- 7.59775
- 0.111
-
-
- 0.0485
- 0
- 7.59775
- 0.1165
-
-
- 0.0485
- 0
- 7.59775
- 0.078
-
-
- 0.0485
- 0
- 7.59775
- 0.0835
-
-
- 0.0485
- 0
- 7.59775
- 0.089
-
-
- 0.0485
- 0
- 7.59775
- 0.0945
-
-
- 0.0485
- 0
- 7.59775
- 0.1
-
-
- 0.0485
- 0
- 7.59775
- 0.1055
-
-
- 0.0485
- 0
- 7.59775
- 0.111
-
-
- 0.0485
- 0
- 7.59775
- 0.1165
-
-
- 0.0485
- 0
- 7.59775
- 0.078
-
-
- 0.0485
- 0
- 7.59775
- 0.0835
-
-
- 0.0485
- 0
- 7.59775
- 0.089
-
-
- 0.0485
- 0
- 7.59775
- 0.0945
-
-
- 0.0485
- 0
- 7.59775
- 0.1
-
-
- 0.0485
- 0
- 7.59775
- 0.1055
-
-
- 0.0485
- 0
- 7.59775
- 0.111
-
-
- 0.0485
- 0
- 7.59775
- 0.1165
-
-
diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_3/model.sdf b/submitted_models/ctu_cras_norlab_marv_sensor_config_3/model.sdf
index fcf66cf3..acd5bf72 100644
--- a/submitted_models/ctu_cras_norlab_marv_sensor_config_3/model.sdf
+++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_3/model.sdf
@@ -1,8 +1,5 @@
-
-
+
@@ -471,16 +468,104 @@
0.256 0.248 0 0 -0 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 3.659
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
+
+ 0.15175 0 0 0 -0 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 -0.05825 0 -0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.3035 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.1165
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
@@ -617,545 +702,145 @@
-
- 0.256 0.248 0 0 -0 0
+
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.22 -0.09 0.02 0 -0 0
+ 4.06
- 0.0017663
+ 0.0151492
0
0
- 0.0017663
+ 0.0129839
0
- 0.0031038
+ 0.0173903
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
- front_left_flipper_wheel1
- front_left_flipper
+
+ front_left_motor
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.299357 0.248 0 0 -0 0
+
+ 0.256 -0.248 0 3.1415926535897931 -0 -3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ -0.08 0 0 0 -0 0
+ 3.659
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0 0 -0 0
-
- 0.075
- 0.111
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 2
-
1
150
- 0.000580373
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- 0.342714 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0.05825 0 -0.126179 0
-
- 0.075
- 0.1055
-
+
+ 0.3035 0.075 0.078
+
-
+
- 1e+07
- 1
+ 1
+ 150
+ 0 0 1
- 4
-
+
+
+
+
+ -0.15175 0 -0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
1
150
- 0.000580373
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- 0.386071 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.1
+ 0.078
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000580373
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- 0.429429 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0945
+ 0.1165
-
-
- 1e+07
- 1
-
- 16
-
1
150
- 0.000580373
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel5
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- 0.472786 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel6
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- 0.516143 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel7
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- 0.5595 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel8
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0.22 -0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- front_left_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.256 -0.248 0 3.1415926535897931 -0 -3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
@@ -1292,1550 +977,139 @@
-
- 0.256 -0.248 0 3.1415926535897931 -0 3.1415926535897931
+
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.22 0.09 0.02 0 -0 0
+ 4.06
- 0.0017663
+ 0.0151492
0
0
- 0.0017663
+ 0.0129839
0
- 0.0031038
+ 0.0173903
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
- front_right_flipper_wheel1
- front_right_flipper
+
+ front_right_motor
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.299357 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
+
+ 0 0 0.15 -3.1415926535897931 0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.111
-
-
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- 0.342714 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1055
-
-
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- 0.386071 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1
-
-
-
-
-
- 1e+07
- 1
-
- 8
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- 0.429429 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0945
-
-
-
-
-
- 1e+07
- 1
-
- 16
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel5
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- 0.472786 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel6
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- 0.516143 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel7
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- 0.5595 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel8
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0.22 0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- front_right_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 0 0.15 -3.1415926535897931 0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
- 0
-
- 1
- 50
-
- 0
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
- 0
- 0.009
- 0.00075
- 0.005
- 2e-05
- 400
- 0.00025
-
-
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
- 0
- 0.021
- 0.05
- 0.0075
- 0.000375
- 175
- 0.005
-
-
-
-
-
-
-
- imu
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.244 0 0.1321 0 0 -3.1415926535897931
-
- 0.019862 0 0.0145 0 -0 0
- 0.14
-
- 1.96233e-05
- 0
- 0
- 6.75088e-05
- 0
- 6.75088e-05
-
-
-
- 0.0117 0 0.0145 0 -0 0
-
-
- 0.054 0.029 0.029
-
-
-
-
- 0.042024 0 0.0145 0 1.5707963267948966 0
-
-
- 0.026
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace.dae
-
-
-
-
- 0.029024 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_fisheye_lens.dae
-
-
-
-
- 0.051574 0 0.0145 0 -0 0
- 15
- 0
-
- 2.40855
-
- 2048
- 1536
- R8G8B8
-
-
- 0.025
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 393.077
- 393.077
- 1023.5
- 767.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- rear_cam
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
-
-
-
-
-
-
- -1 -1 1
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
-
-
-
-
- 0.3035 0 0 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
-
-
-
- 1
-
-
- rear_left_flipper
- base_link
-
- 0 1 0
-
- -1e+16
- 1e+16
- 120
- 1
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
- rear_left_flipper_end_point_inflated
- rear_left_flipper
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
- rear_left_flipper_end_point
- rear_left_flipper
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.256 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.0017663
- 0
- 0
- 0.0017663
- 0
- 0.0031038
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
-
- 0
- 0
-
- 0
-
-
-
- -0.299357 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.111
-
-
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- -0.342714 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1055
-
-
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- -0.386071 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1
-
-
-
-
-
- 1e+07
- 1
-
- 8
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- -0.429429 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0945
-
-
-
-
-
- 1e+07
- 1
-
- 16
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- -0.472786 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel6
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- -0.516143 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel7
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- -0.5595 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- rear_left_flipper_wheel8
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- -0.22 -0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- rear_left_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.3 -0.18 0.1921 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
- rear_right_box
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.21 0 0.1921 0 -0 0
-
- 0.039802 0 0.0145 0 -0 0
- 0.232
-
- 3.25187e-05
- 0
- 0
- 0.000158598
- 0
- 0.000158598
-
-
-
- 0.02465 0 0.0145 0 -0 0
-
-
- 0.0555 0.029 0.029
-
-
-
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
-
-
- 0.03974
- 0.0125
-
-
-
-
- 0 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
+ 0
+
+ 1
+ 50
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+ 0
+ 0.009
+ 0.00075
+ 0.005
+ 2e-05
+ 400
+ 0.00025
+
+
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+
+ 0
+ 0.021
+ 0.05
+ 0.0075
+ 0.000375
+ 175
+ 0.005
+
+
+
+ 0
+
-
- camera_0
- rear_right_box
+
+ imu
+ base_link
0
@@ -2857,66 +1131,66 @@
-
- -0.21 0 0.1921 0 -0 3.1415926535897931
+
+ -0.244 0 0.1321 0 0 -3.1415926535897931
- 0.039802 0 0.0145 0 -0 0
- 0.232
+ 0.019862 0 0.0145 0 -0 0
+ 0.14
- 3.25187e-05
+ 1.96233e-05
0
0
- 0.000158598
+ 6.75088e-05
0
- 0.000158598
+ 6.75088e-05
-
- 0.02465 0 0.0145 0 -0 0
+
+ 0.0117 0 0.0145 0 -0 0
- 0.0555 0.029 0.029
+ 0.054 0.029 0.029
-
- 0.062834 0 0.0145 0 1.5707963267948966 0
+
+ 0.042024 0 0.0145 0 1.5707963267948966 0
- 0.03974
+ 0.026
0.0125
-
+
0 0 0.0145 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace.dae
-
- 0.042964 0 0.0145 0 -0 0
+
+ 0.029024 0 0.0145 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_fisheye_lens.dae
-
- 0.072044 0 0.0145 0 -0 0
- 9
+
+ 0.051574 0 0.0145 0 -0 0
+ 15
0
- 1.50971
+ 2.40855
- 1920
- 1200
+ 2048
+ 1536
R8G8B8
- 0.011726
+ 0.025
300
@@ -2926,10 +1200,10 @@
- 1020.51
- 1020.51
- 959.5
- 599.5
+ 393.077
+ 393.077
+ 1023.5
+ 767.5
0
stereographic
@@ -2938,9 +1212,9 @@
-
- camera_2
- rear_right_box
+
+ rear_cam
+ base_link
0
@@ -2962,85 +1236,160 @@
-
- 0.3 0.1445 0.2106 0 1.5707963267948966 0
+
+ -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ 0.08 0 0 0 -0 0
+ 3.659
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0.0105 0 0.00925 0 -0 0
+
+ 0.15175 0 0 0 -0 0
- 0.021 0.035 0.0185
+ 0.3035 0.075 0.078
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
-
+
+ 0.15175 0 0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 -0.05825 0 -0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.3035 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.1165
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
+
+
+
+ -1 -1 1
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
+
+
+
+
+ 0.3035 0 0 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
+
+
+
+ 1
-
- cliff_sensor_front_left
- rear_right_box
+
+ rear_left_flipper
+ base_link
+ 0 1 0
+
+ -1e+16
+ 1e+16
+ 120
+ 1
+
0
0
- 0 0 1
0
-
- -1e+16
- 1e+16
-
+ 1
+ 1
0
0.2
@@ -3048,71 +1397,23 @@
-
- 0.3 -0.1445 0.2106 0 1.5707963267948966 0
+
+ -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ 1e-05
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
- cliff_sensor_front_right
- rear_right_box
+
+ rear_left_flipper_end_point_inflated
+ rear_left_flipper
0
@@ -3134,71 +1435,23 @@
-
- -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
+
+ -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ 1e-05
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
- cliff_sensor_rear_left
- rear_right_box
+
+ rear_left_flipper_end_point
+ rear_left_flipper
0
@@ -3220,71 +1473,61 @@
-
- -0.3 -0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
+
- 0.0105 0 0.00925 0 -0 0
- 0.012
+ -0.22 -0.09 0.02 0 -0 0
+ 4.06
- 1.56725e-06
+ 0.0151492
0
0
- 7.8325e-07
+ 0.0129839
0
- 1.666e-06
+ 0.0173903
+
+
+
+
+ rear_left_motor
+ base_link
+
+
+ 0
+ 0
+
+ 0 0 1
+ 0
+
+ -1e+16
+ 1e+16
+
+
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ -0.3 -0.18 0.1921 0 -0 0
+
+ 1e-05
+
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
- cliff_sensor_rear_right
- rear_right_box
+
+ rear_right_box
+ base_link
0
@@ -3306,38 +1549,89 @@
-
- -0.25 0.12 0.1921 0 -0 1.5707963267948966
+
+ 0.21 0 0.1921 0 -0 0
- 0 0 0.0135 0 -0 0
- 0.168
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 8.687e-05
+ 3.25187e-05
0
0
- 0.000150206
+ 0.000158598
0
- 0.000216664
+ 0.000158598
-
- 0 0 0.0135 0 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
- 0.1 0.074 0.027
+ 0.0555 0.029 0.029
-
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
+
+
+ 0.03974
+ 0.0125
+
+
+
+
+ 0 0 0.0145 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mobilicom.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- mobilicom
+
+ camera_0
rear_right_box
@@ -3360,42 +1654,90 @@
-
- -0.275 0.17 0.2056 -0.5 -0 1.5707963267948966
+
+ -0.21 0 0.1921 0 -0 3.1415926535897931
- 0 0 0.085 0 -0 0
- 0.03
+ 0.039802 0 0.0145 0 -0 0
+ 0.232
- 7.3e-05
+ 3.25187e-05
0
0
- 7.3e-05
+ 0.000158598
0
- 1.5e-06
+ 0.000158598
-
- 0 0 0.085 0 -0 0
+
+ 0.02465 0 0.0145 0 -0 0
-
- 0.17
- 0.01
-
+
+ 0.0555 0.029 0.029
+
-
- 0 0 0.085 0 -0 0
+
+ 0.062834 0 0.0145 0 1.5707963267948966 0
- 0.17
- 0.01
+ 0.03974
+ 0.0125
+
+
+ 0 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
+
+
+
+
+ 0.042964 0 0.0145 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
+
+
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
+ 0
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
+
+ gaussian
+ 0
+ 0.007
+
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
+
-
- mobilicom_antenna_l
- mobilicom
+
+ camera_2
+ rear_right_box
0
@@ -3417,42 +1759,71 @@
-
- -0.225 0.17 0.2056 0 -0 1.5707963267948966
+
+ 0.3 0.1445 0.2106 0 1.5707963267948966 0
- 0 0 0.085 0 -0 0
- 0.03
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 7.3e-05
+ 1.56725e-06
0
0
- 7.3e-05
+ 7.8325e-07
0
- 1.5e-06
+ 1.666e-06
-
- 0 0 0.085 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
-
- 0.17
- 0.01
-
+
+ 0.021 0.035 0.0185
+
-
- 0 0 0.085 0 -0 0
+
-
- 0.17
- 0.01
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- mobilicom_antenna_r
- mobilicom
+
+ cliff_sensor_front_left
+ rear_right_box
0
@@ -3474,73 +1845,70 @@
-
- 0.26 -0.04 0.1921 0 -0 0
+
+ 0.3 -0.1445 0.2106 0 1.5707963267948966 0
- 0.0155 0 0 0 -0 0
- 0.024
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 1.764e-06
+ 1.56725e-06
0
0
- 4.58e-06
+ 7.8325e-07
0
- 4.58e-06
+ 1.666e-06
-
- 0.0155 0 0 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
- 0.043 0.021 0.021
+ 0.021 0.035 0.0185
-
- 0 0 0.0105 0 -0 0
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flir_boson.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
- 0.03 0 0 0 -0 0
- 1
- 8.6
+
+ 0.021 0 0.00925 0 -0 0
+ 10
0
-
- 1.6057
-
-
- 154.51
- 154.51
- 159.5
- 127.5
- 0
-
- stereographic
- 1
-
-
- 320
- 256
- L8
-
-
- 0.2
- 50
-
-
-
- 253.15
- 673.15
- 1.6
-
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
-
- thermocam
+
+ cliff_sensor_front_right
rear_right_box
@@ -3563,72 +1931,85 @@
-
- -0.256 -0.248 0 0 -0 0
+
+ -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
-
-
-
-
- 0 0 0 3.1415926535897931 -0 3.1415926535897931
+
+ 0.0105 0 0.00925 0 -0 0
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
-
+
+ 0.021 0.035 0.0185
+
-
-
- -0.3035 0 0 0 -0 0
+
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
- 1
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper
- base_link
+
+ cliff_sensor_rear_left
+ rear_right_box
- 0 1 0
-
- -1e+16
- 1e+16
- 120
- 1
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
- 1
- 1
0
0.2
@@ -3636,23 +2017,71 @@
-
- -0.6375 -0.248 0 0 -0 0
+
+ -0.3 -0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
- 1e-05
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 1.56725e-06
+ 0
+ 0
+ 7.8325e-07
+ 0
+ 1.666e-06
+
+ 0.0105 0 0.00925 0 -0 0
+
+
+ 0.021 0.035 0.0185
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+
+
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- rear_right_flipper_end_point_inflated
- rear_right_flipper
+
+ cliff_sensor_rear_right
+ rear_right_box
0
@@ -3674,23 +2103,39 @@
-
- -0.6375 -0.248 0 0 -0 0
+
+ -0.25 0.12 0.1921 0 -0 1.5707963267948966
- 1e-05
+ 0 0 0.0135 0 -0 0
+ 0.168
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 8.687e-05
+ 0
+ 0
+ 0.000150206
+ 0
+ 0.000216664
+
+ 0 0 0.0135 0 -0 0
+
+
+ 0.1 0.074 0.027
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mobilicom.dae
+
+
+
-
- rear_right_flipper_end_point
- rear_right_flipper
+
+ mobilicom
+ rear_right_box
0
@@ -3712,425 +2157,352 @@
-
- -0.256 -0.248 0 0 -0 0
+
+ -0.275 0.17 0.2056 -0.5 -0 1.5707963267948966
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0 0 0.085 0 -0 0
+ 0.03
- 0.0017663
+ 7.3e-05
0
0
- 0.0017663
+ 7.3e-05
0
- 0.0031038
+ 1.5e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.085 0 -0 0
- 0.075
- 0.1165
+ 0.17
+ 0.01
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
- 1
+
+ 0 0 0.085 0 -0 0
+
+
+ 0.17
+ 0.01
+
+
+
-
- rear_right_flipper_wheel1
- rear_right_flipper
+
+ mobilicom_antenna_l
+ mobilicom
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.299357 -0.248 0 0 -0 0
+
+ -0.225 0.17 0.2056 0 -0 1.5707963267948966
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0 0 0.085 0 -0 0
+ 0.03
- 0.00162322
+ 7.3e-05
0
0
- 0.00162322
+ 7.3e-05
0
- 0.00281766
+ 1.5e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.085 0 -0 0
- 0.075
- 0.111
+ 0.17
+ 0.01
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
- 1
+
+ 0 0 0.085 0 -0 0
+
+
+ 0.17
+ 0.01
+
+
+
-
- rear_right_flipper_wheel2
- rear_right_flipper
+
+ mobilicom_antenna_r
+ mobilicom
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.342714 -0.248 0 0 -0 0
+
+ 0.26 -0.04 0.1921 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.0155 0 0 0 -0 0
+ 0.024
- 0.00148707
+ 1.764e-06
0
0
- 0.00148707
+ 4.58e-06
0
- 0.00254535
+ 4.58e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0155 0 0 0 -0 0
-
- 0.075
- 0.1055
-
+
+ 0.043 0.021 0.021
+
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
- 1
+
+ 0 0 0.0105 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flir_boson.dae
+
+
+
+
+ 0.03 0 0 0 -0 0
+ 1
+ 8.6
+ 0
+
+ 1.6057
+
+
+ 154.51
+ 154.51
+ 159.5
+ 127.5
+ 0
+
+ stereographic
+ 1
+
+
+ 320
+ 256
+ L8
+
+
+ 0.2
+ 50
+
+
+
+ 253.15
+ 673.15
+ 1.6
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
+
+ thermocam
+ rear_right_box
+
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.386071 -0.248 0 0 -0 0
+
+ -0.256 -0.248 0 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ -0.08 0 0 0 -0 0
+ 3.659
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0 0 -0 0
-
- 0.075
- 0.1
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000580373
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- -0.429429 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0.05825 0 -0.126179 0
-
- 0.075
- 0.0945
-
+
+ 0.3035 0.075 0.078
+
-
+
- 1e+07
- 1
+ 1
+ 150
+ 0 0 1
- 16
-
+
+
+
+
+ -0.15175 0 -0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
1
150
- 0.000580373
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel5
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- -0.472786 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.089
+ 0.078
-
-
- 1e+07
- 1
-
- 32
-
1
150
- 0.000580373
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel6
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- -0.516143 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0835
+ 0.1165
-
-
- 1e+07
- 1
-
- 64
-
1
150
- 0.000580373
- 0
0 0 1
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
+
+
+
+
+ 0 0 0 3.1415926535897931 -0 3.1415926535897931
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
+
+
+
+
+ -0.3035 0 0 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
+
+
+
1
-
- rear_right_flipper_wheel7
- rear_right_flipper
+
+ rear_right_flipper
+ base_link
0 1 0
-1e+16
1e+16
- -1
- 11.976
+ 120
+ 1
0
@@ -4138,67 +2510,92 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.5595 -0.248 0 0 -0 0
+
+ -0.6375 -0.248 0 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000580373
- 0
- 0 0 1
-
-
-
-
- 1
-
- rear_right_flipper_wheel8
+
+ rear_right_flipper_end_point_inflated
rear_right_flipper
- 0 1 0
+
+ 0
+ 0
+
+ 0 0 1
+ 0
-1e+16
1e+16
- -1
- 12.8205
+
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ -0.6375 -0.248 0 0 -0 0
+
+ 1e-05
+
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
+
+
+
+
+ rear_right_flipper_end_point
+ rear_right_flipper
+
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
@@ -4898,200 +3295,6 @@
rear_left_flipper_j
rear_right_flipper_j
-
-
- 0.0485
- 0
- 7.53825
- 0.078
-
-
- 0.0485
- 0
- 7.53825
- 0.0835
-
-
- 0.0485
- 0
- 7.53825
- 0.089
-
-
- 0.0485
- 0
- 7.53825
- 0.0945
-
-
- 0.0485
- 0
- 7.53825
- 0.1
-
-
- 0.0485
- 0
- 7.53825
- 0.1055
-
-
- 0.0485
- 0
- 7.53825
- 0.111
-
-
- 0.0485
- 0
- 7.53825
- 0.1165
-
-
- 0.0485
- 0
- 7.53825
- 0.078
-
-
- 0.0485
- 0
- 7.53825
- 0.0835
-
-
- 0.0485
- 0
- 7.53825
- 0.089
-
-
- 0.0485
- 0
- 7.53825
- 0.0945
-
-
- 0.0485
- 0
- 7.53825
- 0.1
-
-
- 0.0485
- 0
- 7.53825
- 0.1055
-
-
- 0.0485
- 0
- 7.53825
- 0.111
-
-
- 0.0485
- 0
- 7.53825
- 0.1165
-
-
- 0.0485
- 0
- 7.53825
- 0.078
-
-
- 0.0485
- 0
- 7.53825
- 0.0835
-
-
- 0.0485
- 0
- 7.53825
- 0.089
-
-
- 0.0485
- 0
- 7.53825
- 0.0945
-
-
- 0.0485
- 0
- 7.53825
- 0.1
-
-
- 0.0485
- 0
- 7.53825
- 0.1055
-
-
- 0.0485
- 0
- 7.53825
- 0.111
-
-
- 0.0485
- 0
- 7.53825
- 0.1165
-
-
- 0.0485
- 0
- 7.53825
- 0.078
-
-
- 0.0485
- 0
- 7.53825
- 0.0835
-
-
- 0.0485
- 0
- 7.53825
- 0.089
-
-
- 0.0485
- 0
- 7.53825
- 0.0945
-
-
- 0.0485
- 0
- 7.53825
- 0.1
-
-
- 0.0485
- 0
- 7.53825
- 0.1055
-
-
- 0.0485
- 0
- 7.53825
- 0.111
-
-
- 0.0485
- 0
- 7.53825
- 0.1165
-
-
diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_4/model.sdf b/submitted_models/ctu_cras_norlab_marv_sensor_config_4/model.sdf
index ab5aa779..dd4e4f75 100644
--- a/submitted_models/ctu_cras_norlab_marv_sensor_config_4/model.sdf
+++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_4/model.sdf
@@ -1,8 +1,5 @@
-
-
+
@@ -471,16 +468,104 @@
0.256 0.248 0 0 -0 0
- 1e-05
+ 0.08 0 0 0 -0 0
+ 3.659
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
+
+ 0.15175 0 0 0 -0 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.15175 0 -0.05825 0 -0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0.3035 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.078
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
+
+ 0 0 0 1.5707963267948966 -0 0
+
+
+ 0.075
+ 0.1165
+
+
+
+
+
+ 1
+ 150
+ 0 0 1
+
+
+
+
@@ -617,545 +702,145 @@
-
- 0.256 0.248 0 0 -0 0
+
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.22 -0.09 0.02 0 -0 0
+ 4.06
- 0.0017663
+ 0.0151492
0
0
- 0.0017663
+ 0.0129839
0
- 0.0031038
+ 0.0173903
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
- front_left_flipper_wheel1
- front_left_flipper
+
+ front_left_motor
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.299357 0.248 0 0 -0 0
+
+ 0.256 -0.248 0 3.1415926535897931 -0 -3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ -0.08 0 0 0 -0 0
+ 3.659
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0 0 -0 0
-
- 0.075
- 0.111
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 2
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel2
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- 0.342714 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0.05825 0 -0.126179 0
-
- 0.075
- 0.1055
-
+
+ 0.3035 0.075 0.078
+
-
+
- 1e+07
- 1
+ 1
+ 150
+ 0 0 1
- 4
-
+
+
+
+
+ -0.15175 0 -0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel3
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- 0.386071 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.1
+ 0.078
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel4
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- 0.429429 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0945
+ 0.1165
-
-
- 1e+07
- 1
-
- 16
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- front_left_flipper_wheel5
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- 0.472786 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel6
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- 0.516143 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel7
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- 0.5595 0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_left_flipper_wheel8
- front_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0.22 -0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- front_left_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.256 -0.248 0 3.1415926535897931 -0 -3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
@@ -1292,543 +977,55 @@
-
- 0.256 -0.248 0 3.1415926535897931 -0 3.1415926535897931
+
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.22 0.09 0.02 0 -0 0
+ 4.06
- 0.0017663
+ 0.0151492
0
0
- 0.0017663
+ 0.0129839
0
- 0.0031038
+ 0.0173903
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1165
-
-
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
- front_right_flipper_wheel1
- front_right_flipper
+
+ front_right_motor
+ base_link
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- 0.299357 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
+
+ 0 0 0.15 -3.1415926535897931 0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.111
-
-
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel2
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- 0.342714 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1055
-
-
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel3
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- 0.386071 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.1
-
-
-
-
-
- 1e+07
- 1
-
- 8
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel4
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- 0.429429 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0945
-
-
-
-
-
- 1e+07
- 1
-
- 16
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel5
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- 0.472786 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.089
-
-
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel6
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- 0.516143 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel7
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
-
- 0
- 0
-
- 0
-
-
-
- 0.5595 -0.248 -0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
-
- front_right_flipper_wheel8
- front_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
-
- 0
- 0
-
- 0
-
-
-
-
- 0.22 0.09 0.02 0 -0 0
- 4.06
-
- 0.0151492
- 0
- 0
- 0.0129839
- 0
- 0.0173903
-
-
-
-
- front_right_motor
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0 0 0.15 -3.1415926535897931 0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
0
@@ -1836,7 +1033,6 @@
1
50
- 0
@@ -1907,6 +1103,7 @@
+ 0
@@ -2011,162 +1208,13 @@
stereographic
1
-
-
-
-
-
- rear_cam
- base_link
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
-
-
-
-
-
-
- -1 -1 1
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
-
-
-
-
- 0.3035 0 0 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
-
-
-
- 1
-
-
- rear_left_flipper
- base_link
-
- 0 1 0
-
- -1e+16
- 1e+16
- 120
- 1
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
-
-
- rear_left_flipper_end_point_inflated
- rear_left_flipper
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
+
+
+
-
- rear_left_flipper_end_point
- rear_left_flipper
+
+ rear_cam
+ base_link
0
@@ -2188,364 +1236,149 @@
-
- -0.256 0.248 0 3.1415926535897931 -0 3.1415926535897931
+
+ -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.08 0 0 0 -0 0
+ 3.659
- 0.0017663
- 0
- 0
- 0.0017663
- 0
- 0.0031038
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.15175 0 0 0 -0 0
-
- 0.075
- 0.1165
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 1
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- rear_left_flipper_wheel1
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
-
- 0
- 0
-
- 0
-
-
-
- -0.299357 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00162322
- 0
- 0
- 0.00162322
- 0
- 0.00281766
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.15175 0 0.05825 0 0.126179 0
-
- 0.075
- 0.111
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 2
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- rear_left_flipper_wheel2
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
-
- 0
- 0
-
- 0
-
-
-
- -0.342714 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00148707
- 0
- 0
- 0.00148707
- 0
- 0.00254535
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.15175 0 -0.05825 0 -0.126179 0
-
- 0.075
- 0.1055
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 4
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- rear_left_flipper_wheel3
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
-
- 0
- 0
-
- 0
-
-
-
- -0.386071 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.1
+ 0.078
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- rear_left_flipper_wheel4
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- -0.429429 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0945
+ 0.1165
-
-
- 1e+07
- 1
-
- 16
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- rear_left_flipper_wheel5
- rear_left_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- -0.472786 0.248 0 3.1415926535897931 -0 3.1415926535897931
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
-
- 0.075
- 0.089
-
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
+
-
-
-
- 1e+07
- 1
-
- 32
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
+
+
+
+
+ -1 -1 1
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
+
+
+
+
+ 0.3035 0 0 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
+
+
+
1
-
- rear_left_flipper_wheel6
- rear_left_flipper
+
+ rear_left_flipper
+ base_link
0 1 0
-1e+16
1e+16
- -1
- 11.236
+ 120
+ 1
0
@@ -2553,128 +1386,92 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.516143 0.248 0 3.1415926535897931 -0 3.1415926535897931
+
+ -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.0835
-
-
-
-
-
- 1e+07
- 1
-
- 64
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
+ 1e-05
+
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
+
+
-
- rear_left_flipper_wheel7
+
+ rear_left_flipper_end_point_inflated
rear_left_flipper
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.976
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.5595 0.248 0 3.1415926535897931 -0 3.1415926535897931
+
+ -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
- rear_left_flipper_wheel8
+
+ rear_left_flipper_end_point
rear_left_flipper
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 12.8205
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
@@ -2895,223 +1692,51 @@
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/basler_ace2_pro.dae
-
-
- 0.042964 0 0.0145 0 -0 0
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
-
-
-
- 0.072044 0 0.0145 0 -0 0
- 9
- 0
-
- 1.50971
-
- 1920
- 1200
- R8G8B8
-
-
- 0.011726
- 300
-
-
- gaussian
- 0
- 0.007
-
-
-
- 1020.51
- 1020.51
- 959.5
- 599.5
- 0
-
- stereographic
- 1
-
-
-
-
-
- camera_2
- rear_right_box
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.3 0.1445 0.2106 0 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
-
-
-
- 0.021 0 0.00925 0 -0 0
- 10
- 0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
-
- gaussian
- 0
- 0.015
-
-
-
-
-
- cliff_sensor_front_left
- rear_right_box
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- 0.3 -0.1445 0.2106 0 1.5707963267948966 0
-
- 0.0105 0 0.00925 0 -0 0
- 0.012
-
- 1.56725e-06
- 0
- 0
- 7.8325e-07
- 0
- 1.666e-06
-
-
-
- 0.0105 0 0.00925 0 -0 0
-
-
- 0.021 0.035 0.0185
-
-
-
-
+
+
+ 0.042964 0 0.0145 0 -0 0
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/evetar_lens.dae
-
- 0.021 0 0.00925 0 -0 0
- 10
+
+ 0.072044 0 0.0145 0 -0 0
+ 9
0
- 1
-
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
- 3
- 1
- -0.0314159
- 0.0314159
-
-
-
- 0.1
- 12
- 0.01
-
+
+ 1.50971
+
+ 1920
+ 1200
+ R8G8B8
+
+
+ 0.011726
+ 300
+
gaussian
0
- 0.015
+ 0.007
-
+
+
+ 1020.51
+ 1020.51
+ 959.5
+ 599.5
+ 0
+
+ stereographic
+ 1
+
+
-
- cliff_sensor_front_right
+
+ camera_2
rear_right_box
@@ -3134,8 +1759,8 @@
-
- -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
+
+ 0.3 0.1445 0.2106 0 1.5707963267948966 0
0.0105 0 0.00925 0 -0 0
0.012
@@ -3148,7 +1773,7 @@
1.666e-06
-
+
0.0105 0 0.00925 0 -0 0
@@ -3156,7 +1781,7 @@
-
+
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
@@ -3196,8 +1821,8 @@
-
- cliff_sensor_rear_left
+
+ cliff_sensor_front_left
rear_right_box
@@ -3220,8 +1845,8 @@
-
- -0.3 -0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
+
+ 0.3 -0.1445 0.2106 0 1.5707963267948966 0
0.0105 0 0.00925 0 -0 0
0.012
@@ -3234,7 +1859,7 @@
1.666e-06
-
+
0.0105 0 0.00925 0 -0 0
@@ -3242,7 +1867,7 @@
-
+
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
@@ -3277,182 +1902,14 @@
gaussian
0
- 0.015
-
-
-
-
-
- cliff_sensor_rear_right
- rear_right_box
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.25 0.12 0.1921 0 -0 1.5707963267948966
-
- 0 0 0.0135 0 -0 0
- 0.168
-
- 8.687e-05
- 0
- 0
- 0.000150206
- 0
- 0.000216664
-
-
-
- 0 0 0.0135 0 -0 0
-
-
- 0.1 0.074 0.027
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mobilicom.dae
-
-
-
-
-
- mobilicom
- rear_right_box
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.275 0.17 0.2056 -0.5 -0 1.5707963267948966
-
- 0 0 0.085 0 -0 0
- 0.03
-
- 7.3e-05
- 0
- 0
- 7.3e-05
- 0
- 1.5e-06
-
-
-
- 0 0 0.085 0 -0 0
-
-
- 0.17
- 0.01
-
-
-
-
- 0 0 0.085 0 -0 0
-
-
- 0.17
- 0.01
-
-
-
-
-
- mobilicom_antenna_l
- mobilicom
-
-
- 0
- 0
-
- 0 0 1
- 0
-
- -1e+16
- 1e+16
-
-
-
-
-
- 0
- 0.2
-
-
-
-
-
- -0.225 0.17 0.2056 0 -0 1.5707963267948966
-
- 0 0 0.085 0 -0 0
- 0.03
-
- 7.3e-05
- 0
- 0
- 7.3e-05
- 0
- 1.5e-06
-
-
-
- 0 0 0.085 0 -0 0
-
-
- 0.17
- 0.01
-
-
-
-
- 0 0 0.085 0 -0 0
-
-
- 0.17
- 0.01
-
-
-
+ 0.015
+
+
+
-
- mobilicom_antenna_r
- mobilicom
+
+ cliff_sensor_front_right
+ rear_right_box
0
@@ -3474,38 +1931,70 @@
-
- -0.24 -0.16 0.1821 0 0 -3.1415926535897931
+
+ -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
- 0.0845 -0.024 0.0655 0 -0 0
- 0.5
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 0.000931042
+ 1.56725e-06
0
0
- 0.00220342
+ 7.8325e-07
0
- 0.00170437
+ 1.666e-06
-
- 0.0845 -0.024 0.0655 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
- 0.189 0.072 0.131
+ 0.021 0.035 0.0185
-
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mote_deployer.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
+
+ 0.021 0 0.00925 0 -0 0
+ 10
+ 0
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
+
-
- mote_deployer
+
+ cliff_sensor_rear_left
rear_right_box
@@ -3528,73 +2017,70 @@
-
- 0.26 -0.04 0.1921 0 -0 0
+
+ -0.3 -0.1445 0.2106 3.1415926535897931 1.5707963267948966 0
- 0.0155 0 0 0 -0 0
- 0.024
+ 0.0105 0 0.00925 0 -0 0
+ 0.012
- 1.764e-06
+ 1.56725e-06
0
0
- 4.58e-06
+ 7.8325e-07
0
- 4.58e-06
+ 1.666e-06
-
- 0.0155 0 0 0 -0 0
+
+ 0.0105 0 0.00925 0 -0 0
- 0.043 0.021 0.021
+ 0.021 0.035 0.0185
-
- 0 0 0.0105 0 -0 0
+
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flir_boson.dae
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae
-
- 0.03 0 0 0 -0 0
- 1
- 8.6
+
+ 0.021 0 0.00925 0 -0 0
+ 10
0
-
- 1.6057
-
-
- 154.51
- 154.51
- 159.5
- 127.5
- 0
-
- stereographic
- 1
-
-
- 320
- 256
- L8
-
-
- 0.2
- 50
-
-
-
- 253.15
- 673.15
- 1.6
-
+ 1
+
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+ 3
+ 1
+ -0.0314159
+ 0.0314159
+
+
+
+ 0.1
+ 12
+ 0.01
+
+
+ gaussian
+ 0
+ 0.015
+
+
-
- thermocam
+
+ cliff_sensor_rear_right
rear_right_box
@@ -3617,96 +2103,39 @@
-
- -0.256 -0.248 0 0 -0 0
+
+ -0.25 0.12 0.1921 0 -0 1.5707963267948966
- 1e-05
+ 0 0 0.0135 0 -0 0
+ 0.168
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 8.687e-05
+ 0
+ 0
+ 0.000150206
+ 0
+ 0.000216664
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
-
-
-
-
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
-
-
-
-
- 0 0 0 3.1415926535897931 -0 3.1415926535897931
-
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
-
-
-
-
- -0.3035 0 0 0 -0 0
+
+ 0 0 0.0135 0 -0 0
-
- https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
-
-
-
- 1
-
-
- rear_right_flipper
- base_link
-
- 0 1 0
-
- -1e+16
- 1e+16
- 120
- 1
-
-
- 0
- 0
-
- 0
-
-
-
- 1
- 1
-
- 0
- 0.2
-
-
-
-
-
- -0.6375 -0.248 0 0 -0 0
-
- 1e-05
-
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
-
-
+
+ 0.1 0.074 0.027
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mobilicom.dae
+
+
+
-
- rear_right_flipper_end_point_inflated
- rear_right_flipper
+
+ mobilicom
+ rear_right_box
0
@@ -3728,23 +2157,42 @@
-
- -0.6375 -0.248 0 0 -0 0
+
+ -0.275 0.17 0.2056 -0.5 -0 1.5707963267948966
- 1e-05
+ 0 0 0.085 0 -0 0
+ 0.03
- 0.001
- 1e-06
- 1e-06
- 0.001
- 1e-06
- 0.001
+ 7.3e-05
+ 0
+ 0
+ 7.3e-05
+ 0
+ 1.5e-06
+
+ 0 0 0.085 0 -0 0
+
+
+ 0.17
+ 0.01
+
+
+
+
+ 0 0 0.085 0 -0 0
+
+
+ 0.17
+ 0.01
+
+
+
-
- rear_right_flipper_end_point
- rear_right_flipper
+
+ mobilicom_antenna_l
+ mobilicom
0
@@ -3766,425 +2214,349 @@
-
- -0.256 -0.248 0 0 -0 0
+
+ -0.225 0.17 0.2056 0 -0 1.5707963267948966
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0 0 0.085 0 -0 0
+ 0.03
- 0.0017663
+ 7.3e-05
0
0
- 0.0017663
+ 7.3e-05
0
- 0.0031038
+ 1.5e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0 0 0.085 0 -0 0
- 0.075
- 0.1165
+ 0.17
+ 0.01
-
-
-
- 1e+07
- 1
-
- 1
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
- 1
+
+ 0 0 0.085 0 -0 0
+
+
+ 0.17
+ 0.01
+
+
+
-
- rear_right_flipper_wheel1
- rear_right_flipper
+
+ mobilicom_antenna_r
+ mobilicom
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 8.58369
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.299357 -0.248 0 0 -0 0
+
+ -0.24 -0.16 0.1821 0 0 -3.1415926535897931
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.0845 -0.024 0.0655 0 -0 0
+ 0.5
- 0.00162322
+ 0.000931042
0
0
- 0.00162322
+ 0.00220342
0
- 0.00281766
+ 0.00170437
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0845 -0.024 0.0655 0 -0 0
-
- 0.075
- 0.111
-
+
+ 0.189 0.072 0.131
+
-
-
-
- 1e+07
- 1
-
- 2
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
- 1
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/mote_deployer.dae
+
+
+
-
- rear_right_flipper_wheel2
- rear_right_flipper
+
+ mote_deployer
+ rear_right_box
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.00901
-
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.342714 -0.248 0 0 -0 0
+
+ 0.26 -0.04 0.1921 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 0.0155 0 0 0 -0 0
+ 0.024
- 0.00148707
+ 1.764e-06
0
0
- 0.00148707
+ 4.58e-06
0
- 0.00254535
+ 4.58e-06
-
- 0 0 0 1.5707963267948966 -0 0
+
+ 0.0155 0 0 0 -0 0
-
- 0.075
- 0.1055
-
+
+ 0.043 0.021 0.021
+
-
-
-
- 1e+07
- 1
-
- 4
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
- 1
+
+ 0 0 0.0105 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flir_boson.dae
+
+
+
+
+ 0.03 0 0 0 -0 0
+ 1
+ 8.6
+ 0
+
+ 1.6057
+
+
+ 154.51
+ 154.51
+ 159.5
+ 127.5
+ 0
+
+ stereographic
+ 1
+
+
+ 320
+ 256
+ L8
+
+
+ 0.2
+ 50
+
+
+
+ 253.15
+ 673.15
+ 1.6
+
+
-
- rear_right_flipper_wheel3
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 9.47867
-
+
+ thermocam
+ rear_right_box
+
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
-
- -0.386071 -0.248 0 0 -0 0
+
+ -0.256 -0.248 0 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ -0.08 0 0 0 -0 0
+ 3.659
- 0.00135783
- 0
- 0
- 0.00135783
- 0
- 0.00228687
+ 0.0017491
+ 2.8512e-07
+ 0.0018277
+ 0.012277
+ -3.6288e-07
+ 0.010941
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0 0 -0 0
-
- 0.075
- 0.1
-
+
+ 0.3035 0.075 0.078
+
-
-
- 1e+07
- 1
-
- 8
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel4
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10
-
-
- 0
- 0
-
- 0
-
-
-
- -0.429429 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00123551
- 0
- 0
- 0.00123551
- 0
- 0.00204224
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.15175 0 0.05825 0 -0.126179 0
-
- 0.075
- 0.0945
-
+
+ 0.3035 0.075 0.078
+
-
+
- 1e+07
- 1
+ 1
+ 150
+ 0 0 1
- 16
-
+
+
+
+
+ -0.15175 0 -0.05825 0 0.126179 0
+
+
+ 0.3035 0.075 0.078
+
+
+
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel5
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 10.582
-
-
- 0
- 0
-
- 0
-
-
-
- -0.472786 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00112011
- 0
- 0
- 0.00112011
- 0
- 0.00181143
-
-
-
- 0 0 0 1.5707963267948966 -0 0
+
+ -0.3035 0 0 1.5707963267948966 -0 0
0.075
- 0.089
+ 0.078
-
-
- 1e+07
- 1
-
- 32
-
1
150
- 0.000575601
- 0
0 0 1
- 1
-
-
- rear_right_flipper_wheel6
- rear_right_flipper
-
- 0 1 0
-
- -1e+16
- 1e+16
- -1
- 11.236
-
-
- 0
- 0
-
- 0
-
-
-
- -0.516143 -0.248 0 0 -0 0
-
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
-
- 0.00101163
- 0
- 0
- 0.00101163
- 0
- 0.00159447
-
-
-
+
0 0 0 1.5707963267948966 -0 0
0.075
- 0.0835
+ 0.1165
-
-
- 1e+07
- 1
-
- 64
-
1
150
- 0.000575601
- 0
0 0 1
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.dae
+
+
+
+
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.dae
+
+
+
+
+ 0 0 0 3.1415926535897931 -0 3.1415926535897931
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/belt.dae
+
+
+
+
+ -0.3035 0 0 0 -0 0
+
+
+ https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/small_wheel.dae
+
+
+
1
-
- rear_right_flipper_wheel7
- rear_right_flipper
+
+ rear_right_flipper
+ base_link
0 1 0
-1e+16
1e+16
- -1
- 11.976
+ 120
+ 1
0
@@ -4192,67 +2564,92 @@
0
+
+
+ 1
+ 1
+
+ 0
+ 0.2
+
+
+
-
- -0.5595 -0.248 0 0 -0 0
+
+ -0.6375 -0.248 0 0 -0 0
- 0 0 0 1.5707963267948966 -0 0
- 0.457375
+ 1e-05
- 0.000910062
- 0
- 0
- 0.000910062
- 0
- 0.00139133
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
-
- 0 0 0 1.5707963267948966 -0 0
-
-
- 0.075
- 0.078
-
-
-
-
-
- 1e+07
- 1
-
- 128
-
-
-
- 1
- 150
- 0.000575601
- 0
- 0 0 1
-
-
-
-
- 1
-
- rear_right_flipper_wheel8
+
+ rear_right_flipper_end_point_inflated
rear_right_flipper
- 0 1 0
+
+ 0
+ 0
+
+ 0 0 1
+ 0
-1e+16
1e+16
- -1
- 12.8205
+
+
+
+
+ 0
+ 0.2
+
+
+
+
+
+ -0.6375 -0.248 0 0 -0 0
+
+ 1e-05
+
+ 0.001
+ 1e-06
+ 1e-06
+ 0.001
+ 1e-06
+ 0.001
+
+
+
+
+ rear_right_flipper_end_point
+ rear_right_flipper
+
0
0
+ 0 0 1
0
+
+ -1e+16
+ 1e+16
+
+
+
+
+ 0
+ 0.2
+
+
+
@@ -4952,200 +3349,6 @@
rear_left_flipper_j
rear_right_flipper_j
-
-
- 0.0485
- 0
- 7.60075
- 0.078
-
-
- 0.0485
- 0
- 7.60075
- 0.0835
-
-
- 0.0485
- 0
- 7.60075
- 0.089
-
-
- 0.0485
- 0
- 7.60075
- 0.0945
-
-
- 0.0485
- 0
- 7.60075
- 0.1
-
-
- 0.0485
- 0
- 7.60075
- 0.1055
-
-
- 0.0485
- 0
- 7.60075
- 0.111
-
-
- 0.0485
- 0
- 7.60075
- 0.1165
-
-
- 0.0485
- 0
- 7.60075
- 0.078
-
-
- 0.0485
- 0
- 7.60075
- 0.0835
-
-
- 0.0485
- 0
- 7.60075
- 0.089
-
-
- 0.0485
- 0
- 7.60075
- 0.0945
-
-
- 0.0485
- 0
- 7.60075
- 0.1
-
-
- 0.0485
- 0
- 7.60075
- 0.1055
-
-
- 0.0485
- 0
- 7.60075
- 0.111
-
-
- 0.0485
- 0
- 7.60075
- 0.1165
-
-
- 0.0485
- 0
- 7.60075
- 0.078
-
-
- 0.0485
- 0
- 7.60075
- 0.0835
-
-
- 0.0485
- 0
- 7.60075
- 0.089
-
-
- 0.0485
- 0
- 7.60075
- 0.0945
-
-
- 0.0485
- 0
- 7.60075
- 0.1
-
-
- 0.0485
- 0
- 7.60075
- 0.1055
-
-
- 0.0485
- 0
- 7.60075
- 0.111
-
-
- 0.0485
- 0
- 7.60075
- 0.1165
-
-
- 0.0485
- 0
- 7.60075
- 0.078
-
-
- 0.0485
- 0
- 7.60075
- 0.0835
-
-
- 0.0485
- 0
- 7.60075
- 0.089
-
-
- 0.0485
- 0
- 7.60075
- 0.0945
-
-
- 0.0485
- 0
- 7.60075
- 0.1
-
-
- 0.0485
- 0
- 7.60075
- 0.1055
-
-
- 0.0485
- 0
- 7.60075
- 0.111
-
-
- 0.0485
- 0
- 7.60075
- 0.1165
-
-