From 2c6dc8c8e794bd35239f2b0646a458ef0070a40c Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Sun, 20 Jun 2021 21:52:32 +0200 Subject: [PATCH 01/14] Absolem: fix bad merge. --- .../urdf/basler_cameras.xacro | 123 ++++++++++++++++++ .../urdf/nifti_robot.xacro | 113 +++++++++++++--- .../urdf/utils.xacro | 16 +++ 3 files changed, 235 insertions(+), 17 deletions(-) create mode 100644 submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/basler_cameras.xacro diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/basler_cameras.xacro b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/basler_cameras.xacro new file mode 100644 index 00000000..0dad1d67 --- /dev/null +++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/basler_cameras.xacro @@ -0,0 +1,123 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ${virtual_lens_origin} 0 ${camera_height/2} 0 0 0 + ${frame_rate} + ${visualize} + + ${radians(hfov_deg)} + + ${resolution_x} + ${resolution_y} + R8G8B8 + + + + ${clip} + 300 + + + gaussian + 0.0 + 0.007 + + + + stereographic + true + ${pi} + 1024 + + + + + + + ${f} + ${f} + ${(resolution_x - 1) / 2} + ${(resolution_y - 1) / 2} + 0 + + + + + + + + + + + + + + + + + \ No newline at end of file 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 30fccaec..5bd60a65 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 @@ -440,6 +440,9 @@ + + + @@ -718,6 +721,14 @@ filename="package://ctu_cras_norlab_absolem_sensor_config_1/meshes/${top_box_mesh_name}"/> + + + + + + + + @@ -792,7 +803,37 @@ - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -852,7 +893,12 @@ - + + + + + + @@ -1294,22 +1340,49 @@ + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - + + + + + + + + + + + + @@ -1643,9 +1716,15 @@ - - + + + + + + + diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/utils.xacro b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/utils.xacro index ccab9e53..4bcec06e 100644 --- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/utils.xacro +++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/urdf/utils.xacro @@ -66,4 +66,20 @@ + + + + + + + 0 0 0 0 + + ${max(0, r - 60/255.0)} ${max(0, g - 60/255.0)} ${max(0, b - 60/255.0)} 1 + 0 0 0 0 + 0 0 0 0 + + + + + \ No newline at end of file From b6803aa89363aee7c86ba62b769717b8e8aa1822 Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Sun, 20 Jun 2021 23:00:12 +0200 Subject: [PATCH 02/14] Implement more plausible model of tracks. --- .../config/common.yaml | 3 + .../launch/common.rb | 145 +- .../model.sdf | 2538 ++-------- .../urdf/nifti_robot.xacro | 233 +- .../model.sdf | 3124 +++---------- .../model.sdf | 3124 +++---------- .../model.sdf | 3274 ++++--------- .../model.sdf | 3954 +++++----------- .../model.sdf | 3954 +++++----------- .../model.sdf | 4076 +++++------------ .../config/sim.yaml | 2 +- .../launch/common.rb | 87 +- .../model.sdf | 3999 +++++----------- .../urdf/marv.xacro | 17 +- .../model.sdf | 4017 +++++----------- .../model.sdf | 3947 +++++----------- .../model.sdf | 4059 +++++----------- 17 files changed, 10888 insertions(+), 29665 deletions(-) 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..373794b2 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,106 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add diffdriveJoints[i] = "" end wheelSlip = "" + trackControllers = "" + trackLinks = "" for track in tracks - for wheel in 1..numTrackWheels - diffdriveJoints[0] += "<#{track}_joint>#{track}_track_wheel#{wheel}_j\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\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" end for flipper in flippersOfTrack[track] - for wheel in 1..numFlipperWheels - diffdriveJoints[wheel-1] += "<#{track}_joint>#{flipper}_flipper_wheel#{wheel}_j\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\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" 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 +150,8 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add #{_modelURI} #{diffDrive} + #{trackedVehicle} + #{trackControllers} @@ -119,9 +186,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add 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 8df5f808..0e4403b0 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 @@ -849,26 +849,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 @@ -920,26 +958,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 @@ -983,11 +1093,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 @@ -997,7 +1107,7 @@ 0.010941 - + 0 0 0 1.5707963267948966 -0 0 @@ -1006,146 +1116,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 @@ -1153,251 +1220,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 @@ -1405,89 +1289,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 @@ -1495,1636 +1324,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 @@ -3132,170 +1467,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 @@ -3303,6 +1605,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..7ecd0b95 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 @@ - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + 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 baf05902..ee07f78a 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 @@ -663,26 +663,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 @@ -734,26 +772,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 @@ -797,11 +907,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 @@ -811,7 +921,7 @@ 0.010941 - + 0 0 0 1.5707963267948966 -0 0 @@ -820,317 +930,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 @@ -1138,1669 +1034,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 @@ -2808,296 +1217,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 @@ -3107,8 +1490,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 @@ -3116,56 +1516,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 @@ -3173,32 +1534,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 @@ -3206,170 +1569,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 @@ -3377,170 +1712,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 @@ -3548,6 +1850,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 607c2aa4..0fa66680 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 @@ -679,26 +679,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 @@ -750,26 +788,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 @@ -813,11 +923,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 @@ -827,7 +937,7 @@ 0.010941 - + 0 0 0 1.5707963267948966 -0 0 @@ -836,317 +946,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 @@ -1154,1669 +1050,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 @@ -2824,296 +1233,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 @@ -3123,8 +1506,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 @@ -3132,56 +1532,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 @@ -3189,32 +1550,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 @@ -3222,170 +1585,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 @@ -3393,170 +1728,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 @@ -3564,6 +1866,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 9ca0eaf3..05bebd1f 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 @@ -679,26 +679,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 @@ -750,26 +788,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 @@ -813,11 +923,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 @@ -827,7 +937,7 @@ 0.010941 - + 0 0 0 1.5707963267948966 -0 0 @@ -836,260 +946,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 @@ -1097,1815 +1050,268 @@ 0 - - - 0.25 0.1985 0.01855 0 -0 0 - - 0 0 0.0141 0 -0 0 - 0.7575 + + + 1 + 1 + + 0 + 0.2 + + + + + + 0.275 0.119535 0.2035 -1.5707963267948966 1.5707963267948966 0 + + 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 @@ -2913,296 +1319,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 @@ -3212,8 +1595,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 @@ -3221,56 +1621,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 @@ -3278,32 +1639,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 @@ -3311,170 +1674,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 @@ -3482,170 +1817,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 @@ -3653,6 +1955,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 38727173..bcfffa85 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 @@ -441,26 +441,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 @@ -512,26 +550,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 @@ -575,11 +685,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 @@ -589,7 +699,7 @@ 0.010941 - + 0 0 0 1.5707963267948966 -0 0 @@ -598,260 +708,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 @@ -859,522 +812,610 @@ 0 - - - 0.25 0.1985 0.01855 0 -0 0 - - 0 0 0.0141 0 -0 0 - 0.7575 + + + 1 + 1 + + 0 + 0.2 + + + + + + 0.185 0 0.195 0 -0 0 + + 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 @@ -1382,1736 +1423,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 @@ -3119,296 +1595,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 @@ -3418,8 +1801,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 @@ -3427,56 +1827,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 @@ -3484,32 +1845,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 @@ -3517,170 +1880,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 @@ -3688,170 +2023,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 @@ -3859,6 +2161,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 959607f4..b6aee5aa 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 @@ -457,26 +457,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 @@ -528,26 +566,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 @@ -591,11 +701,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 @@ -605,7 +715,7 @@ 0.010941 - + 0 0 0 1.5707963267948966 -0 0 @@ -614,260 +724,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 @@ -875,522 +828,610 @@ 0 - - - 0.25 0.1985 0.01855 0 -0 0 - - 0 0 0.0141 0 -0 0 - 0.7575 + + + 1 + 1 + + 0 + 0.2 + + + + + + 0.185 0 0.195 0 -0 0 + + 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 @@ -1398,1736 +1439,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 @@ -3135,296 +1611,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 @@ -3434,8 +1817,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 @@ -3443,56 +1843,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 @@ -3500,32 +1861,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 @@ -3533,170 +1896,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 @@ -3704,170 +2039,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 @@ -3875,6 +2177,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 034c279a..b69ca503 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 @@ -457,26 +457,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 @@ -528,26 +566,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 @@ -591,11 +701,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 @@ -605,7 +715,7 @@ 0.010941 - + 0 0 0 1.5707963267948966 -0 0 @@ -614,260 +724,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 @@ -875,522 +828,610 @@ 0 - - - 0.25 0.1985 0.01855 0 -0 0 - - 0 0 0.0141 0 -0 0 - 0.7575 + + + 1 + 1 + + 0 + 0.2 + + + + + + 0.185 0 0.195 0 -0 0 + + 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 @@ -1398,1825 +1439,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 @@ -3224,296 +1700,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 @@ -3523,8 +1906,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 @@ -3532,56 +1932,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 @@ -3589,32 +1950,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 @@ -3622,170 +1985,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 @@ -3793,170 +2128,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 @@ -3964,6 +2266,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..5036d61a 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,75 @@ 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 = "" + 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" + 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 +104,8 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add #{_modelURI} #{diff_drive} + #{trackedVehicle} + #{trackControllers} diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf index 6ccedcea..92ce3fe8 100644 --- a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf +++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/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.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,1443 +977,137 @@ - - 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.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 + + + + + - - rear_right_box + + imu base_link @@ -2748,66 +1130,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 @@ -2817,10 +1199,10 @@ - 1020.51 - 1020.51 - 959.5 - 599.5 + 393.077 + 393.077 + 1023.5 + 767.5 0 stereographic @@ -2829,23 +1211,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 @@ -2853,90 +1396,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 @@ -2958,71 +1434,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 @@ -3043,72 +1471,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 @@ -3130,71 +1510,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 @@ -3216,70 +1548,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 @@ -3302,38 +1653,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 @@ -3356,42 +1758,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 @@ -3413,42 +1844,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 @@ -3470,72 +1930,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 @@ -3543,23 +2016,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 @@ -3581,23 +2102,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 @@ -3619,425 +2156,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 @@ -4045,67 +2420,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 + + + @@ -4805,200 +3205,7 @@ 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..bb2e1552 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 @@ - + + + + + + + + + + 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 3438077c..0f77a312 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,1443 +977,137 @@ - - 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.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 + + + + + - - rear_right_box + + imu base_link @@ -2748,66 +1130,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 @@ -2817,10 +1199,10 @@ - 1020.51 - 1020.51 - 959.5 - 599.5 + 393.077 + 393.077 + 1023.5 + 767.5 0 stereographic @@ -2829,23 +1211,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 @@ -2853,90 +1396,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 @@ -2958,71 +1434,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 @@ -3044,71 +1472,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 @@ -3130,71 +1510,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 @@ -3216,70 +1548,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 @@ -3302,38 +1653,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 @@ -3356,42 +1758,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 @@ -3413,42 +1844,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 @@ -3470,38 +1930,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 @@ -3524,72 +2016,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 @@ -3597,23 +2102,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 @@ -3635,23 +2156,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 @@ -3673,425 +2213,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 @@ -4099,67 +2474,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 + + + @@ -4859,200 +3259,7 @@ 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 155ac4a3..ffc53114 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 @@ -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.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 - - @@ -1289,1381 +977,407 @@ - - 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.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 + 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 + + + + + - - rear_left_flipper_wheel1 - rear_left_flipper + + imu + base_link - 0 1 0 - - -1e+16 - 1e+16 - -1 - 8.58369 - 0 0 + 0 0 1 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 + 0.2 + + + - - -0.342714 0.248 0 3.1415926535897931 -0 3.1415926535897931 + + -0.244 0 0.1321 0 0 -3.1415926535897931 - 0 0 0 1.5707963267948966 -0 0 - 0.457375 + 0.019862 0 0.0145 0 -0 0 + 0.14 - 0.00148707 + 1.96233e-05 0 0 - 0.00148707 + 6.75088e-05 0 - 0.00254535 + 6.75088e-05 - - 0 0 0 1.5707963267948966 -0 0 + + 0.0117 0 0.0145 0 -0 0 - - 0.075 - 0.1055 - + + 0.054 0.029 0.029 + - - - - 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.042024 0 0.0145 0 1.5707963267948966 0 - 0.075 - 0.1 + 0.026 + 0.0125 - - - - 1e+07 - 1 - - 8 - - - - 1 - 150 - 0.000580373 - 0 - 0 0 1 - - - - 1 + + 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_left_flipper_wheel4 - rear_left_flipper + + rear_cam + base_link - 0 1 0 - - -1e+16 - 1e+16 - -1 - 10 - 0 0 + 0 0 1 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 + 0.2 + + + - - -0.472786 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.00112011 - 0 - 0 - 0.00112011 - 0 - 0.00181143 + 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.3035 0.075 0.078 + + + + + + 1 + 150 + 0 0 1 + + + + + + 0.15175 0 0.05825 0 0.126179 0 - - 0.075 - 0.089 - + + 0.3035 0.075 0.078 + - + - 1e+07 - 1 + 1 + 150 + 0 0 1 - 32 - + + + + + 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_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.3035 0 0 1.5707963267948966 -0 0 0.075 - 0.0835 + 0.078 - - - 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 + 0.1165 - - - 1e+07 - 1 - - 128 - 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 + + + + + + + -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_wheel8 - rear_left_flipper + + rear_left_flipper + base_link 0 1 0 -1e+16 1e+16 - -1 - 12.8205 + 120 + 1 0 @@ -2671,38 +1385,10 @@ 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 - - + 1 + 1 0 0.2 @@ -2710,8 +1396,8 @@ - - -0.3 -0.18 0.1921 0 -0 0 + + -0.6375 0.248 0 3.1415926535897931 -0 3.1415926535897931 1e-05 @@ -2724,9 +1410,9 @@ - - rear_right_box - base_link + + rear_left_flipper_end_point_inflated + rear_left_flipper 0 @@ -2734,104 +1420,37 @@ 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 - - - + + -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 + + - - camera_0 - rear_right_box + + rear_left_flipper_end_point + rear_left_flipper 0 @@ -2853,90 +1472,23 @@ - - -0.21 0 0.1921 0 -0 3.1415926535897931 + - 0.039802 0 0.0145 0 -0 0 - 0.232 + -0.22 -0.09 0.02 0 -0 0 + 4.06 - 3.25187e-05 + 0.0151492 0 0 - 0.000158598 + 0.0129839 0 - 0.000158598 + 0.0173903 - - 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_motor + base_link 0 @@ -2958,71 +1510,23 @@ - - 0.3 0.1445 0.2106 0 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 - - - - - - - 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_right_box + base_link 0 @@ -3044,70 +1548,89 @@ - - 0.3 -0.1445 0.2106 0 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 - 1 - - - - 3 - 1 - -0.0314159 - 0.0314159 - - - 3 - 1 - -0.0314159 - 0.0314159 - - - - 0.1 - 12 - 0.01 - + + 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.015 + 0.007 - + + + 1020.51 + 1020.51 + 959.5 + 599.5 + 0 + + stereographic + 1 + + - - cliff_sensor_front_right + + camera_0 rear_right_box @@ -3130,70 +1653,89 @@ - - -0.3 0.1445 0.2106 3.1415926535897931 1.5707963267948966 0 + + -0.21 0 0.1921 0 -0 3.1415926535897931 - 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_left + + camera_2 rear_right_box @@ -3216,8 +1758,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 @@ -3230,7 +1772,7 @@ 1.666e-06 - + 0.0105 0 0.00925 0 -0 0 @@ -3238,7 +1780,7 @@ - + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/tfmini_plus_lidar.dae @@ -3274,124 +1816,13 @@ 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 + + cliff_sensor_front_left + rear_right_box 0 @@ -3413,42 +1844,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 @@ -3470,62 +1930,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 - - 320 - 256 - L16 - - - 0.2 - 50 - - - - 223.15 - 453.15 - 0.06 - + 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_left rear_right_box @@ -3548,72 +2016,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 - - 0 1 0 - - -1e+16 - 1e+16 - 120 - 1 - + + cliff_sensor_rear_right + rear_right_box + 0 0 + 0 0 1 0 + + -1e+16 + 1e+16 + - 1 - 1 0 0.2 @@ -3621,23 +2102,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 @@ -3659,23 +2156,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 @@ -3697,425 +2213,284 @@ - - -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.000580373 - 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.000580373 - 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.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 + + 320 + 256 + L16 + + + 0.2 + 50 + + + + 223.15 + 453.15 + 0.06 + + - - 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 @@ -4123,67 +2498,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 + + + @@ -4883,200 +3283,7 @@ 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 9eb58e59..01a4dd88 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 @@ -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.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 - - @@ -1289,1443 +977,137 @@ - - 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 - - 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 - - - - - - - - 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.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.075 - 0.111 - - - - - - 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.075 - 0.1055 - - - - - - 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.075 - 0.1 - - - - - - 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 - - - - - - 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 - - - - - - 1e+07 - 1 - - 32 - - - - 1 - 150 - 0.000575601 - 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.000575601 - 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.000575601 - 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 + + + + + - - rear_right_box + + imu base_link @@ -2748,66 +1130,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 @@ -2817,10 +1199,10 @@ - 1020.51 - 1020.51 - 959.5 - 599.5 + 393.077 + 393.077 + 1023.5 + 767.5 0 stereographic @@ -2829,9 +1211,9 @@ - - camera_0 - rear_right_box + + rear_cam + base_link 0 @@ -2853,104 +1235,160 @@ - - -0.21 0 0.1921 0 -0 3.1415926535897931 + + -0.256 0.248 0 3.1415926535897931 -0 -3.1415926535897931 - 0.039802 0 0.0145 0 -0 0 - 0.232 + 0.08 0 0 0 -0 0 + 3.659 - 3.25187e-05 - 0 - 0 - 0.000158598 - 0 - 0.000158598 + 0.0017491 + 2.8512e-07 + 0.0018277 + 0.012277 + -3.6288e-07 + 0.010941 - - 0.02465 0 0.0145 0 -0 0 + + 0.15175 0 0 0 -0 0 - 0.0555 0.029 0.029 + 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.062834 0 0.0145 0 1.5707963267948966 0 + + 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.03974 - 0.0125 + 0.075 + 0.078 + + + + 1 + 150 + 0 0 1 + + + - - 0 0 0.0145 0 -0 0 + + 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/basler_ace2_pro.dae + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/big_wheel.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 + -1 -1 1 + https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/CTU_CRAS_NORLAB_MARV_SENSOR_CONFIG_1/tip/files/meshes/flipper_arm.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 - - - + + + + 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 - - camera_2 - 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 @@ -2958,71 +1396,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_inflated + rear_left_flipper 0 @@ -3044,71 +1434,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 + rear_left_flipper 0 @@ -3130,71 +1472,23 @@ - - -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 - - 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_motor + base_link 0 @@ -3216,71 +1510,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 - - - - 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 - - - + 1e-05 + + 0.001 + 1e-06 + 1e-06 + 0.001 + 1e-06 + 0.001 + + - - cliff_sensor_rear_right - rear_right_box + + rear_right_box + base_link 0 @@ -3302,38 +1548,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 @@ -3356,42 +1653,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 @@ -3413,42 +1758,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 @@ -3470,38 +1844,70 @@ - - -0.24 -0.16 0.1821 0 0 -3.1415926535897931 + + 0.3 -0.1445 0.2106 0 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_front_right rear_right_box @@ -3524,62 +1930,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 - - 320 - 256 - L16 - - - 0.2 - 50 - - - - 223.15 - 453.15 - 0.06 - + 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_left rear_right_box @@ -3602,72 +2016,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 @@ -3675,23 +2102,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 @@ -3713,23 +2156,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 @@ -3751,425 +2213,338 @@ - - -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 + + 320 + 256 + L16 + + + 0.2 + 50 + + + + 223.15 + 453.15 + 0.06 + + - - 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 @@ -4177,67 +2552,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 + + + @@ -4937,200 +3337,7 @@ 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 - - + From c0ee4ff68fcd705b8bee0e38240d38925945af9e Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Tue, 17 Aug 2021 01:42:55 +0200 Subject: [PATCH 03/14] Merge upstream thermal cam settings for MARV SC3 --- .../model.sdf | 24 +++++++++++++++---- 1 file changed, 19 insertions(+), 5 deletions(-) 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 ffc53114..2c69bd75 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,5 +1,8 @@ - + + @@ -2307,10 +2310,21 @@ 0 1.6057 + + + 154.51 + 154.51 + 159.5 + 127.5 + 0 + + stereographic + 1 + 320 256 - L16 + L8 0.2 @@ -2318,9 +2332,9 @@ - 223.15 - 453.15 - 0.06 + 253.15 + 673.15 + 1.6 From 0a298b220df13569b37bc618941765e0fd59cee3 Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Mon, 15 Nov 2021 23:18:01 +0100 Subject: [PATCH 04/14] Update with latest changes. --- .../model.sdf | 2 +- .../urdf/nifti_robot.xacro | 1 + .../model.sdf | 2 +- .../model.sdf | 2 +- .../model.sdf | 2 +- .../model.sdf | 2 +- .../model.sdf | 2 +- .../model.sdf | 2 +- .../model.sdf | 7 ++--- .../urdf/marv.xacro | 1 + .../model.sdf | 7 ++--- .../model.sdf | 7 ++--- .../model.sdf | 26 ++++++++++++------- 13 files changed, 32 insertions(+), 31 deletions(-) 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 f43e4de2..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 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 7ecd0b95..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 @@ -2007,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 8c65d294..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 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 7ece47be..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 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 8f99c2a8..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 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 3a78b962..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 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 efa11bd9..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 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 b825e860..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 diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf index 0e84dec7..a1464614 100644 --- a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf +++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf @@ -1,8 +1,5 @@ - - + @@ -1036,7 +1033,6 @@ 1 50 - 0 @@ -1107,6 +1103,7 @@ + 0 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 bb2e1552..649cda5c 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 @@ -856,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 3fde80f3..284abb3d 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 @@ -1,8 +1,5 @@ - - + @@ -1036,7 +1033,6 @@ 1 50 - 0 @@ -1107,6 +1103,7 @@ + 0 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 91852f60..ad85bce8 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 @@ - - + @@ -1036,7 +1033,6 @@ 1 50 - 0 @@ -1107,6 +1103,7 @@ + 0 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 019b9986..11d9195b 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 @@ - - + @@ -1036,7 +1033,6 @@ 1 50 - 0 @@ -1107,6 +1103,7 @@ + 0 @@ -2365,10 +2362,21 @@ 0 1.6057 + + + 154.51 + 154.51 + 159.5 + 127.5 + 0 + + stereographic + 1 + 320 256 - L16 + L8 0.2 @@ -2376,9 +2384,9 @@ - 223.15 - 453.15 - 0.06 + 253.15 + 673.15 + 1.6 From bbbbe3979595c7b85de4974c279b2d439fe1dce8 Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Tue, 16 Nov 2021 18:46:53 +0100 Subject: [PATCH 05/14] Removed empty wheel slip plugin. --- submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf | 1 - .../ctu_cras_norlab_marv_sensor_config_1/urdf/marv.xacro | 2 +- submitted_models/ctu_cras_norlab_marv_sensor_config_2/model.sdf | 1 - submitted_models/ctu_cras_norlab_marv_sensor_config_3/model.sdf | 1 - submitted_models/ctu_cras_norlab_marv_sensor_config_4/model.sdf | 1 - 5 files changed, 1 insertion(+), 5 deletions(-) diff --git a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf index a1464614..63e0fb53 100644 --- a/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf +++ b/submitted_models/ctu_cras_norlab_marv_sensor_config_1/model.sdf @@ -3206,7 +3206,6 @@ rear_left_flipper_j rear_right_flipper_j - 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 649cda5c..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 @@ -762,7 +762,7 @@ - + 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 284abb3d..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 @@ -3260,7 +3260,6 @@ rear_left_flipper_j rear_right_flipper_j - 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 ad85bce8..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 @@ -3295,7 +3295,6 @@ rear_left_flipper_j rear_right_flipper_j - 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 11d9195b..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 @@ -3349,7 +3349,6 @@ rear_left_flipper_j rear_right_flipper_j - From 23bec12097e1772fe65f13d1ffe376b38800e07d Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Wed, 5 Jan 2022 18:07:55 +0100 Subject: [PATCH 06/14] Use power_draining_topic to start battery drain for tracked vehicles. --- .../ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb | 4 ++++ .../ctu_cras_norlab_marv_sensor_config_1/launch/common.rb | 3 +++ 2 files changed, 7 insertions(+) diff --git a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb index 373794b2..48f1ac79 100644 --- a/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb +++ b/submitted_models/ctu_cras_norlab_absolem_sensor_config_1/launch/common.rb @@ -36,6 +36,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add wheelSlip = "" trackControllers = "" trackLinks = "" + power_draining_topics = "" for track in tracks if useWheels @@ -61,6 +62,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add HEREDOC trackLinks += "<#{track}_track>#{track}_track" + power_draining_topics += "/model/#{_name}/link/#{track}_track/track_cmd_vel" end for flipper in flippersOfTrack[track] if useWheels @@ -86,6 +88,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add HEREDOC trackLinks += "<#{track}_track>#{flipper}_flipper" + power_draining_topics += "/model/#{_name}/link/#{flipper}_flipper/track_cmd_vel" end end end @@ -177,6 +180,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add 1.9499 4.95 true + #{power_draining_topics} 0 for wheel_num in 1..num_wheels # we only want odometry from the first diffdrive @@ -71,6 +72,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add HEREDOC trackLinks += "<#{track}_track>#{flipper}_flipper" + power_draining_topics += "/model/#{_name}/link/#{flipper}_flipper/track_cmd_vel" end end trackedVehicle += <<-HEREDOC @@ -131,6 +133,7 @@ def _spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw, _add 1.9499 9.9 true + #{power_draining_topics} Date: Thu, 18 Nov 2021 12:07:39 +0100 Subject: [PATCH 07/14] CCN Marmotte: Implement proper tracks. --- .../launch/example.ign | 10 +- .../launch/spawner.rb | 82 +--- .../model.sdf | 372 +++--------------- .../specifications.md | 6 +- .../urdf/robot_from_sdf.xacro | 116 +----- .../worlds/example.sdf | 7 + .../launch/example.ign | 20 + .../launch/spawner.rb | 110 ++---- 8 files changed, 155 insertions(+), 568 deletions(-) create mode 100644 submitted_models/ctu_cras_norlab_marmotte_sensor_config_2/launch/example.ign diff --git a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/launch/example.ign b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/launch/example.ign index 6cec8f92..5a950369 100644 --- a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/launch/example.ign +++ b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/launch/example.ign @@ -6,7 +6,9 @@ --> <% - require_relative 'spawner' + #require_relative 'spawner' + _base_dir = defined?(base_dir) ? base_dir.tr('"', '') : File.realpath(File.join(File.dirname(__FILE__), "..")) + load File.join(_base_dir, "launch", "spawner.rb") # Modify these as needed $enableGroundTruth = true @@ -34,9 +36,11 @@ +<% if local_variables.include?(:ros) and ros %> roslaunch subt_ros competition_init.launch world_name:=<%=$worldName%> vehicle_topics:=0 enable_ground_truth:=<%=($enableGroundTruth)?"1":"0"%> robot_names:=<%=robotName%> +<% end %> @@ -166,7 +170,9 @@ filename="ignition-launch-gazebo-factory"> <%= spawner(robotName, modelURI, $worldName, 0, 0, 0, 0, 0, 0) %> -<%= rosExecutables(robotName, $worldName) %> +<% if local_variables.include?(:ros) and ros %> + <%= rosExecutables(robotName, $worldName) %> +<% end %> diff --git a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/launch/spawner.rb b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/launch/spawner.rb index 8139b94c..f3f01f44 100644 --- a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/launch/spawner.rb +++ b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/launch/spawner.rb @@ -10,24 +10,20 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw) #{_name} #{_modelURI} - - - front_left_wheel_joint - front_middle_left_wheel_joint - rear_middle_left_wheel_joint - rear_left_wheel_joint - front_right_wheel_joint - front_middle_right_wheel_joint - rear_middle_right_wheel_joint - rear_right_wheel_joint - #{0.525} - 0.129 + + + left_track + right_track + #{0.525} + 0.258 + 0.5 /model/#{_name}/cmd_vel_relay - -1 - 1 - -3 - 3 + + -1 + 1 + -3 + 3 + 10 gas - - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0.25 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - diff --git a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/model.sdf b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/model.sdf index b46ce2c4..a035588c 100644 --- a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/model.sdf +++ b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/model.sdf @@ -718,80 +718,23 @@ - - - 0.360 0.26 0.00 0 -0 0 + + + 0 0.26 0.00 0 -0 0 0 0 0 0 -0 0 - 1.5 - - 0.02467 + 6.0 + + 0.03828 0 0 - 0.04411 + 0.2925 0 - 0.02467 + 0.2642 - 0 0 0 1.5707963267948966 -0 0 - - - 0.1 - 0.129 - - - - - - 1e+07 - 1 - - - - - 0.5 - 1 - 0.001 - 0 - 0 0 1 - - - - - - - front_left_wheel_link - base_link - - 0 1 0 - - -1e+16 - 1e+16 - - - 0 - 0 - - 1 - - - - 0.120 0.26 0.00 0 -0 0 - - 0 0 0 0 -0 0 - 1.5 - - 0.02467 - 0 - 0 - 0.04411 - 0 - 0.02467 - - - - 0 0 0 1.5707963267948966 -0 0 + 0.360 0 0 1.5707963267948966 -0 0 0.1 @@ -807,65 +750,8 @@ - 0.5 - 1 - 0.001 - 0 - 0 0 1 - - - - - - - front_middle_left_wheel_link - base_link - - 0 1 0 - - -1e+16 - 1e+16 - - - 0 - 0 - - 1 - - - - -0.120 0.26 0.00 0 -0 0 - - 0 0 0 0 -0 0 - 1.5 - - 0.02467 - 0 - 0 - 0.04411 - 0 - 0.02467 - - - - 0 0 0 1.5707963267948966 -0 0 - - - 0.1 - 0.129 - - - - - - 1e+07 - 1 - - - - - 0.5 - 1 + 1 + 150 0.001 0 0 0 1 @@ -873,39 +759,8 @@ - - - rear_middle_left_wheel_link - base_link - - 0 1 0 - - -1e+16 - 1e+16 - - - 0 - 0 - - 1 - - - - -0.36 0.26 0.0 0 -0 0 - - 0 0 0 0 -0 0 - 1.5 - - 0.02467 - 0 - 0 - 0.04411 - 0 - 0.02467 - - - 0 0 0 1.5707963267948966 -0 0 + -0.36 0 0 1.5707963267948966 -0 0 0.1 @@ -921,8 +776,8 @@ - 0.5 - 1 + 1 + 150 0.001 0 0 0 1 @@ -930,45 +785,11 @@ - - - rear_left_wheel_link - base_link - - 0 1 0 - - -1e+16 - 1e+16 - - - 0 - 0 - - 1 - - - - - 0.360 -0.26 0.00 0 -0 0 - - 0 0 0 0 -0 0 - 1.5 - - 0.02467 - 0 - 0 - 0.04411 - 0 - 0.02467 - - - - 0 0 0 1.5707963267948966 -0 0 + - - 0.1 - 0.129 - + + 0.72 0.1 0.258 + @@ -979,8 +800,8 @@ - 0.5 - 1 + 1 + 150 0.001 0 0 0 1 @@ -989,38 +810,27 @@ - - front_right_wheel_link + + left_track base_link - - 0 1 0 - - -1e+16 - 1e+16 - - - 0 - 0 - - 1 - - - 0.120 -0.26 0.00 0 -0 0 + + + 0 -0.26 0.00 0 -0 0 0 0 0 0 -0 0 - 1.5 - - 0.02467 + 6.0 + + 0.03828 0 0 - 0.04411 + 0.2925 0 - 0.02467 + 0.2642 - - 0 0 0 1.5707963267948966 -0 0 + + 0.360 0 0 1.5707963267948966 -0 0 0.1 @@ -1036,8 +846,8 @@ - 0.5 - 1 + 1 + 150 0.001 0 0 0 1 @@ -1045,39 +855,8 @@ - - - front_middle_right_wheel_link - base_link - - 0 1 0 - - -1e+16 - 1e+16 - - - 0 - 0 - - 1 - - - - -0.120 -0.26 0.00 0 -0 0 - - 0 0 0 0 -0 0 - 1.5 - - 0.02467 - 0 - 0 - 0.04411 - 0 - 0.02467 - - - - 0 0 0 1.5707963267948966 -0 0 + + -0.36 0 0 1.5707963267948966 -0 0 0.1 @@ -1093,8 +872,8 @@ - 0.5 - 1 + 1 + 150 0.001 0 0 0 1 @@ -1102,44 +881,11 @@ - - - rear_middle_right_wheel_link - base_link - - 0 1 0 - - -1e+16 - 1e+16 - - - 0 - 0 - - 1 - - - - -0.36 -0.26 0.0 0 -0 0 - - 0 0 0 0 -0 0 - 1.5 - - 0.02467 - 0 - 0 - 0.04411 - 0 - 0.02467 - - - - 0 0 0 1.5707963267948966 -0 0 + - - 0.1 - 0.129 - + + 0.72 0.1 0.258 + @@ -1150,8 +896,8 @@ - 0.5 - 1 + 1 + 150 0.001 0 0 0 1 @@ -1160,22 +906,24 @@ - - rear_right_wheel_link + + right_track base_link - - 0 1 0 - - -1e+16 - 1e+16 - - - 0 - 0 - - 1 - + + left_track + -1 + 1 + -3 + 3 + + + right_track + -1 + 1 + -3 + 3 + 0 diff --git a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/specifications.md b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/specifications.md index 46606181..34045c96 100644 --- a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/specifications.md +++ b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/specifications.md @@ -10,7 +10,7 @@ This Ignition Gazebo model is based on the Team MARBLE's HD2, namely on the mesh Thanks to the original authors Derek Vasquez (dvasquez@ssci.com), Neil Johnson (njohnson@ssci.com) and Hector Escobar (hescobar@ssci.com) for making our lives easier! ## Usage Instructions -The robot motion is controlled via standard `cmd_vel` commands and produces standard odometry. The tracks are modeled by 4 virtual wheels on each side. +The robot motion is controlled via standard `cmd_vel` commands and produces standard odometry. The tracks are modeled by `TrackController` Gazebo plugin. ## Usage Rights No additional restrictions have to be taken into account for this configuration. @@ -33,7 +33,7 @@ This Marmotte with sensor configuration 1 includes the following sensors. The sp * Xsens MTi-100 IMU, modeled by the `imu_sensor` plugin ### Control -The robot is controlled by the DiffDrive plugin. It accepts twist inputs which drive the vehicle along the x-direction and around the z-axis. The model follow the MARBLE's approach with 4 wheels on each side approximating tracks. +The robot is controlled by the TrackedVehicle plugin. It accepts twist inputs which drive the vehicle along the x-direction and around the z-axis. ### Motion Characteristics The characteristics are identical to the MARBLE HD2 robot: @@ -52,8 +52,6 @@ We leave the same endurance as the Team MARBLE, i.e. 1 hour. Based on the experi ### Diversions from Physical Hardware of the Marmotte The Marmotte HD2 has a payload bay similar to those on ClearPath Husky robots. This detail is not shown in the mesh visualization. Moreover, the sensor rack visualization is based on our CAD file of the robot and misses wiring and light bulbs. We consider these details irrelevant for the simulation. -The tracks have to be approximated by wheels, as DartSim/Ignition Gazebo have no support for tracked vehicles. There is a working model for ODE/Gazebo, but there is no straight way of transferring it to Ignition Gazebo. This approximation results in worse performance on obstacles, and it can even happen that a piece of terrain gets "stuck" right between two wheels and the robot would completely stop in a case that would not be a problem with real tracks. - Cameras have no distortion as the simulator doesn't support it. The 3D lidar produces the 360 degree scans in a single instant in simulation, as opposed to the 100 ms-long interval it takes the real lidar. diff --git a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/urdf/robot_from_sdf.xacro b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/urdf/robot_from_sdf.xacro index 50404898..66a1fb82 100644 --- a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/urdf/robot_from_sdf.xacro +++ b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/urdf/robot_from_sdf.xacro @@ -49,132 +49,52 @@ - + - + - - - - - - - - - - - - - - - - - - - + - - - - + - + - - - + + + - - - - + + - - - - + - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + - - - - + - - + + - - - - + diff --git a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/worlds/example.sdf b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/worlds/example.sdf index 9ea5042c..5c46cff1 100644 --- a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/worlds/example.sdf +++ b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_1/worlds/example.sdf @@ -171,6 +171,13 @@ https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Jersey Barrier + + pallet + 2 0 0.02 0 0 0 + https://fuel.ignitionrobotics.org/1.0/openrobotics/models/Euro pallet + 1 + + diff --git a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_2/launch/example.ign b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_2/launch/example.ign new file mode 100644 index 00000000..45885010 --- /dev/null +++ b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_2/launch/example.ign @@ -0,0 +1,20 @@ + +<% + base_launch = `rospack find ctu_cras_norlab_marmotte_sensor_config_1`.chomp + "/launch" + base_dir = File.realpath(File.join(File.dirname(__FILE__), "..")) + + ros_param='' + if defined?(ros) and ros + ros_param='ros:=true' + end + + headless_param='' + if defined?(headless) and headless + headless_param='headless:=true' + end +%> + + + ign launch -v4 <%= File.join(base_launch, "example.ign") %> base_dir:=<%= base_dir %> robotName:=<%= robotName %> <%= ros_param %> <%= headless_param %> + + \ No newline at end of file diff --git a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_2/launch/spawner.rb b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_2/launch/spawner.rb index 74ff2d1a..4893112c 100644 --- a/submitted_models/ctu_cras_norlab_marmotte_sensor_config_2/launch/spawner.rb +++ b/submitted_models/ctu_cras_norlab_marmotte_sensor_config_2/launch/spawner.rb @@ -10,24 +10,20 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw) #{_name} #{_modelURI} - - - front_left_wheel_joint - front_middle_left_wheel_joint - rear_middle_left_wheel_joint - rear_left_wheel_joint - front_right_wheel_joint - front_middle_right_wheel_joint - rear_middle_right_wheel_joint - rear_right_wheel_joint - #{0.525} - 0.129 + + + left_track + right_track + #{0.525} + 0.258 + 0.5 /model/#{_name}/cmd_vel_relay - -1 - 1 - -3 - 3 + + -1 + 1 + -3 + 3 + true 1 - - - linear_battery - 12.694 - 12.694 - -3.1424 - 78.4 - 78.4 - 0.061523 - 1.9499 - 9.9 - true - @@ -62,58 +44,6 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw) 10 gas - - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0.25 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - - 0.086 - 0 - 63.765 - 0.129 - - /model/#{_name}/breadcrumb/deploy @@ -131,6 +61,20 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw) + + + linear_battery + 12.694 + 12.694 + -3.1424 + 78.4 + 78.4 + 0.061523 + 1.9499 + 9.9 + true + From 54db40cb79d14cc91be07c90e65e97e41bd12cca Mon Sep 17 00:00:00 2001 From: Martin Pecka Date: Thu, 18 Nov 2021 15:08:21 +0100 Subject: [PATCH 08/14] MARBLE_HD2: Implement proper tracks + little fixes. --- .../marble_hd2_sensor_config_1/CMakeLists.txt | 2 +- .../launch/example.ign | 18 +- .../launch/spawner.rb | 82 +--- .../materials/textures/HD2_Albedo.jpg | Bin 0 -> 908310 bytes .../materials/textures/HD2_Albedo.png | Bin 2933853 -> 0 bytes .../materials/textures/HD2_Metalness.jpg | Bin 0 -> 246789 bytes .../materials/textures/HD2_Metalness.png | Bin 89037 -> 0 bytes .../materials/textures/HD2_Roughness.jpg | Bin 0 -> 465633 bytes .../materials/textures/HD2_Roughness.png | Bin 742629 -> 0 bytes .../marble_hd2_sensor_config_1/meshes/hd2.dae | 2 +- .../marble_hd2_sensor_config_1/model.sdf | 372 +++------------- .../marble_hd2_sensor_config_1/pan_echo.sh | 2 +- .../specifications.md | 8 +- .../marble_hd2_sensor_config_1/tilt_echo.sh | 2 +- .../urdf/robot_from_sdf.xacro | 212 +-------- .../worlds/example.sdf | 6 + .../launch/example.ign | 20 + .../launch/spawner.rb | 82 +--- .../launch/example.ign | 21 + .../launch/spawner.rb | 101 +---- .../marble_hd2_sensor_config_3/model.config | 14 + .../marble_hd2_sensor_config_3/model.sdf | 414 ++++-------------- .../marble_hd2_sensor_config_4/README.md | 2 +- .../launch/example.ign | 21 + .../launch/spawner.rb | 82 +--- .../marble_hd2_sensor_config_4/model.config | 14 + .../marble_hd2_sensor_config_4/model.sdf | 414 ++++-------------- 27 files changed, 416 insertions(+), 1475 deletions(-) create mode 100644 submitted_models/marble_hd2_sensor_config_1/materials/textures/HD2_Albedo.jpg delete mode 100644 submitted_models/marble_hd2_sensor_config_1/materials/textures/HD2_Albedo.png create mode 100644 submitted_models/marble_hd2_sensor_config_1/materials/textures/HD2_Metalness.jpg delete mode 100644 submitted_models/marble_hd2_sensor_config_1/materials/textures/HD2_Metalness.png create mode 100644 submitted_models/marble_hd2_sensor_config_1/materials/textures/HD2_Roughness.jpg delete mode 100644 submitted_models/marble_hd2_sensor_config_1/materials/textures/HD2_Roughness.png create mode 100644 submitted_models/marble_hd2_sensor_config_2/launch/example.ign create mode 100644 submitted_models/marble_hd2_sensor_config_3/launch/example.ign create mode 100644 submitted_models/marble_hd2_sensor_config_3/model.config create mode 100644 submitted_models/marble_hd2_sensor_config_4/launch/example.ign create mode 100644 submitted_models/marble_hd2_sensor_config_4/model.config diff --git a/submitted_models/marble_hd2_sensor_config_1/CMakeLists.txt b/submitted_models/marble_hd2_sensor_config_1/CMakeLists.txt index 2fa5e884..3ed546f0 100644 --- a/submitted_models/marble_hd2_sensor_config_1/CMakeLists.txt +++ b/submitted_models/marble_hd2_sensor_config_1/CMakeLists.txt @@ -5,7 +5,7 @@ find_package(catkin REQUIRED) catkin_package() -install(DIRECTORY launch meshes materials urdf +install(DIRECTORY launch meshes materials urdf worlds DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) install(FILES model.sdf model.config diff --git a/submitted_models/marble_hd2_sensor_config_1/launch/example.ign b/submitted_models/marble_hd2_sensor_config_1/launch/example.ign index dd4ae56a..4f966689 100644 --- a/submitted_models/marble_hd2_sensor_config_1/launch/example.ign +++ b/submitted_models/marble_hd2_sensor_config_1/launch/example.ign @@ -6,7 +6,9 @@ --> <% - require_relative 'spawner' + #require_relative 'spawner' + _base_dir = defined?(base_dir) ? base_dir.tr('"', '') : File.realpath(File.join(File.dirname(__FILE__), "..")) + load File.join(_base_dir, "launch", "spawner.rb") # Modify these as needed $enableGroundTruth = true @@ -20,7 +22,8 @@ end # This assumes that this launch file is in a directory below the model - modelURI = File.expand_path("../", File.dirname(__FILE__)) + _model_base_dir = defined?(model_base_dir) ? model_base_dir.tr('"', '') : "../" + modelURI = File.expand_path(_model_base_dir, File.dirname(__FILE__)) $worldName = 'example' worldFile = File.join(File.expand_path("../worlds", File.dirname(__FILE__)), "#{$worldName}.sdf") @@ -34,9 +37,11 @@ +<% if local_variables.include?(:ros) and ros %> roslaunch subt_ros competition_init.launch world_name:=<%=$worldName%> vehicle_topics:=0 enable_ground_truth:=<%=($enableGroundTruth)?"1":"0"%> robot_names:=<%=robotName%> +<% end %> @@ -162,8 +167,13 @@ <%end%> -<%= spawner(robotName, modelURI, $worldName, 0, 0, 0, 0, 0, 0) %> -<%= rosExecutables(robotName, $worldName) %> + + <%= spawner(robotName, modelURI, $worldName, 0, 0, 0, 0, 0, 0) %> + +<% if local_variables.include?(:ros) and ros %> + <%= rosExecutables(robotName, $worldName) %> +<% end %> diff --git a/submitted_models/marble_hd2_sensor_config_1/launch/spawner.rb b/submitted_models/marble_hd2_sensor_config_1/launch/spawner.rb index a0b8bf25..f3685430 100644 --- a/submitted_models/marble_hd2_sensor_config_1/launch/spawner.rb +++ b/submitted_models/marble_hd2_sensor_config_1/launch/spawner.rb @@ -10,24 +10,20 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw) #{_name} #{_modelURI} - - - front_left_wheel_joint - front_middle_left_wheel_joint - rear_middle_left_wheel_joint - rear_left_wheel_joint - front_right_wheel_joint - front_middle_right_wheel_joint - rear_middle_right_wheel_joint - rear_right_wheel_joint - #{0.525} - 0.129 + + + left_track + right_track + #{0.525} + 0.258 + 0.5 /model/#{_name}/cmd_vel_relay - -1 - 1 - -3 - 3 + + -1 + 1 + -3 + 3 + 10 gas - - - - 0.086 - 0 - 41.47103925 - 0.129 - - - 0.086 - 0 - 41.47103925 - 0.129 - - - 0.086 - 0 - 41.47103925 - 0.129 - - - 0.086 - 0.25 - 41.47103925 - 0.129 - - - 0.086 - 0 - 41.47103925 - 0.129 - - - 0.086 - 0 - 41.47103925 - 0.129 - - - 0.086 - 0 - 41.47103925 - 0.129 - - - 0.086 - 0 - 41.47103925 - 0.129 - - diff --git a/submitted_models/marble_hd2_sensor_config_1/materials/textures/HD2_Albedo.jpg b/submitted_models/marble_hd2_sensor_config_1/materials/textures/HD2_Albedo.jpg new file mode 100644 index 0000000000000000000000000000000000000000..e0dfec96a5c0af494a6a6204e36b828410340cb3 GIT binary patch literal 908310 zcmb4qbyQnj^kr~@yK4!>Dee~90zrd26ev!R;_j}+TM7g#P>MrvXz}81K?)T2qD6=A zw`OL|zjLxyUe8}prD`v=$>DICnVrC01fp&`|lm? z+0Zf3|1)e%ObkpQHVzID8wkX~BgDhOCBOv&@rm&X2#JV@iE!{pNJ)rDpFb1*cN3KV zJkijxpB;&Cfw<3S|3B^N2Y?tG8-NW!Lm>vB5~H9IqdfHj7ytkibTkwc6u|#AG;|D1 zR4i;1AkOo3A0hw>8tU^Y3?L>RAwC8QF$yXgF#sKdgc*~RAB^=v)4~m#Od#|lIg6mY zRzdC0Qwkw%%MX)4N|3OQdsu2+eZxAdi0ErwD-Tbvh_u4)sWYmVVs8}m-iJq~_w-J) zy)7zk+|akS$tYo0oQcZZ{7c>U$M);<$aK#^{crm}p*;`%92*w)^Hm7(bI7RAp`oLp z0kNKcT3i4MDltDA2{SqvgH%BCg@qet=qVPNyw=C(peD&F1cg7i*Rcq#TZWy9yzYJz zo?2hn1Jc%cS_0sqJ>QA=`Af+H_Ha#f5z8o9b>*6~&=CK&mtmG`r1paM%$y3zc7|3X#%(vIup)AA6*}{18vXqleeah=7$I9e0SWtg0to;eK&({^Y@bf zG))EzKjaNmtaRn%8M^gX+jPkm`Jat-GvboWO>%SRg0hd`pi<$IZXv@1S~4k4!;#!?4dkg62q%#(3738p{Ve8pk;f8CK2F zG{YK%I5=bc4;&j$fX3A)0MPRluDJU#Ys}(0mFFB!Oh;>DowYY%OL_&19YiYu00|)o zQPXi1nTO%`&mQrzHDrN%tBG6PPNV60GgCA)+xtPRd>`SHF97RcV({*!9HVkL^B&ZR zTl<9W)m?g^@Gzmb$-~FSucoYj7{h%}RH(l4UXkzMtv9o@wUzMaipO=;u4AZiq0 zM1v}OhetWoaz8B;Mmjz~BP}q16{ti*YMy*E{`1kctivpE-dhkEbRQhN14G`H z9_Amh4POXO`+ah;jkR8xZ>U>y5%ArBRO6?`z>d+6!aJQAjfb5g5XIIrN$96jj((z+E0uw3WtWT$7oR*_Y>w&^*%Q~&$;*WN&M|%TS32nTVgFPE6`hY;WNP~=X_bjK z(i6UsDBEi2y6)cw93T4KGE|o)q~3@xwR`>NWuOP^*;ED*j2j>|bG0TS4KmXxdmOYV7Ehc~tY2?%egD3PhPNMPtwQeIq6f z9)bc20alqpIt+)aD78+)lM;;E_XzR&U3tFL`0Y?MdTe6;EX*)5F)sO{5w> z>!u{fIhZQPCzlz-yEX8tXQ|2J<}1lDpl5-8`jx;2rmj$Vn5W^j!}M@o^!96 zN5|RWg1|TVQHHWjLBSd{Ypa8E!9=?j`==L%<^$=7pd+6LPw(<0o>tIJG+Tq3+dy;$ zug>!8le>Im);){4ZOIdWka0>@a{dVrpLG!2J3ByY-zc#^6~RQ#q0C2uMWVrM>ej#I zDegKh<>#|}-kSD#iYjqF-`r&N_^)rzus8RZ$IW?BL=gf4mKYgj|jX2 zzL>Z2LJ}^G=Js4A1KLy&29d42M3Edg+P+a`W?J%kX&hSMNeFZcY->egu|j#`a3bMv zM}Gzfa^)=4L_+qTE{|m$Z);3!jqFYEwNI5%U@{GTEX;Uo~U0 zK`&tAlKV8IrTZm)-x??(m$I{uYpa+8z3M;0&lFp9ZOBMB75Q}CuUj}xg2F!s$R0^g z>khBxIW}muXsfWz@y$x1gZ0mlWfaHapxc3IMp2_RORzqrrhO|TR2mcnXP~ekLi6|& zEN%!${gXDTkGWkBY9d!%5 z7gY-u4lcpK@P?gknXW@x?c2wUxWqTb3F1OzKlq0T-x4m4>q{_vyQu3F{Cu_T_UL|& zkj1z!2zd3%^z_%hpU(+z##-l{OF|=Cl0U2|mS=6veE!6|+ps~9BsrtUEEp#3q2=uq z&C~Qt+9rXW^h|@$;*p%Fv7&7*R7xR(eN`H5)9klLMP1e^tZQ}k#V~I`?GBLJCR--y zTF5=-qkuT#q>fD!97d6fOq+ z#5B>bw&9kcG?&!(+jnb1dwae1AR*;t6-(Xja6$>&Ehy?%;X8UeayYvraxfaFmv1#H zzrCYrr9N&`U(_pZEUn#6WSSL?Dno&pbN8)@i>FF*WtUm}7XPZJBl=d>X@ zxnyYt3`_@LL1H4LECta?8heo7+DB++hV;-l$AYv9` zm{3Fme^x___=FnHzZ-`d&fFdD;qmH$%QQHE^4{3 zi!Si~PUXeTWvR>)AmjRZ*uT^F^Jh;(43 zqW4UB8Z$hryC_xe?aPE{pvED>3lm~76Z&lpjvqtxs07YhzqaSnj158mjPDk2iQ9X!(x$WZk`{7P zMu$a8U)uf|(*pxV4yqut9RQi>eQ*0J8SQd{sgsNfYSY7GLN4$Zb)o}Xi2S>J--yhf z*BITRr*a``=WX=Jlenc*F$}|Z^;jFy;N*I4~fwJ@Cq+Sdc=|m&M;l0 zx{hfBnI`Cu0bc_I)j}>d(ef?Y08e))2Se2ozTuR5ucU2&gyLc}u}i!~JS8Qzam0&1 zY%eU7xs;(1hzwM$Vj$fv7t(Z#w0?B86uX3cTcj)8eLpi zEb=)YqbCu=$1F~j13*B}=P-L(JI8 zDQvGSW>U*uyh$2L@?Eo*uRsmksrS*yHs)Mki}nFx@TUaiEgqfHr<0;h$)?+pOWCoB zh|*lMP`dd1F*c>2u6qZR)^$UBJ#vbn%Vn^lH~+m22b<@6gXPsEf|r;>JVt8DW5#%U(VX7K}>AYeJk+7pok86$Y*jQ~VQ$w<|667AqYCHDnMo z{HNTjNX+Mz1KzijhWDPqv1stha8N_ww{fQLcTE%>qh*p7zgeCkw=x?viJ#Wa)La5)J`toGnx z=x-G}>9sC>VdzT5)~SxdmoiaV1-&3x-DpSq=#Gon#T)DJRLKY6<@~MeKY@$j(N2_P z{kC91?z+uHv(cbnh3m~+f9EH_r{^sB%J}}^Dw;RTxl@m7b6hg_?!L3bah&#g2BCjJ zd0rp~bqktXGurUiP1w-mJ>jW3!;M}v(-LG>XD|L41|l9XdIB)tyUciW*!DhXlI^u$4z82I*lX=fUJuHd_S~-TDUA|wui#G|9jANvDExO#cbCL6bXYlt z{xekKEo%8D*m_~a`GBC!w8$j|*~14;O|4z|p+u7>f$wNg;$*@`*4k%sE`_X7;^Y~W z@^#c3eer|uPN>N1t5%Ujs_@JDMqNY`A%#T~j}nR^hwAOmJ8#`QP4B;u*F{5=))Za0 z-u!nMx3j;Kixv~z?Kd)6l1IU+y(co+9;jy?4n0vj#iT;SBZkj)KtDL59xi|~axJ85MI^m*+AI21NJcAo%F z&fi^&TtcN9azNbN9Mnpj&`E9durwwI@!q)gDDC0NOzOadCxD7t^WzW6N8PT=ionVI ztgOZPJb5IrLGo4Dk+XPW%}Se3?rcdBkL}2BZEQCcO|)+$0qXz<)eEKkK60iNB59meEa!cGlGPIq~wfYyFBJmh9K->uWoTrtvK) zE>SYlWri@NfQi6ygbBHv7yfY`no}>OC%5^wFYhT1>!J%d&ZEds7yUVP;E9{cFkg3) zFB6`aVZ~6$e(YyLwW8?C(nwSSW;?#(K8&`)c7^R}how4uv-5x@q$enQzqpb!HWq{b zrH59VU>`Y>A3z} zwqDb<%YyeFctr{Mk5(~U(#x38)bqa$?%&c0cQ6t4*mdDmQcqUvskeITPqZMXkCQ)2 z_-xJ{)w^Dgeh+^41o%=tZX#n7Jof~^s@U@ADu0ySw@Nlde8(cuts*%eRxA1}{OPTL zz=*~R#bf}GiBZ4sU#@zmfEn+}o~--!y)kce>4m9k-GFhXhG@=)|Kk&2N-s&_MUSIO zVtYe5h^&lNE__L-diHwb(eYcht<%xm&!&E3(ZuKCv>V%#20K#GTSjV}bI0HIi=#VN zzw(@PBUR@_;ndXa+3do4xmz2qHF4%j z)W*4kNPZzhhEollHldrh4`NWV#n{CrM4e$tnJiMYt=af{k&iZ9#R)DdEzqqfB`}2x z|N3?tH@Jb&VxHny+N;gcQ)cch?+OZthv_tf92MmS6n)P;^r7O?&~|=cdU%t%?RKr} zc=PgpZ6P>q92~7NpUYspsoY zUrLK;pDwc9{Cfy|0+_$rd;&Cd5g*)|8}2=Lt3OIP>#vzlo{e4F#)}R_93ibG7&!PG zPgk6yg0d>J6w60iA7!~l?(^rQ8NcrZyq>n$Z>99v5*2$KuKbtPmviP#765^~J(@~~ z13cfSdZ4NWswb>c{klqy-{;OXIl7ybg?UA0@+npx=Hhy-n>iO^#zL_8XTT}gm*bpw z!8jM*vYG<>8l>a5!PUn>Dpy$>*%#871|H7G-c1)-{#WNM!gtqVj%eLoCXYt!IOt>F z;s`?in(hf8QM>%#)v_5hxDW^G>xr^D$Y*#I7hrr^pHo&aRe+a%*GobBc68RZO`1~4 zn`Hb0!q6$R1l05TRUs0dB=D$ntE7Yj@OHpQQ%`d?RZIH2M%-%AKL`-`C$Ib60gFM1 z=A(uQ;(5vjZC}~?P}l_6i3Gnzn)(Lpp9Z|$*q`_^TB)d&ht7yEd;(u2>>RD&HCb+t z`ee`QEY^r#0z`#?b^&y|;w&zRjH9|G$7So4-`0K3M>!^UNZ=$#ET7U$h?PLPA`OmX z>`GbqQ0V1H41{uYu|i%e!KdBVc69wBh9jKYo4#%ltu%mbPCRy%4@CttJWK>Y`8Td9 zU8Yhzi=0B_@!w51)+1fvDcx>wTj7!4!d!|AJsuLgWkq*`ft z1V>t%$A6QbzQI5(fx%Og9=$atd=jD8cXJ!Rdw=$+Vkv&wrZ8d&wUtt2g+NLdNGAxwT0@IIrX^-DXx z^Dnhw+i&1h9NV2~r1qlyBVkSU@NFwbo9~REn5UL6(Z{km4}PsJd{L}7Z7klNQwqa^ z?~niW^GiCWekqW-8tRD`(EWw2c{B}?(4+D8m24=t4Iu?r%k0xCu*D)~hggS?sT(IV z(|Y1UwD2A0o)zI3RBC(coM8=_7YH-Q!N`uggunN-#o&Jr65&v5CiGAINvlLlURP_7*-Fdql=`Wm*dRJGLyNJoVT(XiPgrpX7Y zzZiS-@;i~^7vQ{5v`<LpDqo9Onb_4(G+n#bzr)aUCBLL3X^NhCD^}RcgPgDDnI6^=YpV+fRVn zDi8HT4ed?YGZjtSDpO&A)ABK$ArUv_I_sP9%l8rNoZh0s+>{I z3wa2Z>056fGYdpk*b(MWTv0oymd;#c9eDu+K-QaRCtp%4NLxKuRF0i7xz`stGw zrJW0LR#cQp`#6~x$M@m8nfkfK>}M}RCGX{XaB7=-&m{Y~4-c1&uPF(eGncH3QA>Cn zG*LL7K~+A$XTtP6Z5d62{B(*1L7#X+cZ4^_YJJ#ZCC6HXn0CAG7BGu$rBDl~jH>mK zO<;~DvJ*AbAmc4+ItIEOKlrm9rPCf6PVyV5AG-h?NsqlE(`I7yOC{6jnFqo^ZKFJYmt5pnZGEDtxABJZKD{EE zc|$Oz(`a^2ZjWoG9&9E)KD5I)MxF$o0nqwH(+jX_$QzpD1A7!r1z}AR0CLNgj7=P_ z7F}2q=NORcVj$8l(G(F8F+gei3~XYMae91`^s=z@PR86XE0HTNF)!2&>i*BZNah4H zW=affC~WqaD5DrX3mccuBVERxIRmAZ)>SzHRZ#X!|DwSYz z86=-)n_g99)~4P>?-2N>emr_~=#kJ7StB}s$EU-=X%uGSQyd1^An^@{OEn}dy~zC^ zAOwt;k;PA&!6}5Jp4&_KExhj(-W}@rDvAsb(I_5Sef$KNgjc30(mZ#1>}by(qgFdS7r9Uw%I8iM{7D@i1SfDHeAB0HNGUjx+!8unrCM%w@bEB>hv8TF^!PZ2<5~YXsiFj8eMeC*W)IUr z|LQ3?I4ALGgug{!)wN}d-^DEM^r3i(_8P%v&CPSnfA9EWwU3vYpv}?6IkF59Y0dfC zfs;gv-$ON`(zgb6(slmY;Ssv{{|#imP+v-yM4`QIQ?w(_uS>YNTsb-AMc zElf0n`NTjZ=tJq>E6gUy2v0KrrKA$i)mJbgOqCiwT8{%aaDy{ADV)i4jmt%O1QZ;> zmAAJLhOBbDeg)DE#LP8Sb(cca@;Ty5n#$4qV76%bO`CNki~(SV+))hu5)M{66*q$r z)r1k^xu962otyQxyL@CI=QR>_Zw9HRW;~bqMg+CW4O?2HjY*~z+Y=X0fN(1+o-r(| z8bU*X-|in8t!QVPa`~&W7irz zJyex-mb8%)q!$l`VXO0n)r?iolqTbl5KdWd-Vh<}?>PMYT4Q-PM?q_kjSO!GVXYaU z8+x{Ms~ut4$mh|dX6wexBD=(b8<8&0OPvaGI7vI%wuLIim|Tu^oeSX}a7+FaRSX9^Rwp{`SWeA3cKQiNJkt}g zKIavJ6VyC2U7Hkb3GiV|9OloGa*TI)@DSD0&p=q*&yNkr*Y+V&CW?7tG*L0*dFnbL z3g1BgAzc7qh*M6h-8l?lv}S#BKeqG)7@LUXpzhW}53_|9<-|OLoJK8HUs;zrM?!Q5 ziMTjDhIH1`lgJ2gkS=e(JAyy!r0te5qJfXl!$A}&itos%C;WWk2-$J)QYx7y{GFfked(;w!VF2&6f4l5HA4h{-+gs$9wSF9?@yjiRT~8Y0P|ka+KwtaUOlZXb z$`t_f?V%fX?0IGem$`@@r?KJ6ro`DR?ux59z)IB7q80_2jXUXwn2#x`6$1V&cLocL4>p54nL{KwA1G@a&1%Jd~f{E`4eC`DCY^#^#s^{{{-NE0; z9&IjVAM&37uP~Cj?C#~@>|$MxPB7QeZ~d-FiYBkQ?8qLxB7Sjb78wcX7aw4=GC1W? zbnn(Ic_XNF`ogBBr#w%YmpK4Qrg_`v`cN@@7i}~x`)eWrFq!7G%0BC z^FNnw7ex4I+f@4}ro;>EbQp5`U)cpl*dkHCw;vF&ZtFoCKH-p29%T$nAqU&Jh9dDQ zAcE+Doql^GwoyM_sC)99nw>wU#m?71WF&ItG*Y$sL{7Y||CICQ&hdji?W@7Zx!aQ= zG+PElqwjVlO{d?wol`kC0!A-qG6|&RoOG+=h=n=?6FB`PlDz|BAp)5avA7P1>8Pn!%o`Q^KCX@g@}l znt+gCMucvH<&Z%sj6Zo-dSEc4S9J~j9vK)+B`0f`(XVEqFJ&m^_g}IQSr0izX)N5wSb{+d zgP^rT#Hz)(QM6Ywf#1~LSJ+f)6AxKTpflP@oE9(9YN1vp2`C0gVEXfrPvwg!qZv!0 zZ{lSV6|ZZ*sQCTu?y^AGq)tMJP*X1F{O>~H6r?u&uvw1urw88oc*%yW!KF*f(T0Ai zoHyTQ4ZIGs7_`3%G*dv+i`7$=emlVYZJi(bC*R#kT7>`BH&9qyv}(%Es9WiURUWO_ z8)*N8X3}vfsl+jn+klx|`4q~%tP{RaIr-;Qe(TQY^8C~W6VD-0{U&fmLmj@X9v!+f zpR;FuE6osgFza!AxgE^d75`6yvoG~w+AelZEy%kf%bB99;DYaDUumHkRtW8W|Dk%! zvo-V2Lw@NVBo@Jy(ZDImRsH%*pHTO^wWiK(nqL#NOlQ~ec*MF}`Tncn;%v*CesVYW z*fsuWkssPk1n8iz@4P=&g~v*T2oE!=JmVOy+ijOJEXl7+{c;UA0=xcQKO9_5{+?^* z?X{%1+7y_HpfqLC{jzsO@N;;{@nSV+YJJZyu=)HX=wv6DGd!B}HMl#)^jYju%B zNi#bU3_MAbUM}POrkqlk5r(~ikCjexg_Qm9g`={d7b|D|xZTiR8E51Su&o8a`j(bX z@=iH~1RVcz-t2g4cie_oMAE`FH@DqgxUXK>xE1B2Gmkn44GDo(-6t%AJkR^mjm`>2 z!vl$2C$Xl1y_ZdQmtDUe;~(;Ff`V~xY!#<2gUUsNxnM(MF0^ykJI2gYykfIabhFyN^J>5xikE zlU`4!Y*6(qnbiFIO|Y`nME|2kcYt}d`=#Nyy$pRpLZIx0;{_w(=i`U9?fX|p z_)S|U&uJV)jh=`R$hIAc6}JwKLr=9Mv%jvaqG?9>!lZ`66PqK+%5gBk=nmLYyAra6 zW~rUWJk#Np)(xA996ZcGEpTUwg&N#JcUC<0Bbq!D6-uX;P;Dgiwl*I<(wV< z(i|qaqe)df403b~nz1)lN z&o%dgUX_jV$pVI4ZS5gL(_SCi_YoDQDC_NY8?2wF%^ zBqOJ-&?i}^)}R66QB02RYGPtwz==|xl@A7cg2hsVg%1h6UOjYyDLHyGJg~WS`D$Ke z2rPn#%$+?ZB`qC;{ZdOwgJqk5Bf*ju9B*!w-O>MeN8IA|cWXIT{cN60r_ovopd8Bw zpxNarwqOnm{1fb?Kdlv0`Mrm12-!O&QSC|jPtMNg9Ibxidd^YPEPGS)Eo$bWq^Ij_ z1#skGSjA2?l=CHEzO!~_-)gFRC!fUmamPhtV&AW-N}3>j)zA=hhx8Ob8}_lt_C%1r z8>6=&qj@jyP7O)}<^6>S-w({(COnwy^EPRJeuj?%MAsh(BmGRI8B5ok1^e$;y^yYI{wp5cI@>Ia9%#BWak$!bXv zZqr7GqX;G&d6IV!Q~;{a-+vY4mP3m;avZ-EGRRx*vt6Zlp8$^4wQX%*?@xdT%&FyX z6orQc&N0xG^dTjt@$Yu+xJVseXR}TH7UL0^iH@tOgdrYcvSo)|Jp8Tp4C#=>p zTHJNrgh(6;u~6eFB&x*>^9!$&N|nlWy>h*mEqQ1_oW~C*&r-35k8*Gzlr({@22kqE zvXNzFt<;P#o#M=%(zAePb=Q)LL1K{$#V?-n*E*#AEC%Z=%}_@?qaDnjZrb5yPDY8p zp!iY0pgyEP_WAFGyzXBkh{3gJTtZ5h|A0*fA|3CQonmQDx> zJ5S6cfVdK!cTr?BN74%k8QGXHhRJd`>=*mZ$iZiBf_ge=k zV753CDKK=C?XT$R$Xz62oRr||pFYOWFK$=QI(o z4u8fs(-KV#EpO5n1(H7;ex~rUV<)P~SDVH68-{Yuq zwj6D^TpvH4j6UdJVO=?v&hJ^DF`7;faDVvRZ77iUYGY`aw`#jI_rXlqn#DXd*jW0f zS2E=y9i#*PlUGHn^+qA@x=BR;zic^&R5=`fK6hJz^v)7>@&GU#?)%b6XFUneg4tsmRPig4eX2m&4rS>~RZgjLm-BYs+c5-o7KAKyQPz98MAX0KMWF$!3$!(@r$Uc6XCdm8k z*NWQGr5Tt@O3GR!;@I$Y##e;wKjYdwC-nNv4VKrBoM#*K)#x`yhn;uSQb5+~M@sT@ z#i{PyKm|n-_(lYjcMV0Z4zqZ|_E|mgaRlm@CRc|?gM}6Xf9?;VFq!Zt!1er1(<5t; z##PaC>mPg_oOV0#*Zc`^6#RJd1ek|${tpt&j)MWKa^^m!X|E6LXSA?)D>XJ$MjEL` zf)c^#sMr-r`nUr9`~4ERQWDK(`C2N8pX>f*npx-D+IuKAmKNhj*YzLstAqyp63N=b z|BAMYs=Hh4nF?)I3eD&KACOp)YLE%N1nrKRK(cIhDSp9=*hAE%#)hA2xxRRy~@6qeLZQLrFHH3x1Pb4ajlCn z_b#x-fw{?)#bdE1;oY5eLv|m6ZnJQEXlcFwi)*_zkoUWCX4)(>?I7oztK%XM>`uph)_H6_>wftJpdSAnlw7^zm7vKCY`WK|)Y-oss=HP#k*UE%jPX%YFwr7$pkz-zM4oV)!YceHKr!-|HeSJ;jL zGh`(tN?uu;Pe+c0w`p^Jdd+lZU~1Hgx82bUlr^$5(%O07Zcgy8YxJzcMdaUk$G`KP zo6~=rQHS$6n6x!;k7LxzMol2IOGId_^o^D7B^$mxk^KeNgTi6X^suUZs*10j$ zXoq|kYj|ZRsd0`2%jbE2cf2CAHGD9#S;1vg$ol4&gbr}xf22G5hd}MI=cWM)VaqEF zwf;Yd750&eod`@q(U8{~t2ta&4qlBk{<`h}=97nDhI*{4SBj^E!F?lAW#V#7rK!x+ zcu9(P&_O?m%JRm3IE=G{mxZ?{G8E!Qu?%$H^rr)T>%Nk+7=XZ`$o_C4gN*Mi;-p{8 z@4O~tB&CX5qvkyT{GSZ**qXW^b5^XtCero^hLrIo(czsf|pi>j%T>fyb+?Ci%42LzSTNNs14!pH(kvJ8A|rc)sXrVzLq zS`FL>>eGl`Jc{n0iA*j@^oguA|6at&fMmux` z!|9m(H&B?Av6ToHDMB}D;&)7EBZ#|%L)ipoKZ^?nIAD{2FhG^)A%*rl{l~ly6^0&Z z4c?Ao3gqGMs4DXqB1AnsHjXH!poN92d%g-9D(oSRXxL0C1!l5_nXP)A)jbm0mHTY! zzRO*|S7jh~f{nNXA{A7N3HYKpDzNYu^FWnh6>!aMXwXrkIG`M!IU&*W{Rx1I`r{%% z60h~cPV#JU+`lf;gH6vU{nL|Sk9QAZ7pAq@{&Rs+9>I}^(>K~c(d@JZPLi})5XT&v ze=mm|f+U^QccudsjM`bMF=HW1s84S`d0xM}6-=qYGd_FnJybnpdcv+&J6ewvcdVDB zj1((gr_!c45;|ya-#=_BT!sGr#BR^V31Jgm*H6B93s2O^*4HYi}$Xba?EbF+qioK}#i z?=d{TLEU!BWB&lm_y2%p)U6h5UCM;UzvHkd=JhG`Vb3C^uemU-47My}T{Qj^pe9?; zl*vMo_@@h*sV%2-Ws_lM_c*|F_9cO?E1wUM+;GFN?VaMJI{R#PbI^MK)bg1n+fu=z zX1USjXlhF1cJkip&$Kg%9h-eZ;Arj#v>S$)8 zBynL8!JoQ@`jtny&YM2PyJ{Fs_&2h;XiNAi2k=W#`Gpd-RDEd+X@irme+)$$J%WRs zwzir5W;^|nUedo6;&AvHRaHaN?cPTck2NMCBF@^C`}Zo+TfChPwzQ03_9IK7i3%;g zd-R2k8A{d0>?dJF3EQD z5!VMYZRq82AQJc^kH`<=VbOyRZ$Ch25tEiM&J1(x!GT$M6*GQe|+d04XYwk zPAfrW*d+W2X0{nx#NZ^ORV*}7V{JR6wq^#)@71RN!X#;tVv?7jEym9&a^R!Ly88as9H#PM0_5J*L)nMPft^GP+oHRKw z+I-Qx?|IS>b}+BoOL``XN1D~g7@MqA?KLeLDU)|xcc;k5h%3k0cn%Lo2B$p%98PyP z&#JWpWwku{hPl#*=?!n5Hy)K_4kKNhuaAy;9z5?@^37j`-kJnzC|{fp022pzhHqr? z5Qf~xX>CT=*INc&E8E(i`UmOT9nViD+v}A+tV{Kd5QAm5$$jEIR>;CKin)RF9Hi2h z9%N13p)_o%T$~tN2G~pAzP}%NULIIDGsmh_7&@&B~ zgDGpgSi2pcQ6#A#e~H;%!zBH!B)()psj4sLhNQp%qkLQ#)bMCD zNz)|yj&@DdOiHc*^M(&j=Fxj^C!C=gs4C+)Sg~)>@mQN;gocyAyv%=nv(w|wzf7!W z=pToMLbE;Ev%o>{th;ODnm(N_<}Q+A@MuoD0S}T-gCdi12LB-T7WJr_nOZRs?ex7G z)`TomZf>uLXClJ#cA_RDflrhZGMY8^{!+u|YQpogdOAZHD}-4d44YCG< zN}UQoRXm^2XU9PeSM?2AAMQbz7b=)2PgTzGtt-c*=)lN_|CWg-zpE6nzV|2Ao3qdt zy-NDsv}#A)%;W5WhQr-lhr){TI$Ge(Hc6yvRj$MbYfpnC?KV-*njEGIJn{ZBe`Ehl z^Og+2zIRJVLLUh4ULKtCzU-}t`C!zVr9WFDOu`vqjMrKxl38hN&T%b&zxAi|TZb?X zHaiX|RR{Q64%<_>3;kB2PJso{Y~7aVB5~jYB9Rz`sX(S{im7(UcP>BOcP1GIGdSm+ zM0j+1SN7n$}0$zU#F&x9MUwvfq-|sH+?5h(9!q+)upBQLFbWu`$XJr_dl#sPP@7Igqjm*FB=3 zk2A33rBnYoY`MN~L$3?K!axO2#D=~5jQvdORlMBSm-E06&r5ZUG=`bRXHob|di`u{ zHCE#AMUnL_E2n=C0_cFUjTFMz)&qh!(k47)^wpmL`_`N1X}7DgZOJkL`(3tow5Pad z$@&rx_D_JK>GJ?JYn#U8{G;K%vyFpReZ}^DDti|(3wDU6baz+IX5!F@)m^5cDu0U^ zi{cRlXS)@7(3vuboao~MM$qQu1zYK!D$Bp*UTNLSpd#K9b3e`|Ycc7SDNTYF_cpEK z{qzFX7h-N&9gU|!;<+78u2*Tn$l#mgnaAOav%DOc;_a>K70~?6>{2Jo#i(S{oWi(W zK0naEit9=iXFp(ELzeBlE7>DR|NGFxeVMT$WBJb6>YXYGS)e;DFmh-vynIQ%*cWMOb(MmtF7m~D77wk*&sq{p^JVx}eaHr4VXm0%!?`WDC~{T!Lep##fwP4*Ja05jZ)IwLi}b@hIc+ zUtjuaR3}u7k@ZfwNS=t&*6<7oGbH(uGji2Gk5)IMMxD`N-(x&O!DJ*AjNzb(Zl|3E z`Gk9|&?eHC#IUHPC8xyJ8MfaRGC8y`Bw5B6wDJWKHVwA}u7e9DG`hdLetBD(4UtbT z%-~>2riq7D4IV8TZHwx_x^=e_ZA`4;N&zZ#Od4)t#=e7Q?Rso`UsJN_azT%k-IA^-t^!oSheM8f3L^CtH71VMjZoQ? z{m2{QbN3x4eZRok5aqfp_;NO*m>r8GlHC6fPoO*J!J93V7yXV}n_`wV(cM$ZN6Vmw zGAU3DD0FVxXy$LUzi2S5)w3xE;*^E{4V@vVx+;_7@#RE+&9%XxrbL6@mzshf`yc{E zNNjl#%&X?>9CYKq49)I9Xz{&a%vyk*O@ti3tqt{5f4RB8#-3oZv7B>twd|!VQ&_o_A6|CSBcc^O+ z&ciiYO%O0yXeyHmNgJ5j>J9Dg3O*$?m)0oFrK{fP892V`YD+%bx@WvP|LuD(xj{MS zan{9E;oW7Qd;9e|VC|cm)FRt@X&Z6e@s!idZ*^@Zr5VPZd|2Q}(P?e1Q@%>2^#s`- zc~lxwuyJ9v*Ya@l24il2EALxs0Z;oPi=d-MKO}S&8=XjwNusSVDXWGd?QoUi@EO4{ z8p`ik_TT}xglv$bNq7RXF`hdeEggykM;lkCKW`JJd*A_cM` zcxSod_4WX()ZgJQQJjMXT69U|c*@AIw-sGAwC2nGI2xQ#eX>?#8uY9$4&>%*Yc?sl zul5|i7swh|JJ#zIywac`DNZkEmWyHP?^v1-R-4-QY+YENx~)9>7ZfD3{HQ_L+o4f< z5tLjpfBC`eOaHN{Z$8YNVyibR$77YM6PqtEvo4sn_fvx-YPU*Lxe=XfUBvSfDV=VL zb`U#O+~-5}{;R(S+J~i?Ds5;8+?wv1s9Na+uXWVDkt$KI4LN3wnv7R3UTS@)6sU;^ zGiEEJZ>vRG)a7`Fi#A9;%cd-^2!5;?OOStj3p7(C-4pq(Jf%#A8WD>c=2TGsEhTLq zegQy7K@CrDFAYG{$Rs|@@17S4-<2S^-_|cgy%D#LY<9=OEIx6jjY#;UVz1TuC!ME| zQIeM*Pm!#bm)}I;>~46tN$+8_uP1VV!OdZ$vC<*6ggq4^k!r`s%eOeMU49HdH7k4v zl7pMJA!ZlX#n}rA2 zFL$S%+?UVPw%h%;=2qm~Wo|N9zh*Y)daV!{U3b^c70PvAi}hOJfLeo# z1C^0Wg-x$=M10YGG%0MN9tY7}WL+PGq(8y)GRv4%G%m!Fx%(Ce?!7NVKebo;q`nr} z4r#av={Y|AYkf32aPg;qXxFeLrT2CAYF56;Jm@u4}C*RG?-`p=<8pSYG$L`v<|DzdUcdyqC#@g5-N6Mng8T zmy;p0G0&DsC8_6VX6`pXMdJ5_8@#<*FEyXO(8$Wee$qnJ6Id5*$D)in$;J{{I(a{IS8D~ znJ{zho-aoA#%=4jNTapde$osnytMEmv2Emy9eJP*Z;DC4KoE7t2?;+z7at z_+0x3AB=bw`^f4JUE4cOI5?wXu5-93rOgZzxWrT<1EaOltB|pIWj=~jndy|6Cds>W3wy3KtE`ZGL*~j zcg=cR%^o6psE;nJt+)&-_&?T7$o_ONd_}T7&nEYyls05j`uuiJV99+*;G7(YWKL9w zX+DUzuZ(~`W!6dMdAai5R*>qRL?Y^*4SOFObja%FdYp)%mk!&#Kr z*O3<~E9Mr|KP{>Z(>M&wT-7?+BH2>ez7@U*_i>Mte|O;g`t1|LKc8J2B?~&7h7r$8 zqdx`AQG4@gE%*adsQ?kiy81#^7QaxmgIQ5F-=I9o z^KWp&(NgF51R_)@XA>d@|8qo=d2?A!BNWtO)#@cj!N)5fM|`@WTq8a79Uvdw(0Yn> z#~qj!e(IuwvwRH=Bm^56iE~C$ih@G1kWCrt2hQbN|D*9mY4h_Eelr29S^$o|SUi9> z^%38KN|c-JlL!1*)0Tuy(}|e!PY13qJnqLBVS|A~{BUJ491a;==U4HtwDYB<$v9-} zth3~s*GHsB>~k{j#+Z;!*JHNcm_>MaDTsvFi$9&#;C*=D+rlBCQQ-zXAJ3yY{B6E% zr5P#s!b)$eg_-|$4$0t{M@aG8EB;vuJ3T823VD#s8XpPv-l3veVb&|hSk3KwH|=dz z&HkbpFlGh;9UVz&9Rs$UQ9K~wG^1jHEYsenr;Q`NS>?Jnl_4j|{4f_(72@*OB)p-c2cgH=iRqqb} zZc$|pts9%ek*%p!#;e)q1~c$nzI>klt}alnf6(JszKdUzOHg~B%i4;M%^Y%N4#))| z?=r}$CbA6V#tUa@p%koEgYq1^gv^nmP{*8j<+#$H7m{9Z0mi=R#j<(cep&>*>TkCB z4;MoOo#u5^$2XxFDlkLyZkv;(4l2C>7L8dmQS4dvyyFxQkr;?Ly5;}k@KrQfz_osa z)%9m%z+1j{i^Lpsa3_@kRXH0U2?H)Q$r}J0soP&_*vp~h{swZ}k!BX5Z#*>$mqdyu zhGIZI*(l|qTAdw4=8%4Gm9Iv#|Fi;_k6jrJ%|HyTQx#`VRw#*DII9m)U|kX*UDj>vZf!QQM|vWU z8Qg2jnOB%0QSXgQ-$&$q5XX%Qa^2kvKMKj~U^Mx8O`h;>eCJ`;O3uD}D_`* zgKRz+K4J1VVrm^uB18gqL9Re)>38L^d>%hN@%#tiS_f?g7b2H~MRjOqi2wL?{sYWI z19!73P!exVD+oso=IJIo)8z*joTkEn1<39FS-`jruSkr@K zH&gTja(Ank0qeOA+hJ+BVg2Ll58hYM@ZauxpSSzsdM+5y3yWSY z-L5tmG$E{AIj5~Eaf0))B|zXZ(;>!7LTv+qTFYeOFr?FHcAQPhV+KkI3r`YAB7F?c zHkXru4t1s>TLv&1Ddamzwc)%?@)9>NoV7v#sX*2|va67HlDTixO`qoK%l(%MRTSKb z#x41WR@x;9D0-q@$-0uBFQ0fI}Bv-t{eerTy;tCp=rsY2^ z3yGL5ByidSabRVt5TSETok|x1m9!q|j`GlNM~FQ*kroXIGe@;-_6zut!eyjhcSj`1 z`&E9B$7aOw58EAty)smK=!h;X3}zE!|7!f39X~e-9QgP05o;+=W6|N|i|C`6ipTxk z%a*SiudshAk^H6AO7C5075+}JSqd&(I$qBU^o5xP2CE;lO|#sTwv~>_K4$fcvlQEZ z>gV42GEXM~%&t5fiNg?~aXMxjjQBX(6n)sV{Mbz>JC1ZpQN?J$0OiN6PAi!F9g<04 zcPe9`S4|KXT9LSUr?w*$jTN5qj2W;;B`e!0p`&xlHT<4-aZ6#nGw@UfkCuvoj4t&y za_QWBz_fp~>4)>iTX0LO+nm@-nWS<43Gp&Fn`f4*pR6ZBXRgloFS|nILyo%ddHw;E zR_{*^DL;+YVPw(4*r{DI)|T`6B&@p~JNUwmO&Blo4=PV3v?XslN)3SDnXP;n99?z; zgO+2ZuWovjz?id}Ld%QGtkbP2R`l)6I{Y1KF&p3IdS2a?*%^l~ zbcGf(2`^!8dv05de(=la`nI@BbOl9TcGN|VxE&s!a;=(5GYW*nj90Uh$RY+fjASZa zaDG1$b*p8JqTs1#B?vc+c>w9Vjn--k&T_CR zyo!bGI+4htFlt$#9e&p#{uYuzUI(iLF>rC>U}%{iH-QJtm-9)j@>}1{jGz%Ku#cRv zufBpgF|Rl?KYdR4@$OxJcCcYNMpm&w1_SGK&p%OU*uM$#Jp2bxf0zm^*2MHN&x}uh zPo;LjqMvu;C%qT$1$_-6ACDe5wo?I{3@1u;xW=bKZE)>u0uy!W;{DPRFm=i7w)jx>wOgywTxV==rVnw zkyFKf3)Wp`xt_Ayu=b>rFp6H z%b7byC}^heqgGol09UrMuOD=(SXt1Bg*A&m3656H-f3-$H?Co|L*Czbk1iSR8xXl> zCg;T~WM`e;r@!<2Q4N=$nGZHl<LXd+B6G;xE_8ccqSgLVV{NfyvD=gxc(_Lw19B&cS3`cd)X$w~?#H%T7Qd=0q$lu87U(`Ie zLuBhYfAm#6mrNO<=9>^nZ~ay|>Fc=-#()@wIMGk#ddF+9*EiYx_HSgfc_lU=5HCSa zc%%TcUInvYP)k=Tno@uM$_%SjND178vGD8$^GQ7zcHocj7Vy|V*RGkDuFTjqfsnP5 zfWEaNu+|gcV7ndBj!v+?)mcx7lD6Qj^zl@G0`{$}4S)0x{R|g;&W7fFYBro`n${jfxZ!29Ducgr`%bOUFZ$X*jnxKXKkEGN0+i4L7dq zj~ITy2E$pS@2-Zn{`y^eEd-O+)VHqDFQ*zN-F4=k_ZQV=!7SqW;IL=lmz;f>1Wg2# z^Va&yr;irF?ZX*9kycd9W@{EyI&o^zx5??jnw~YI84#E@GOT{B%7~9t|A}lQIqY$* zbm;^7aX>swwKb$;K_s@c9BFFdySRC~Of@lZpgb+;x&6asMbCK*fs<}P(I-J)pQNe} zWBhDDU5YMUh&24HXGcsk@a5US$G=#=61Q<6m}{5sfeyRe{kL8j8}@igung&aRGfW0 z;ucb0S6trIR&#oC%z@qXkr4RzJ$6stI9^&Uf8O|>HvwHQ0X@CBVmg@L>wO)XRF`H! z=@uq)q7;UGJmj9G#ds@B^z+rf<vsTJP{3Zm zS?#{0y&pEQPY*Nst)uF4;eEob^L4()TPxus<6+yJe6v_|D|&?4BR|%HkDY=llvtgU zw?xGNK?cvNv*3(hgWOXO{!E)O_AcJXilt{RkL8m_GT!8C@!dfkp$E1tY1#-*rCR6z~0o4>s&^?ZH?d0{YdTkvw0n0Z}kN^ zIaP?X1m**gag!G9yjI$rr^GL_2IW^Ms-UUcw7|_Bomzz)n1urv<2nyqs4{ zw{HmoryhpN*|(y^6MEw|{ewzSL9y{aVm#QQN;5&&V2Bu85RjTzDt79|^Kv7~On8yX z7$>!(Qaf^sYG{l}MGKFO{=n%e2#Cq7e!0K~SjuDFi?+YumP{&r;3`|UGPCK!8D+4C z`NK=}u5tTQKn=I5`_+AL$UKwUa?)G=6*n=W zSdTQ}XotqVH8F5xk(q)~iq6Y>7LWd0dO0;Mh>~4Er*;pa(b;Mew|GmDJ1lGU;o>NC z{cp(b4W@5*AXEVpih~IaQ=OE;jH37+jDxJ*CoKfz>LO977hL?y0^ko;XVxprs}dB}M`HRW}0J<}_7{$a0WaNY3d6jS?%?3l|{JF8Moe<0Qu=&tFu zWV7(6e#UC0-GAEjw@_R8Lt|v&Rsx)Yu%Zkf|}x`>Z=Npc`vr-wH%8lFa z@{#vdB=BM{&#c8|^(uy&7NJJXD@$q<+%F3rFjKEb9bzGGa><#2khXxB*;KkQqc(Pa z$1+a%wl% zGgY1W+)d3c{hTQ%l=-1r@;Xrdi+xA8k1RZ`(-K$&MqHVkSKLjbMfrAN%d#Tk_$`g{ z*S7qknkr^1NW`{s%*1yd4hg&+gfljYhrsE1rX#%_oRi;2c3R6qp@+(U+EqBV(5bg3 zfI>F98ugfJ$sk<7*!u}{1&$(MarYmm zDZ>*Vp?j{ndF!|^Pg?TV!)A_fNm|S-H5K=Z6x)$rW)a;v%)RLLLEyUne*flnS-nt{ zZN7Ys#&r^j7sdOlr%S3ediF#FBp`Sm^f`jurD5;3ugG0yBMp2e0zNnzo!#yx7Z|%v zBrjOcsaw>{SAs>r=qGwx^M>r@DpPjzciLjeCOe?bmAILJhy`Fam7#Fx#jn>54Vc@< zy8%aCxhJ;|UZce!_ty{PcRr_S>ZirlX&2h{H)xN=iLOD9>kwWF7ye=L;u*e$$tbA3Y zmPpA+-d392;h(pqTpDf)|4hljD@p+`NKLNH_|K6R@nz?Coltf1K3~yyS}G(tpRnKq z`>i@|48L&(XlL7qbh)wdlqZI;Tjd#H$Fnn~XkNZLOWCm&WR*NcK^03-J$Zi4=SEwx zZ+zZ-Z^3L?LlTdGsmveGat0OzFI@SaZHU3~i23-S>;{=+MMGuG{$BuSzu)|NIs^hBto!EA z%U8#TavtW!zxi=+_+&~ri1VoJe(Y1Yt$c8nJIq&L|_3 zrcXidw-S)wEV*76Y~Orlmx7Kje0fYXNu0-1a6PSz-k3y<{S zR`}>KvhIcAP1l& zpIONsfb!>uWh<9L;it5?`H+r8pz#-miU%HaRh<;63V!D;A~) z^xPw%W+S4P;}Vod9!O@lSA`I>K6JT_NV^E$AA=R8w2 zcF)15QTd#$-2RjKNC2~FOqkJMk-LobU-d0>+xvSj`m-yh6h(EOxuU!jJ}*77CNAog@7GmpHr;;k}NyMwBE3*zqELq+S#u<=aF8 zjCrPl3<7K-T)72(-Vrj&#HC>yLpVEvBoZ(DYjEf3y5c2dn+-Jl6Q|)jnS&lZqZ1;L zE$2XGSUehu>>4ye|9mEC{3BauFlehQ62z~aK+$T)>WBz(O0-b?3P>#?wa}ysF=Y?%VWlFSV-}C+Ma{cwb%g(5@lh* z1oAbJB551WtT9L)=alO4Ab{^$`as)gs;O~a?0S2&!>x6U6$D^(&1-;p{MCFx%$3FnUp7`QLxL5CVDGQ@32-z!UTG%HJLbtcezDK$_n&6 z=kYpuCN6yCyrU3AqRbYFgLC%!VelV-q_1=EOq=KML=bJ&JJB}e3|p{LNi>Qnff^t{ zz(;I}1U-%{=5O!*J7M96=$8`Gtb<_7bxkWFX-=q+{E>RW5B>sjV0PWis%(2G8$UI{ z8*$}?#Pi!U)%|;`+`4FFnEO9K-1g9ZAZya?N$hx9IcC*<$4mZTvVP~UzWf8Mzmb`H zLwb$aGs@<(%@8fHnyo>=PX-S7p0`(m_%7z3FvoMTPW8v#1k2%DD$y&gD_M_U+^@qP zPJR`)vJ}tXTJ}m=nEEJn3$4TM&R(4S_&vLrDO(PpZm~GKCsp^BR{Vu=i+~dC|%a!@Vk_Z_4kf*$; z&GEyp{~Vu*m_gX=|0~lu;6dt`phuskia$O4%W6`cYgnBV;05bnS@nO%l&nPgZV)Y0 zE+_>ovjfW;Rq=quYy!SIefv%FZNQH@fJ6pITlOEo>e=TY@5>%#!W2B8h;I`FoOmNq z!-%LkQBc!0#W+Lr7xXatYpv_)cqRn9Pj)iM%)%cTG;n|#{#n*a!C`SXnSSt`>CmnT zOFIc+jk(?5Q_y2}tvJg~yC^Q$2`yU9v)p{L!($s@8+^v=OFQ6EZbnO=wXb%|uF@~} z^AAgiV!g~(^2eQ%VpgYqzY_(Mqqs_pxA^{c;drpF=gw=l9%r+=KN3Ty*Nr=gIR>vy zD*EsS{7m-ll`0E~Z~6((SmPZITJCJ6i+976u&D&BqVk|5Z3k9<5;UTgVu=vkpt{Q~ z`)uX6XRNS?pvqyd7wqJ)S_5pCPU6h~tcuV2@&<>vVJLJiSk_xM@3yaCZv5*%KuzJp z%}tQoO#?P=`ujh?$i)U74>LFoDW`pH`&Sj>>wm*;LR+@_idot#I=6j9FT(gv!u*sz<$E6LN~!zd zu=5dr3-=!lYhApY(*JoQ?b{y_thx}Ua1i|c1y90lsB^;0mz)?~U;o$4y8nBGV+|ze z2R(Xv3#ArDzStEDcHP$~jpD-MxwH&TWcXY({2wjz7a`($+u4v+SzOH<@4( zPG$g(){dj(+9XWwPTW75Z@<+ng2%|uKZKT1W2oGf?>BVNExq>B>qbP>N@(^6n09-s znU8}`)k2gu_M~1zHqaCtaJu3?2XAxEmd1fBBKXq1Xuq53IMXakFk$EtY&)`?Ja-#J z+?iCthV}2v=ic(+Llp50&HgWs{d_aPd+)O4idiSnN~Wi|S%2YAYVxvGX3KIN+?_z{ zN4tfHm5Ah;B+=3fTIMiPi9zQ;JQ_D%@vke5U$+c{nNkqaB!Lyb=mj$^k&~d z(p_NkybE2No5muY73%lW;zeQ;EY+;zzeyXS)VU1Q`s;Oz>2bwa19>I#EC08c#`Zs} zv+p)@c23B;+O(ZK^&}AR&kDRU{=dHlv&P+~?W}zwJDU5T?Y@07y6yIGG8^phGfeSP z!7Ww#x4p+0*k__h=B(3h{<_Z+Yjz>8PM^4VZafpggQTSV*k5P!4GgTL-5vJjO7t-Gy)_b3SBXKEn z8NzBYzuoI2mZ=+L+b?!E{=VhBV_nJRKGf-+_kVv$WvEMP`g3=&VZ(&RRq=rRfuF*u z@<3vSvrI3B`^CfE`kQ;w{fqu23MKuc>#Za1VytHuE)w|QVcv<-ib8-D)(mzvg ze>Wd?{25hDkcMMj5+<+OpN6s!eggK70!HDXv@`dv>@i!xNQXGFMB7mbc8?=H)!PFJOE}%RIu!&ezEY`Os#Rsl%!}oPl5~ zqjQmgXgONc)YKeQHZ;^*b#!)k>h)aI2v{V&%;tm0V&glob{Ar(4RX3yYY`doY2ldj z9Vah^sPg1Zw554nITvRJUlHU#M*-Jzu*a?%tqwLWu_aFIJ7OdpR|hHx&t&sJm@%8C z8c_r8RLe~i{m(~I{ffdYCB9Jtc2QvJ<1%Wxbl`!D&CrZX6EQJ zE+O`2{GX);c|LT`f{m%BCScng(MnkBq9*U~m3-rJF@;9pb>~+5}YQ9SNgP^Yz?q2yS zsjFnsMt71xWDl_v#H@dfo#ev1TCA0RfDbJ6AHM7v(1g-zW`8Yvi2v3a@8C8$#8~EX zOI@OQOUt8zB$Jr=qscGV`Pn;8d#IBz+_PQrupWk15i@I@)fyv9H+bAo=g^|nupW$8 zE*l!hRC!s~zus^jhIik8C3E#4RjkkVB361!N!Ksn@9*sU6{Go9T`mWocjY`82EXpu z7FR+ABd-&$)c%8&C1jLv^TaU_Gx5+#-Jtxrgez-tL6L=uUBpil$?S9qg7NXxs^G#W ziP`K5gAsO;)0(AZ81URjveVr3`B`E4g)8J55RovMUeD45Y03GrANFLgoh69S?^CTD zO`Fhic@Ow;GFNMEq~QX1O$hSR_%!nkv6dFVXf&{JwQa6rwV#mOx8N}E<&RX&ytB_k zVy)qH9OQVCBM#^oJhuG>y~ue zvG7&%iBTrZb*a^nI2;9wE_31OAKu3WAdfhIMmv(t8P!i5(?$o>~d4`4B?h9uH5WKZ(F%zrdc=PACsH zASwbR6t%=PpWVGTt@Df=sWQ`AHm3E=oY08OEfKySg_wyT8)GsA*$yBBe>5gTj;BJ~ zyS}R?V9J~oSiDAb&J$Nh2VucO$k``NKe8=zzZBIC*He6q5+9EqsmP^q)Jwna+H$gP zYV{;9?A+AJ%OK3^BKq~6E?xlv$vT=o~xQ44vNeCj{=DFNUxa7ZFLm`Fw zB$T`g%$F>wMo*zq-eW(YY!?xH*w4gQ?3IQJWyDg^Vj@8s^7@~#l@r)SoI=Sz>;-|d zsvDBo?wdTBIxaSfq=vs^T1&F_d!{4jX$&XdoL(8OJmH-qXVw4xIwZJ}6D`84?LKz* zHQRCd9WY(lBB3fOl{kOd*_hEhRGzWO4D;8)RpSNQjvUr*!S$tPt5qw>QX<%Yh;0LV zKzM5v#2b)M>t}vx7J{*Lx`pnG{r)t5oN}5{gJNR&e&Fj0TWK2+o}MUg@sLN8ae;A4 z!!6K}@NJnlDf~yNXo>JcBc431L zM)H!FpPfSohw~4B_zKDn_za3tUO5XW9B+U^)opUw$&YFF8w|qeBYBCR^YWa+*(*lw zX1Fzd@K#mH+rB;-`-Ssz&V$_WX4D7Y3FUGqq)yo~$D{5EK2@w|a#SF-Uk5i+`rsyf zOQ8zq6%!x^8+1aY-koDsj=B#l;!Hzg%0~)e_5v`lST>fvCm`a8dhe|QK7TyF zCjWI@$lisj9b|3F$xXkUjvH$OQ3F$DaDjrmE-&)Vn=Ze%w=-Hd`br7GNTmxihCf1u zN}95Ra>)dE@%eGgu`NVZwckIln+PA88?PM%|3Mm*uycLYRD6j>Vd~`feFd{T-(77d z)pntPk8!EXs_?!*l{3~PZZHQU3ll=pDGO++MrmWh_zhvR!#j%pcyl4+?yUFLLR@;; zj#hZy;dHegdEw%s7w?^SgSZ(CiaoVG1TEnlbI#a*w^$Vv$J{9%-aG6NJ-iaNjTPuCJC`8MEW4 zJ`g6yggR5WdUR~gRT_giGr@>a-bF)fAbzHSPF6YKRi0WF^Cd+?twsM{SefJqQ+{`B z?^u`ZT6>aR$<+yyMrNLq9wZK!t(OIwbd#j3BhW_y%lYiM_+@?C1Qgb7!P~tWdf?x$GL!+KFf zZ}+iSeaZA0VIkhaapq2v8>J)Shaxvs-WdWuSetZk5%*IlO(RtF?;MRcK7oL#a+Y$u zr)HgUsj-)u6H2)p2Sj%LqkK1KONtN1FGj8WNFJ-Ub~)?TUiZ>A`TVR9Z5KL9rHE_P zTya``aZvHoW6u*zO#VsIzG{bmT3OpAlMP~3Hv&d>`~GM!U8n)ZBq6Y-$Rw__SHKEN zC)XWz7nt`ZgZ-#MOr0|y1SHCt3h*jnG%R;ZMEa4BGP z>-7{a@jp|Eovz|6YTYAI2m3KjJr({`*Au@yBs7bxBy*b(KXwa~>bAJ}{X_4~v*Og= zY*QZ&S_nvj&Mm7!9r+E-E@14CXn`rKQBj+Ev(3}$#YXj00(%N-3}kFtx0Pxi(`po}MnVqskOFPOq zlFEQOTnc1m)28gQ%6cg&`QebMH}SG0rYSYH&_K|9sK9r+hos$63g5{Tj3blX3I85l zFZ<;OqhX7jW|N$1NOQhPbbsvTl1q7hzC-wr7_~^E^s;o7%(BdEPOQ2}5K+(6O^!+B zMh~LK5pSI!El$Jf-U-!yhb^!7x$7n0=2Be<+LCvyL}r$uB}ue?fxeg2E@yx2a%ZZb zw@=+pX=s%Gx~^rCFwiK-{qUO(5}5O&y)SfwowFLOYNG?ptkR)SWM!NS)afz{r4;LT zI6XIe-`!2|H!f?iS)N)El1s>J2OkMY&&ynjLA0J zPJMu9GM8*rxGDi&(;8((+z*-*3)bBs&T;K4UGpT>} z`|2bsG)i4?Ry}P`d@`ml3)C7Ceu^gpW>elosHp7$Sk|8VLjw{v9wWPvU&DE)xfU{8 zigmfc)EfPV2%lz@Ku~KQx`JX(f>ox_(~`l?xt(qakkw$1e^Mst3UhaDObRNf6^8tpcti2sz^m&F% zJVBqsP#@v`19Kt9wx{{JeI?YosK?^|W3GPZS^vtq)!8I`&w=}i|LSO1A{M_M`E7T7 z*1IfVxuu5y{BRlm($M_3`TyJy*u9a#+S=yvMvb-xQ^4<>oE4|mY#|qJTmx*U%Nrcf zrM8`jdhE}o9&^}0rNO$D_|s&q6GTOTwb`dfsC)rU<4uc>F4lgfgVvDE0rV4`Nd^JaFz8IX-zl^#yL4+b6s!o!l=sb; zbom~&R`+}-ZqvRQFnfa0yn^O4sN30Z%c+$-3xxgEl7>~q?m zA5=C5I->gnd8lM?aq@MSd=U~S$XOyx9sYrx_jy@@`~XL=^x{=oY+w!Mo=3kfpk?Yn z{$ralO?4E+%7;%B-pJ*DW!mH80*8?Hea-5J?)&FG!kEf+(FYq-bH z;c#@h*oE%XBt8&i&Zny;FX76LBzYenH9lDKDd$M&$e=bpI!km}-RL@-9_b#iPsnFt z$rJ56Z2XDWVpW`UWLd;Yf>w+kWljtUe}>r>ldJyZGV&zJ_w?Xh9TnBMYY91mw}xLi z{DW*>e8cubdu6fq+?6QC3cW77@b{u&D)%<*S8r%s^&dagn*FjoOVPR9Zu5^v>%F5% z{c=UY1&i62|A$iI<5?P#wu}fa+6S(^o3DB{qteO8lfeoTnB7;fHu>q}U{dbmaBX(o zpL;gG8*GTJP1$0}7tzKvtx4V4UpL>G{R4bmMN0TCcY8(JG`ta#C8=wU=>onZ(SoK< z(DL*T>R*OwVk@xrY!^pd!X79uaz{cR7k}yXGyLfQAKP&Fa3Yu!nrrM9F#o&fbK73< zTpwO^DQ4w@N-ExU>3AcXGh418qvY4K)K+3E{Kx*v2%Q(plTi|q1Vv+HGllOWh7?}m zdn`oWPZP}FfAL;yW>hATxvI z3y7fvh>fZh1I0jvv+=e-AJy^@!9ejX_WG}12mAx@?1kAYm|Q5O z1iDqU_jHG@TW_o%uVH%&T!u<&Zo2PTz6^K7F?O}5-;t2I#=tRTXLRecR}HF)yT$X~ zJfHWre~u@%*)mIBHl&yp@Q_J9!LL7T@3og3k6?QjlZCD%xw{GWwT*LA#1>~LEgd!= z`0e^IT-9YGt!}=0TA+F$XAn}uc40a?UN7;{1(&U>2ln}cKYh=xisF7f6i;Keq(ZNx zUO%3vWxAWG4O!jH3=sbd5x9Lk@DFg!tb{dZWQP^~1Gp*eqQf56|B4z494K+~vi?fV zX`&zTNNz4;AeWk0ykuAXJlo096K7#Ao87z|EJlq0nyZf@JI&Uu&n)?pgIMDF>v9k+QIeWFPpqemDPwrNmv@>tOrp*%0+2ZQg2 z*lI<9ay)`T#w0fb@k&JvDghlU<>hv@mK!PL-=e`ofrRUb5%Rn^pgj3#C&N-Jfs84g(q{2@Nw{lEoQ&7czHlE zc}v(%9zn{~MoR(9=HTT#Eye#1jNoPS!|-zb|EF(va>5A%>dzG6d->GJAl#9&$Cj!> zl1~gjn-7pj$3YV00eEKeZMERa;O67Z&lV;#^n`JnCM<7$4O^~htqQvRiQ30d#KAFa zU#&#ZoGyi>D?vw}Is`)a?8DoH$Pk&ptZJnvUlL|Jh+lYrMV4Sncbm|Zmr3nGQYo;U z3D==TfBH$u_9lUOd6W>g} zaC6W-tL5Z%Sx4yvcX={Yi&h_2?bz)Z_ z{Dk6{(-0BLEy$illNFumjuze)*vs!Zm;wTs5C~wZc#ZkLRBo>t1RzIIM zftFRp?+~SxP0M`|-F_pdAt?NjV%bK}R z*MTZs3?mB=(^Buxw5OrZ2-9E$TuyY}oZkU1P>ym*;7~yP{&1ro;k;6^UeX;4MbWv`q2&joo^FN4=+cagE(<*UM+*h|2oq8 zNC`E@>0N=L@N#M$FwOGtqmg_U;}0=?TZtT#TdE{K(uo$NbqEpx96l|GGPa@qJ>v8;ul%G~b|wJNK!=3rx9|+6MRLbGMO@8g8I;LVBta_KY-@(_ zSRF3%emeck#~F+;$4!}>@91w!13>hdzXKJiI>b_gAu7hQKq&z z??$Pe+$40iwG%aYH#2$CC}?T#9^x8Fqdt!9Y|f1&kW4B~E=2YRO-~B0<}(?fkB95H zcu;k~7wZ~~*3OxRHmI}jl{iZBP*;kiYX`dJ1JX8|Ir+op8Z9z);+)VB1pIV8=S8_r!_`4PAs(4 z`c-zdVW+YBF0q=Vo0U?qMIkshd39^HKjUg$W2v65)k2|F^3TK9Ej>a(Pc>m9lz@PR zmVg@jJRdxU@DcILqR$|m^Nr-DBMDEzWy$E3bd)Y97aX4^15Yi1vk-unAYsoF{^Hoa z2BrJnQgx!1;|C|a@CF#;5ebh_6lIH|CC;gjrN;$&JIMWJDm2ataD;H% z&a`NK_1%;I+bImh76sH|E5?4Ew7={mFR7rZ(l_GgRJ(%f z*Gs>ealL#x=TX%_=07bq9RI4cC2$w=%-Duf-2MHQGuR+9H9=lZdf`75chGb-2k?NP z$-=k+y>2C>@+>@cjNtNrY9F?Q@>A&@X^(c9Zb5sqi~pu5w=k_Z4tZ~Y_|AI)6$kal?a@M82q zAyl)v=fyjdHOFfd_ie|rMl}H*re~>f=pWsGfWzf$vQ?RWO`+YTK*z(Fj^paTu9xVr z+n{%;BX2!!e>^t#72b;968&S`d3eRdR*Q7A??QG>?IZPbr0vCC{0>>XPhC;y2vDn@ zU8c4=F2KYO{)DkV!sMkKYxdq2KbWlf{Rhxqzqz{!3)pQCAoR31gD_tG9lHoX09ZUJ znFO4bpgA^jdpyCWaqAW6!_VU7*W{d|kI&x}e9HUtZ{95F$H!Il3tPhqs^a#&HVU&H znyIYOV|TKAJW8JF7JBx`@P%OZ9w?@RS?E*Oc52ONsDjXbKl6si@89w)xq7cgiX`%=UjpUrLf@V(1VN(rBICAKjx-(y|D$ z&cjI%CXF(%>}Diwtp46wp4@T%D5pF1>#DDRKID1%+s8(kSh4kuiMJ)!2bLN=p`R4t zec(~4w&lR~TKCezm#+GseLHsB4V^JM2@$Ik`?LEH20?^+N9KkVL>nim80b z%cCUkeE3}Nlp;=PJ}DBsy(s6zDQqqws^iO!;Gdpcl4#BCYnof!5P3kima;QNm3mybtK_-7AU!$I2B=V~|s zON32*UF~hJ44%7uM%pheY}+{VL9rvTXtUDmT~9T>-$=;@VV)b*(I|nmQGa^IFu)kC zW&l4VOFFw$1E!SGR?kuH3^UB;)ZpZWW+2pA7RLRT$io-NpKE(kMhnvnSnr(T>rR8& zj~@y3Oq%@9P4TpT>%WQOmH@=vRj4 zh#7Y8S*35k{17jr7S0exvI$2B??K8|kwHu`o*~CMA{A+1qspx{$ZZR2kmw^S=(<=dy;7tk;slyBj_0k|S@5x{?Gr@|Pb>*{-OlmDr{8H4z!hA>}0U>t* zcYy`Uk$FK%>6PP2;;0SSH;0-DubxEerQ^pH_zBmv05VuPILSgdEq2lK_s2BcFLWGv zAjJ$nQNIf5$q>~EzGAfE>$U#3)qcOZEmjO6`f?gWB`*#_{$oFQR&elBuW*KTbSfY(n=p;{1Q~Sm05JrnD!J zgZEom=AbO%;dQUeEPa^uPU1*ztP%ChPhDx4QUsfL8p1`OKmtC}wq@xyn1(1T83ZQ| zy0iXb!p6W(<#Cmdr03r|Ynrv>EsBUMJISmKk*IH*t#~yXuD)Efi367iR!L?MpDmo7 z;KDwZn$i{QT%j#`e1Br;3h02j!#Sq2h=gC7AoO1+AXKqmX3=KN1VQ3&Avk7ud-N}8 z+Yq7A7^q8}PCTo=Y!#EDo|f4chwWR@fHa4z0Tcqr! z@Rn{UzI5uk^Fvc8ex!^{Djk`+oGQL(!w^K|tvY@bpM(>bQ}|Cm{nZ10q|5)6z`2ex za~8456hbeVEYNGeEYm{24CdrgFZpC^s5!$L!t>RfS z4#bUQlLJ#yK9k)tb@l**$TL1MSQ8N$VQw#nI8j1MGS7BQ8Pboa%lANEGn1ZpQ`_7n zZOcMV9`%kuO+jASp5bIe(Axnq+z3`>%*dI}HT7^|66y8Qy~tsoG%oD|3O1uA{-36E zf(Qm)E4j=uVi7HuZHoRdijije#QVeYT;|Zrq|u)UO7a6}&WTC_uP{LkE~~uc!}oEzNfKChCO8N9bOF<^9p?j`L7p8;rzu#Et*g-_wJ9;yIa^=Z#&-} z$}a{Rd2VI36wOIAbic8!DYq=@Hpb>-nUR8}%Hjt=ITXdINt4Wif?aKqD6@>Y*RZc3 zQ1NPX$p8l#CM!ks&E-bnxDV>}F%;rUayd2hfr$7EzIp+fJvV08k8h-l=_M6v73y+7 z-c^zv==y-x^GT6%TB1$adiI9Mte~yOFPbXN5SE=4X^XqBnB68Fp-mYGPFgO15HvhXXsqK*kVqP*qt_D^)G>y?N=f z(eW*J*$ZxT_a4g8&Hn?FbE{(ryQun2hZ4+qg+eCQ9fN0oueCGLffn7jPm!PEPLk;E z;#CLmJ8YYItL>D?&X@_*3)IbKtYjgWM22rmxRbFLfc0O9^*H2DGt>!nYPg| zoaD_8>V~_yNV9Ptiix}X=X*Q{Jq|j0E!;|q%$B&1Pr`|z=$_vn!1mvw%lwi+#OHJ= z{{f8fA~&!G>#wvw8YA*Jr`v7@=0fmr6P=+j^62R3c+8v9U+?X`J)F`(U4A#B$}XHm zmzFJ34GX2+v_j!2Y2b2}L^IuTH`cX0jq>oGwzzL6p3T>n6JuH>8Jiu;Wrm_yrYbP` z5u~}f^_XFozv0xGnbXse^fc~82W$OK z%WSawJU4i~{`K{4bPX(L!G=wYA`5?UoIY07oSeCR#yR(_-GRLF1 z1&`oS@0?vwDXfZBbyPTXWFCy-%O6E|f|iyUv^+>BJ7-`XoJEmb14j`* zjaZw258lTa|N6K=_|U(uE$0vQAQ3rCR5HL>E-dZ#?4XctHt{^Xd+~^ug!pus-yILPJhf)s<$?F48 z$Q*vNiL)g~CU?UBnFuf{}&8cg48%LYvq#bf!mcq>;?pL)=V-sbI?lN5@xHWxnONsvb5SbF$JQ~vg{8#Rnn!MKvb z135~JZu%WszcX8LiFr>5?O@!HwA_E*NnPKR&mDv?^LOXFZ0ATZi%o4?eb_`E1fBJ9 z>Yeu1tQ^^Id&JqoJNJIBMy8cJ=^BEu>#_3k8uz|$R=eQ3Gid@R_j0DAueEWFh6J1X zWrx;@G-S4=h}bIIOtee5I)sjv1U!hKAKX$tmAU3I@w{R(+h2F}-X}-N#J)~0Z^@ovgLS54f|EvxqMHCv*C((vl9)(jKLijl-#a$V_H zeYB?~jg8Y5<$1vy{W}Ub|KuN+&%@gK+us%bl;?}3c3ke`dcHk+lk@pot>9;i-p}q+ zs_);JG)SI?QTBOnYFsKMamoU`%bd7yzby6p?e}sk&%Hs-j_Pi&Usw%3vY&aFpSf2~ zUiE4g7kMO%fn2l?JYXJ$J5+DOD|~!33N97iDnw}dagrh1pFxd*^7D}AzU$W1m_Stc z)2g3NqG=6vDF?(|D#Ia{*nw)~U`pW%b%L2guOq}?s$cX-W?x34uGU6*`~H77oy>!+$GV`>iixkj4p0gtTIj4p?h6et;@=wa#)N54j z-RW$v^md*gufNV1@$fWzK#Vo@l1bu0hq9?Vd3o_y9_~OorNTEdq5&8(f%cS(jN^oH zHKZ+@3HuXopJZFEIW*!srf;wP#iSF(o0lVa^*J}%tkp#cz>*&rP9`NDL4h_7ztS)9 z6?J)gJtYB-qHouFDi-W~hZNJH-7^jo3GBXqK7GB`3+xdaX(2pWiV$)CDF>!;m~}Kz zyh9GXQ7<6Ay`53*2KZSMVyW#TOxrmZPD-x$E@rHIa72?;@xiU$))xrhsXU#U?G42} z04@=kldK1D(97Zp!H{Q>2XW8PpZYrZ%tQM;uk%uNw?+)BB4r+XeB*A|)6wmNzpXrt zBVi+txevt$HVe0E6%$YR?*et1gOYOIwM+=D-pV%8AHB!*5E5v*cN7w0($s1znlS6c zx+*#Gn=haH-dMDMxqBS+U{$;KmMQl2rv-bFA=(~~v+r%0Q+?byZ6kkmMlHQ|Pb*B3 zHfrldFfm!cafShR3$boPzx{r{qr3tI{c;E2AF1lc{*A}f?GK#8dkO&+Lk@#0KV5NPRLy3neN!&fyuMHG# z2UriJgo)3X7jbfsbMGVcJQ0N}BqbisXNUY$M>@--?$`T;_OC7LSPSjy^(u`G%PK(m z!iHRI&RaqCZ<5Ck1W=YUlIw1>mQ%&qC9|8=&J(G=*WPXndpdrOgG>=321uF;IibY(w%3{MgixLXPL5AH z9z0XVF)nVmilN;vUA?Qrf(KWC_lRX5Le?(b^8?9yg(~GSuQhnDgm1_e$jS2)ln%f` z(0P~lJiW$(`l)c)$OVJBn-DLr-)uej(l39ikKHqPwpU2ADo}&c_h{$&?7y@=@JieK zuE!Z^9v>3pV37PrRL3wIT!u`eZmZh04{on?j-??z47q!J5wj2zc1cOYlLbt>0a@|D zjag@|ek;?<`I}>PG_B6;y`d&uvych2^pJFnP9CgZgJzWG^3F7rLL)U3^KRUarZ4Zg z-7dEO1LUNyHb0PhSRD@C^453qX8oU4E*8XTGgWzKy$2;^^rI=DKe1} zSI!eA=`b|^SP0AY^*vtC$d4O>Cl~ZD;q=bnaqJw3VYR-fUjj!aAXCHNwA|8V(xFBK zfvNF!1GDXTTJHePi^HT5SxSuN3CetiRl`i!5r>o1Ss*G|T|$IrZ}kl5A9Zr&A2}MY$$zp(vtT+&ulM3U<%X z6R)IL@VI8PpArR@Mb)vgRLZ93%M@ZV01E0Q`knZ6Cjz0fp%-=LJJX4LJ+5O(RUG#A zanxH^Y~E#GGOV#xR`(m5(FLnhDSfU_R(nfEJT*Ja$Ubg7ZS`Im5!X;RQ4R-Xz)D3x znJY$wCaYV|>JOi}GrK&X(Wq+Mb#(0bn%@XHD4LVa@S{3_L_?gO!ZD;sHel6t@rO+> z)$tQSZ?-!DUS#AW5dV{to28iUmr^|e5fxeDy&y|DQI_Gbv79=}}C0Bv5g-q{3!SWdz zBK785g(!O0!~h26KWq%n5J$lnJx6W789fcFH#R_U%S%7C3SXQrKKEXA@pe4Aji!A1 zOS%*gDMvSyz)nPA0>UeE>*54K(&H-ci~W3$1`brg4ack~m}XSp+!Pjixy1ObZxcj@ zeTYLwcKwfPf|E$2{0a;D+HinKeikB~7?Tw~h(!e0ef7c!yR@>1{9;rhO`Hz10I9WO zA=D+p`+^fg(8dH#6Gu1(Rcpxk{r@>_a-jAXy)8<@_jn=%Xs@ht`>&IvpQV{U-0i1i zluJrIVn)SRkJ*mZM@vlmJxvvLjhN1S;Y}tPSBgCJrjka6-Is~R#fy;uuOOTqqN;pP zMn00ly1{r#LU8fREMj*<2*4Gip7>7BTVm=?$*s_Fa&A3e` zN`64p34NSGG@+7!v~cSfrlDbxc7;^Co(O%ooO|Q6ap~YJ(5;4j?kRfM2i^Qo+HQ9{Gj5Ks@=euVh)+`iO|G7^Hrv)LGm z4~1v%q4q8V!6P`XiH;dv0vV!{$!b%I#l^=bv>~JHahAQ#0Zs?ZHrEUSo%0E-n8pc~ za>Z~6T_jkx@GHvAA5&Vali^i_2_nu?WUTk{uwLM+991!Fn z&d4FDOdUWYnUk~G0W{~0V`6HR=KjBC)~d`0Aj=UR%Bpng&S zY{JGRgA+V`7w@Q*e&VQY`} zfy{NP(^*i+g;B;x_3Bt7eA&1lJCN1-xjDsipBR1D3g$KSvtb3|804J-$OsWTG=B<)JsL##%{G@C1dGh4 ztAT`*TiG0^$r`c%J~yF4kpPdN*i=a*vH0q^UN{-yb|a(X>ls&xs@xPKs`v9eDF-C3 z9mZeXcX-WXaP&&g<0IKuT?1PUi?nJsck4lANn;|ifBU+J)KNJ&q?9-;dhGvm!(py% z({35mljPXd9(buOdLm0aj{YrLC@1PGj1Z_F#lpvnh^kSGC;9q4yFnUA63P zYqWOtM2P_lqbtiSWluLm%CV6--_5gWn5QWL@julb83 z31W8VI$hz2<|CTR?bg-rm$2pAU(1PGR`&`W4>Dmfp;i%LQ}R*|lP}Iw8poQV-z}*&Q+c4Zv1etu?^w6DUhHz;o8CRNrd%MKvrHOYY(S72^X^0C;n|_4 z^ak0mU*FS(%WM0|+zDr?;5V_>Q?G4ll2%b|(J`OzO9{2UfXbiIrOEr#Q4(&xoHFnV&$5TEZH09YsQMUW-gXvf>@3w>cw8CU4l^6vKU3qp*-E;KC5_^y6Q`gd~2F&AuI?zG+f*kQ_| zB^Nd3mXWPRz(i83OjoX_R`=>+x^gJgQCAQ(H*ur=A0T8ctn@8&TR*`Sqs+q4!Y1ea zj!6GXPTj-B#m`E#;B=Vd>BjwhSV{B0A&kfSv9AA-{xN0a_&-4Oe*nxcQTIQ<_Sl1l z#j(TWYD*=0%q=TxIChp2`6g)RsF>Iys)cRz@2W%; z#F?meP7r6hl1>%HbCZCY|^PT_AoX5I?IKC&7T;YBJ9Y(wN-JD!`n zT7Q;AIi2CxTe!6#)BZ*puHaIpk$wcuCAO)1))9|-ho`R*V5vy;`|v@S`Tq?@)+cnf zqpQHvdLTKrcijY?&!K+T;Xkt-xVU56s9i8SN3gIL1js8+PSZ$(mOY)(ga6_B&V~N8 zzwM;?z51V&UDL9Xmz*{ahRIAYRsTz=ge6h~PoOLY4AP5Q51b_2MKD!K%u!pZCO_P=bA%^My{$~PmcH7rsB?ou z;a#Pi+@ko1;dl-(;od6@=dkploxAPmYU8mOuLJj7>pXGnbkxgSA*r#z=HJTGU_ZFS z>G;RY{M1>2)5Y|@zSC?{sjfRVxF%wm#qbEi@@5tq`cgMUGz#ok{=3d)p#)SVpPV{+zs;2rO=72e8ess^Y9dC ze?#Z%8`|-Vah-hEzWwCe+x4Alv(k3=LN7rjQOzhWTcZVaY-Q8+JJ20;#md4A<;E_R zEPQ}cUF;Ka$k|ZmARuS(;{)n}#5j4QstBM&p>c{2GFwtPKY|%S@V87|e#E7^KfgEq zfW-sq$H=o-Mg3s$>U0_SZS**J=N#u4crTZm$FtUG@lk;B_V;lk(Zl0%0ej=4zoZVdaj%pi^AGfw zc(X55jj#K?gPH9_p6E1Bm!AO4&syY21|Y2hK(_os%~u z1EUB{yaX(TbM>gPuoS^hh1E+gEdKT~eK7OC^2&MVTPCqQjw$7pWYiy(T=O}sbH^q`1?DqZGKd_3D=6LWuGy2 zdVouhFD@j5GFw_BZyvnmH%B&l@Hpwm@gHFBKr>9H@#@{!d>BvP2f3pwg%A8*%hEfd zJrDe2W54^?e)ScYjY)<%um7-c`98%wc%x$>Y8X?zg?gfaA(_!K=;93L|770}q1X(1 z%kS~3UZVKyJHLa4lo7%4VdBlm879C$C);eTBHptMYZ zh+0v6R2jjUls|M>LjIxgj9p?8$m1j`rpo%Fw*!(stK}WtTuI4ldV*_HClkRhWeq|F z#!gsuMcZ2Eqxxr;^r#j;$;y7gOAGbQ`M=^4lY%qj{JWl)v7{n<%$!%sz z7j8RRnq8s4X{x;+pRMt_rbT$2IMzM3N*sREO@ud^fW_{%9lHIrD=lv*%L@Wo%5zblQ z-#rme86UrHXjWDP@AZS1V)sm~cMR)LR-RZrPJYg@1QApN7{sY3O~|HO_nv5% z*$q8kqa340ZdCg5JHPugcqNg6Fn7X7c{^d9SF~osASIftJ?E%&<*2Nh2e zNb8i%0DgiPZU-Bs18$m0_W8tsfMh_~8t*82@iR^9k!*Was`{D*4!JnvYr4hq0w=n7 zusqbT9k-k#!x|vL6}jTa?W?s);o^@Oo%Ey`Z6@jLfO2(RT z`6UZAMH`x+i5 z!AT0^CY;s1c4FuAy*S=aXmYCl&y1gZm7K$E?-jdc>}I)Y*@hGp*l?3Z)mM?132-T8 zU@WYq_)$9^SyDI43;JH7fvg$<`Vr#x)i#aPuT!-j7>tDddn zS-s(f`8d96xoF)trW!oFHARm1I6)qTLERqW({3Lfq6pk6d!KU5*t^Yg=~5{EBP0iN zdgh$BbP$S`tND^$7Z5D`@5%@h47NoAEnBdD8dRN#KOM*8C`-l!_X``4LoR-c(WPt} z;#3wo4<<3Ar`S1jtU&Hu=Rc1w_;%_E?1NFb-(-wFjtNUI{_r1qDfRy8iXI>1Cn%6X zb_S=Gclml%|3ZNt-Lw+_HGWb*R!Km1cz$KythU9q9z5Q|-ovXe2xwJeehySeX zt?oz{n!F|Ni9JaztmAP70u^6@uuR7_WaxN_jI9d_m-)^ctTc^|{fCZqhHME)Rzn!? zB{GzCctq!a;%1n8`WXXY4y2j*q}c%-a?PE$RlK5LQIA&?TVMeaNhty5VP;jFXb1&c zgr4|vGG?`ep+fLzu<%7-de=#xF?Hhyy!8INC-?s)0{GK5S%zs##>oU3VYAsf<+g#L zepOS?2hKda>Ai;FePn6!a$V3+wH=~qlN&*)cJTCk(8VV*V>-2>;BUEsIv==NJ(r6+ zHu?$qmZ5;0uEhIHHuLY=rr^&m{QQ=1m+ud!qf9-LIqE&oWbw8CNld91`xyt2pq|idjM^ zte5~OUzTB)p*2RE`lKYFI>4xs`5>j4BcB`DHiUf(#7PasR#hpH_1BaCa%$n>>;;K( zJ9!$Euu+}s9_1{Q6cCQ|p&gH?3uML5Hz9bKcW$csc^Vl8YXw zB#@p3nMIRuMKPYkdVjD)R3;!|QOV5%vI;B2R&Zp(!#aJ`YQz2w{!rs<_Y^q<9nip z_078e*qT3ls0Ex%UxR%Wj{Msem5WVdPUoKN?!=jkR!l5wQVm>HaU)cJL$p-X`bCfP z|J^akw&SqMeM6Xp2hIe7(!XFq_};YKE649h=BW-q(?3I(idQL%Sz>sxw!bck9BdZ1 z(hC$l>O5F!F7Lfb3AGRu6B1pqYyBhjT`aY$_nPeeW`@V{5L6?KS~NDJ)GhC9?5GW(YC~*ls84v zImc_F5P^ENFFVE`eW!4jFaEp_Ay{~8E~I2}wmpn4+7Jy(dOZI6xO_^65>h>5@E%*- zk+syNKKYis^^V?Sr`Jj$B*0}+%Kfd~U}COh56kL_;ko)nhaPMdhz->%<=tvj=fIW* zd;RSvxg~gIvUBjyb=BwoX#2)vY_*SIEDRp1aK8UfGQj+SPlD@exX+_sR3o&`g}!H^ z=Vmb=)c0y=B5C?_OZzhbklPY~^X1jS>Hg;2SO>8BI(4_$y~AL^@olkNgQ-<;z`M11 z`_Iu{qQQLb9-zHfvUp%g|3UcAUV)#1|Nn-G_5W^|t|RDk>5w)PmD$NAjH3S#1`QAS{!?anJGP?krL{>K{{h~%AXyN6Vl^|>tix5vq-pyMkdy2i zOk27F-RN?+9KBK zPqLw1VNX^(=?4@1Lh-xW`P_`ybzjqj4co#OvFqFSYzaX{kSqcwq$}@I*%~sXCBPXn zxu@=yQ~@(emo#ktC}<>zOA4gYf6oYG=h;-;@43=?Iv6o7MBXVAXQ%hvdF>ac91!8` zzwf=NLa}%-z?elyg@XkpG=;re}=23~Mpb8F4$LuX{nzu39Ua#p!O(=tz^!qwzoN)+(%gsQzz=;Nhes z>lgsx(DP5ccJu0t63{i2N|1d_33$ys7SibSZ-Lf>pDUo|I&}(?*42Weri+Z)kZt|P zdOd@G@-@stVUM1GUl_+ASh^rmU?zMk5(Wa3{Qze@MG%B)WWuMp8MNb*p9I$MP??C>1QL0wvW?+mqImeMx5Xi)%R?U10D#?MWL~ zj~#w?AKF$GKMvHA&rQVfCkAJ7$JyidM!7oG1|pPV+lZ zPfH8%_9(hK+)vOGj?tyVStTcD8xXyAq%m{+8cMD)QiEbuJnHbNYV0!5Zy7qb2Aos> z$gp|+#H{smR62YOEBAE^Ev)Np%|QP(!AB1+b9B_eb)j2#ki!sdpUrO}&xmN*^P}RI zm#i&ivPCP2PRr`+Tq+DhZDS{4t;yI-=0$E1r2qFwAophzpEnK4A8}Q&xkE2 zFkT@4*iM-i^HQ~}EFKUX?^38H-EX&m0W5)P_L zvD^72`%Pco?7}h5cWr0Bym<6cv+rs0<}K&FNeZ)Pne6Ot8mx4RLkIEDUT-02V8j*L z;kCOa7BHuv;N|u-97QS#+A6W&EFb&CZshq(CLy6(KgS5ofq;z2tyONmlgFRGM#C99M4LupA`do|F)MQ ztPz`yl4m_#&g$bB!Z&d-F!ehMBHHG#0}*g_?&(ls1A=^`xQ{6b(Y2z3SeHRFT&r1P zoR*&TtcFY-9xj_i-+GLjv-TBvzfK|#j4DYfi8q{=64qIwxRY^wbBWsYqf=J#47d{t z2tzAYV$UT1olNnlZsC89`qXrD&8)wJrQC&lH+zM$XfyX~CDPb|gu^nw%<#tD@kZ#i zRjG?J@hnspV`Cm3G5A}1+}~c6J(dU>gvOcOC$uJf?GX8_nhP4LTF+T3v?e%+qsX4Z z0^-pcw^4C9EbCS=(p*|$66r^NCBtqn8F!J?EgcM|MDLEz0p@@Bv5H3&GXVflR&+U! z`up|;{r{aeASV0VpWvDMR(2=XQf`r563M&j`u1O&jTx)&a}LWMdH&e5S=93Aw5kxFw1)f7H!VDeK&-mE)HI zyb8CZiuN`-!w8UxPew{9UT%9k0fsuHtR-Z*8n^!n8m1uhf|3!A933j7og z6Hm-rCkbl((Yp?eF9&zF_-XS46b(ILcGxf#@;7=A#LGFj&Qx}%_;ItkvQHA)(I9Fe#QR2%^(B~w)= zPl9JlhHb{kLMPmGu71^$vj%09@8|=;oa$NeFRdkjC4SzSnsd`P&d;OVdVgyyJ!xLm zj)e-igW{;XJilD14NSIyk$);UI3m+}tuxZ8l4W-mhRnVht-fGMN&c|H;Fp}^bqFu- zvoE*lpa~Fcm>XGIAj*iw$t#~BqO5#UE|w2`nsw;G1T)_pqSt6L*KK*Wb20@Ne0IW| zuz8ZxAb@7HF=aD4N(T<(V2`pu<7(W`9*OTD5rZL(!Q|0oyDm^{& z2D7v`KSFp1vZr#$Y?9pleW*u-jn-6XkK#EmWkg zONHN&ckdqt2g!kYbhA-XIW*+e?}_XGZ@^_j!ytw|K}4}|X<9sK9GH+IQQul&&}|epnCJr-i zsBa(|B%OE8yQAIXplAvN`y9E};b7#mJHD%#4fIB3u9f$#?t>q$YGp>sjOEsMjGNn4 z_&ykm$9~tuyiw?NgTu68g#pLlB0m0SMJu>m2^^`0XLfCTegW$Ln!O$uo_k&in*+%< zLE|C39K2#604tWmT&COo2TDquN_USb#S(i81cGB2AfJV$Psdyl^_BazQp6*P%kkjJ z6WcfZ|1POW^M&b$qD^h@jP)JP3q3h;!*csdJQ#KT({cgH+$4a3vj)&KP&5bIkSkGY?y%DCM#>qpiM@5>gmMja4!nqw`JhPPpEEeO3j186&c{3P zIYUPuGJ1)JKfQ8qi28|yBR>(@3%ag0G~Z1TbX4E$nYF&mgw{ z1QzBf;rgG|D?CW%vZEDEw0(QByp`LT-N1Ijgl=Hi`NZj*aUQVe854=UG97{QJ~A>* zkEr>Be?OVv199`{Bd1uocEf<=VOf!@^R*ShGY8`HxsgoTETe8Xj}qnQQD{6!r=SF| zIO<%|V8H*GkE)XU-MhG{0?WWBWz*S~3p&>18TIMhg<>Xl6%=#e(p9_UaBm8~)J!?ZWU7NX-ytMRz zGJ5$K>GT4q$r7%?!ZQLW2Vj$j|G4*RHkY5n|8C*7G`I4n{`DcNGmG>Pf}sIfC1cES zSjCbC(O`)q^Ua^RUc7u2(&$(J?>DjEm6&6KIR5dm7ytnjsEgXGEqIkx#VvtH*j0Um z;POKNG9eSzH~9RV&WCv3yMJ#5FGZ2YxX>UEoh?L+l+?l-vYaLK*Q zjD4cpahT!TUjzCwikylLb5R(RoC7l0PJnueF44~Nb)9_RfyHEHv7Ddm4sKEP3{X~s zBeL$8iy&$HYs+9WbwjbU%T#wZy9#a0sKJ3aB{OemHm1N$xifod_iW5l?Z@z{YKvHA zws{B9JZ=_erG=>|JAWo1%Jvn_QTtVtNh^QT{0f>=CYwRDSbWF0%!*Hd=SQk~vdNb2 zkIE-zGehO&(w2Zd8x=0OH{HE@jcQ&!+;VL}12iJl9=~Vx+O3(vYhsP@ zjrUJz(PR;#YchgCTI*1ziX}G=?GPT`aH@(eC~7`V9mA<+!Um=QW8$wE*bt`w2tz?H zvt!Q_r(R?J1aBT?5=de^_DJl#N{OlpN`z8^+B=lmqqSF2d(%*R&rnorx3OXtv6b4?YD@M0<-VWq^L<{w z|E@oi>viRm^E%Gscps!rN7FY|k8iJ;OeL(efcs>a1YQA+uTS(3Nboesc5kvZ{MJ^t zCB~;1^CS4#!??0Z)vi#-MsDOwulGNmrTFzqPwj5(3!M*i2L=AInh${r%;x_Y7hU>= zG@35{TuJL!7edjZ=ieZp=#!mB?rN`9m4F4YVF|!TPe?x6_TwU~@Ga~(RJk@;R2`P( z_?r(!r5pumCNYV~zs%Fc(a2IQO&5;NGvjLf@78ZkGRl`mOj`Wxr>6#K1S%ct4hdS6 zNar5F)^dhSNOB072hvr-p%*45S}8ANl-&4;R^Bb$jJ=Sr1uriWf7ZCjCZ+oRJ)$y+ z2!iPHCbM;e0U`MFYt$mMTGJ;5K)?>O@3u5BzS~A(lFU>eQbkzyMvL2uG)C7n8XJTk z5a|QJnCrob)}whm(SAyBf(Uus*c~G2n&hkMNxo_ zH^S`Hsu}Z@1G1G$!5G{KfWERx2e{e&$YM~-F@M8?KoW6 z=g&%V{#Ie7=IZD>k?B0LK1g%f{B{ao8(78b2sSk)zt z`X255d4Tab3kwB1x$d&A#uu8Z5}T^(=3GH#oP}?Ba&q<^N3Ylow1=Xa8o3Sg3LEIjS`cIS5ic!|GElP_)PFH6$w0iYxf{wZ( zekgQbfJ$XZfiyA1yem(v+KzqXLb;2_b9kl4(8Irf^M^Q(rOLonUE5ZZESS1FCQ~4f zSI~{eHTOroOw^Jj7PshL@J-So*l6fEP6|uuPCro4>t_JPOKWHieWs-M&{P9^DWdFP zyEFg22dM9hFFa1soC6X?%NCnxTCaMp7d+-#sVp%N7{MS#)iHVs}{Am%&YLGs(yGD!z#ilw-iYcVG$}!*Myq;jC zLH(KKhTso|@9#!A`QLG@rb#xj&?j#FiaNBg6M-QbY{wn6we|yC&!g4(7))U44uU{Z zL%XlL14z@eB#nIPd&x)Hya|?I*Uq2!~T`oiNZ zfr5!X2N4n=fT#$Wq#zkT+L4ISOVun((xrV*IfdSTS^j9@`K@l1R4vn!g)oohdYb zdn26J@k&KEt=kVuZt6f-LTZx04x5VURrFaF#O46Ybfek6*8`Iq71%UDmgvvws@M4Q$@kHG#7z^>=GUl%OI$G@*Me3LS$A*=xn} zZt$P)nDgu>A0 zwRe4i;$ew@LkX++UY_fIwOX8}mN!@L3SqL3m)M$B`)Ei9LaHn?86;(OiCNOS_gRyv z8~}7f5&Xc0skO0j#LdaTw{f0A#3kY04^tD z1(t#4g3(7)ndLgUaI&cfk7=U`?+pR}0j$J~tiM4wjA$HIaQ`mT2s~wIK!lbm86Xfn`?2M;9zlMd;*Ytn{=TjL~*h%y>TfvU}#!O^_ zkAn5J{IMcs5fp^?yNI67Oy^Ve!L=P3s<-$e6vdC`%L%dCNJkZzkOu>ee-Y68z!ma3 z`$T}5WsdzhBcvsmaQC}?u-=}%v%jq8srC;`p+l>aJc-Wf6oj)S-Ikl~%vVjrCz^It z2~2m}UwjMrHWkpCT>v`K3e;$63GBtyE1d@<8i`76FPTbk8up6TbTFln&(!477@wux z(z<^rays$2rU<(Eqq36Y*>Lr8Z+d&nIfz%mjr`}gXizvVF66`lyj>?i$^hl0CV(ux z)PD*2xiC87q4M(6T5JEP#)8Ln1Em@3!{I)fWtL1944nBLJV!RFkVjZFeJ*W{g@r}w zNiv!>W>MPN*=bt*=;#PX-8QO20M=wkC4>V203HCbW9bD`O8T|S?)Or689W$-QOpXA z&vU%Ee-rea*HPJmJ-P~A7Skvi)F#4g^reU|C;&MxaXX&#NJ+k!z^0*AG3W8?g5%og zIG!7fERUcdF^yxE=0voW&@A`QXF*#30DeCB2XOZI&EI4>q6$$(cRg z+38EiTrHtWXW@W)2(2K&qXbN5g+Vwq_#HB9>P=1xW8x}e!%D>CMoGkErhM7D&!Fqm za|T!jGRuHhP|dQ>UHP3x7DH@u7aDUl$N2LxnEqC! zvVBtz?_?7voIy_$PP}@km|Q14%!GEPwG%VVB9;Ww$tvTvRe`D8qz-V>obX)6_#4;tBl4fU37FZeD=r_A_3^eDcl<(fk|u5Zsio3%t?N6U1O z))-nv&(N3{5$>zMN$4F4K`VqENPot8O9!3!4cfWD$_Ri8rW}Bg<+#-FS}} z7YnbZyN74`l=|jP38Gi4HWy^Guby_>f)Ncmp4*(fpYeT=eHwR3j4R-&ShG$p>DB;D z^H3dkOBY0dcW^LVXDp)+D!>Lywbyjvln&0iiyIU)+IvnCF>H*}2;qyu>yk&L+Cl2S zh3#$vj-7DGv(OR8)tsf4u`;VovOBsoQLBrV8O1NE!TaGXIly)Y|KSOb9nzMkcZgLI;aCm_Vv~P^xcF@8>s3or^frE`_SK zNF8dGZNnXk22KSZGw8Dk0<(l57OakX+-fS17Q*Uw8{HfH_1wi&SC4TGF=bh@zJ0=? z@&(>bDO0ur-+0k zoJIf(k@!8bDp9xh*+&QEKiyg>r-fDiUr&S*xj9iXp@HBmpqyFj&t)UkZ(SQDE427W zMG2MUDX5M|M0MUKtxeswr>cC?k`Y4P-X=~m_vQB>&qY5qhdwalSxD{Ot6%PDLy_*+ zR-?5qc(S0;W8`Xo)z$nqCewph7fojNvc|7Q6(W!?+KAhu-C54mV~oWSA%TC@4NuKK z1a03fu%E^h+ z(p2)P=7H(OCTtmX`dAV?O&p)mGoy3sGqc5Jyba*0!xt7D&xlekg_8Uv=mu*_EP*H^ zeZ=l)uG1@a}C@ZNi9` zKf?92An{iFr%?u@p-n$=`rE59BR2(|CW5g_d{Dp&ePjfeMZ2ta*)STW{&6VhV>DuWS8f7 zu1I4io;PIrb$EWIXp{<_8qM1VV2I{b#gF79ne5vNlU6G2GLgoG z`@T%v_phIS@>1|BAFmzoDs=R0Wbi*_NdSNGKG|iDsM4z@?O_ve(@ci6OGVfB$c&el zL*e2$3OwvVQ!7eiaYPoZYY_nxdc+Iiyou53ub>J{1OoE^^-TXe^j}AOtBtJ%>~hD@$$*G9g%=?;J*B~PUX{qi zmPOzZ!*fR0M8$-l&&}tBzuEnI@?Mk*hsdh4#&(e;Ely&07DGbj8r@Y4hNL+(r^wuC z25>FUmHC)VH&=O7!9c&dCZiA+8zLfr21@4|+QYvxk#%8XZLo=)uT z=~dyNF!Xno;+1<=WR|581e-JrV*DhY6?H_UXo?{x4vJ@IteP2s^Y=!1+66k{UuM*H zC=;7MwhST*+uyq@8~mtbfa9Bp_~1IJkVDk^7&)=CRuubwDY0WkE(XL9 zG$^O-Iv*i<&%W)(MHYEg2-9^6b&+|G_T27yjeYabvJVv%MBzH5&tuxxd=Q{9{`w54}$rwJwlL7U_9O-qY4;1`8JOn$;YxXX@h|J z<*FnVP$T+$z|#ju)#c^qSv>A5Yikhx)_bzA+E~f-#;ftUZ!&)6Bej)T4py$+_vDME zI1hrda8hcJoPltxT8vf0;sqUC2NjF&CsBPt{ffL-_cbdyfjKh;@D7j*tD%d@4p zAW7-2sQiv{IGT0I5Q=D7hG)&oLLx6np8{caaTF#+tN7}OKD%F?4(?T38duBIH?Okq z=aWa`A)0}aCT+10JW4OA^Y-z{3y}z!muvPKvsrhcTf>pgjtau=SKsLkn451D zVFr5IOgrX4O#BodgMK=YFz89{a;L&-x7s!LeUlK4X=~H|)>wrKOy8g+!qqrSgd7a4 zV$7x1B4i?`vs?CU@mjImQ~!*^P?o+n`=R>ErcvT_)Iog2>vW;p5shUkS87=lK@x!B ziP?+*XyQ=U_RKcoVx_HhOwIEH?g&f~ZmTJ97jhSs;%AwFWuiW=?-)=ClTvGAu}(>c zd()vHKZ|IO58fKhR5WjfkhgP$`PoMwz9b5JZHHJ7AFmCHq-$ZYe13`~Fek8x*L~sk zP+u}@BGC7d)_ur5)uH+dwHfh)Uoi*uq^uDZDi$3b@W{Rgjp(}LDm~}b*=YO(nZw|4 zfh#WZvbT4PHAif8A`4iuvy*vWhxl_)qeor;9j0^1bpQa8aEj4~RsSAa|D9bRHDDA^ z9}`2hAEge=H2N_zD&!|=-ii|2`VlGR=QKjrmEw=rQ**EjKqvNCV#@-JfL&EMS zUEZ0<8bv$$eMJB9`sp)!%ja=5h)fyW;<$%in2n6U3eg`k7LjM-+tvwXF{g(dsfcqKk;xoe;jN@PI@WIK4`>-mjTiQM!p*zw0^<8)Iw$azyA*!YL1$>@K{H_3kQ&e3;r z^@{EV%^-r@k3B{J!)Yiea87z21*A7>4`Jx0Ac)>udI&TJxYRJd`LBY+D` zq@h#{c*OpHv9kZBzKKcOfEk1Nw0L^pkkVJ`Owlc z;Ke=A%<-t+v);;BvgzEBMs5>Ip_%Td8v&&A1H!a6A7iFFH~H~YpM>rX*iS6*1u7Z! z!Q+{>;?wW>o1IHv-D8!?>d=d$&u@H$d3mCp3|!19l4+h0HF#S1j#PT(U(-)o@ZKjg~G9pf=w}QGTYLKY;&~FNPE|z3e#=@ zd1uGR{$S9;jcE6y)Z6Z>Uw3OgWj6K8UEnYZ6EYxu6^}_ZrKQKQRF9D&xHWqq;vr)2 z`PICqnjG>kq)5Y7U6?5cY%+qD7RSTgng->ctLdxAzOWT6F`-uCp%(F6e4G}UX z>8RkqnT#E;%(of-YS{ZzUiDet2_7i|dj_lt_53o-z~Ak|M&yA2n{b9r2wa2LMT`A_ z7!7t6md0;Vq8L?)NxW3HqGRe(L4sFAHvThZ$rT2pheE)=q6y&kWzPaQT{cd;+}+}{ zCZhnk5uh5XGp9j!OcUP|t)S;Lakotk{4C^svV~>!<;Hw1DFs|Rx!e_DJJL?zz*#Nu z4Gf2fQX{uRzU?_q-OhyZ9n#R9Bh=%S$~H~w6jawJLo=hnbdJV z9rfjIX~fZMv3d%N)T}$neupUk%yNDaIDj+!U+YowP!od6O4&0%CO*!Hz=pE%0at$kT>2_ z(5WK7+wi+~$3M<>!K$+Z&ehf~5>su*l+_@wL!we?&K?c~DH0RNk=?&WKm|@w69c29>aJc_Mt?e$zK8j@Vp4D_xPD3$rQm#XprR>Bs zx;CJISJ!uTml*g;M~&(tc`Es5{*m=W&sL zR)lOutuOFQzT8N~T5|`U>V84Q>w|MR&Askbi`;!8 z>fc_i%d_?6<7ang6_MU1TuPeP($n-MLA`J_M4r?7K%%TJ=N|!WV zK2TthHhakg^Ld-~DC^NOwr6+rotWOW?7Th8Q0}u;&ddQ3?ytYW_UpfBL-D$axc9@O zqa8v2zr67)YJPsc`^8~Dmqoq5GC|?9?`krk_+nC_wl4yXW3uE-T-}+XBHEEr^uRu* zJN0#i-(X0C$j}mWCF+m%221wp!Mfsfcb(wZQK+P2bkEXRt^WrGCZE)@cs@<01gCkc z`*FTO(_EvzB`x#aRxOHuy`8;hz1zcc>Wcx)GI%h6X&!?>BpF;cy{u};Tm*#Leg$ge zr%qk6l%>acCV9k?CNDMRJc(XJypid709Brzp{{^kXXHp2)MSQJXl7RuXNh?q--$!m z`rl*+V@zw!*{l9~_E|U_*7L(_Xcg=KG;4Sve%nQjxEs+(Jh`9fr#=o5jBe^NZ@PR>PXFUVg>74o_HDmJE(D&v7<0VNI3naZ zfg!0Y(O^oeiBBYT)lB?GvqY+Jc+a;kiC-G~gXqE5#)FLRBuXv=+7}6n3#6edrA_JU zSz7u4hff)tn>G^rK#NF=wEgL7GKx+lc4vJgaN0yw6EtP837->4wmDk|iFU>kCD}lb-JaGCcgE7@x%l6TQ1lA6 zc5;0!Yfsszx01s0_DpA0=m?8MgJm=I>7|5qsrfr@sWx$v?%ql3KdpB+>I#nu3maP! zRH~?%GLu?LIH4GTP}H+UI|-g|Fj4Jr=&UP51Q+k8j5A53N=T$hKhrx4Yr}Q7Uqp2% z8BeS$&Hyp!J`KK z%7uRCXZG*H0ciy+(`CjW9-*H{5zey610tv~$*h*=B$`&tFw?tbD~Q>=k+>3!lbc>u zDrU%9u_$lj74>%K4$sYgMGEq@gg<#^RZxG$^u z0|f=D8_3OOLv|V4ep&oi4)IVfy&H`!7V+i@aedI^HohYc+ltrW_#{9b$n~-&cV&h@ zIbDRj2O|^^{PMc!VV}H@iH9UyyVv9Use9p${E>-e&DWaXo{(DX=9!^uY1f*I*D-gu zZfiXOlGny*gU_9s&&=nK+x};j!F;NKiFAWYV|5TV_*v&uHNRrcandS3tWOT>ksOUz z#FK%+vE%w*2e&RT?aabqp{Ob8MtaC01Pcq<-8ZO+80I2C^t_b(3IWG$d{rvHMc=WR z^4~f7CWVm&?s&VA>tq0+{BXOdTB+lNQ|k17y5zS5^=YBzuB=~?O$GvK{`RTc4 zH4yO7WsrV_Sasn{df#>9Q_ZIw%pxopG=ni^(=zbEZlTPm-@_i19bB zILb7gJfcuty~4@nIteWi7B>e*2t1!yLJ^~NC;)C*f|NR;6S&o6h1Sv!_1%k)Tbs^9 zaMrDQ5D};C4CQBz&t=h7QZ{s&=_ow^o4{(~g%hU>t7a>;cH13TfLGejM_-9ba2}3< zi3}6+VSd4x$J>v$VfK=DAN4RB6xzw9a}eP%vglTHTW1?&1z1fC$91lwsM+4oB6=_ugfL4OqHzlog~ ziS%r2$ZKgq`)_V;47QDm^VEBaYcph)xj_X0r0lfS9BdC$gyS~m579$e-S~G=SFj$E zS3EVk9N(`^hNpH#Kw1{&1RoR;#^TrDeq&rFz7=Wepx)Uj9zJa;(36YBA(i2&fwUd>eVGe-9=jPGyhRek*neF>el4_E zuBPA-*voayi&vrlJw`7JL0=)<4i&s#V`YIvPIS5ZN>KC{CMTdeKj|<;3}ZZ zaCc%-gxd<#c^Rp+Ms#Zc!&-tTC->WF3*3=c1EB%$|l1UA%skpls4af{+$elR_xw99mN7ufK3v0Bxa(?!mH ze!s)-aaTH->aP4V{TmtU4rkXoaSM(&A-zvcz#5t5?T?5^j8**%>Ex(w?b=C}-5+ZW zzCam+rOSb}o-rs1z95))r+rezf*P2UaM!b@wIOp=UhjPKU@ zFH^sYv_Na_Fx%Igif=Z58psB3Ilgvopcv|WprdUPX;_BZijJSNh+?$p;S#2%-=_)dF+M-YUI*AZ`~$EeQuyHUiEJzLYwkgcvE-e90AAO< zaQxV7S0J9eYO^rRb(_4MHIUt*Fo}ktt&tB!H6zv`_>S$lY@hE=4XJZ_d>z5 zEdmkE&#OEUUkPmt=?7;!kDM&RIM2Lx*PO46ZJLVe(eAHaA4zZ^!@PYrwVeur+BysT z|LQXG88TNvv4Y^ie9sm1w#mP-)&KF&;;+u8&{hx%q##sX-c1&sYpn27=|g$_02E=+ z8?BV}9IhMA^Yfv}3+LU!i|VKg=cd4CS_OAwY{fPUJaH3tX8J3R-OU4w-krJ#Es)U0 zL*#cO3~Xi>Q(9`|6|=e~QNx1*DYB-!FJ8O#pPI2d>f0-H_`j)k6(|8a8b%iRD(C9V z`-)84Bp~)~Ey8H~Pp_o9S?a`JlGiQzrU<+(oBvJ|W?pvy`>nGgZR;3q$Lhal^`X|R zQMG02g@1HxViF-OAkdH^D}E!ab&ulQO}g=3bBEjTcxHAkl3D-^%^Ta8Hwh79{NycY z)S1v4z%Y1%JggVz?CI|E7Hb(5&+0r+REB4k;g>G>uxb%8^Fk5hZ*X_hS0zO#&O1e= zPLELB{sBn~8Gcz5$8g5sv;LiuE~$oGW45q{N4FvGI6!C&d7rlZ*FB|G@)sX$S8LMi zS*Ayr#C%|B%Mc&~nUGxM9?R^?hM_{Sph_Utm1vbG`9BxZ|4K9ei8O*}x8)BBZJkpj zVZIz6o#h?^vyP66Ih_9T$FIn{ySh!|$NoYxWW_W&e74jU3}Ap_2_R=tWy|(7OI+y+ zjof|5s+$9hBa$cLR-enf?s#9;Q(#a`f&y$j^kXpNW~l%ujK`hZ%Ml2HZ3*Pl)Sdx$ z@4YL|L`S*%M|n0mZYD0G4~=czIx=G!w);Y>=Yaj0ZN~upTF}HhV031JFCHB8Q`uMa zAAq#@#}i3BebLyc;ZOF5)P=|C3!;jrw`qNM26EpAgzm%2LG{mpS)hzhEjmNv*t9H-r6}~#3pv~NxSfs^78C>xDg|nP2 z*E}E{L^px}3dgrg5JmurAZKyqz41Saqy2xC~T z)kI~tHX$Z`&)MTRf8yV}El6qLkXiy3(D^r-zP0~>QDfc^gUTK#GD4I87I?$;%8GDO zwE{N*Vh^b+o`PfqW?w?UJo%*SgarIgQ9qFAO(tA&ITXeV<%5u>p-@K(V~rH%J*~P~ zPVY7?gwu`>@4x$;8q?a+Gbmx?Z0mA4dTgMb=TYw#Aq1G+#kaD1gyru_x=60l9EpA& z5XV-Dmq7i#1NdX%@Kgva9SRH_J zfIY@KoiWUeB58TQl|1AfBxGo!Et3V<{Fo(L2GRR{iXJC6<{mE5UW^jB*5YDf?!rI8 zt3`K$pf+l39^+`D=nKo44zLI1*n<@Th0D!zFubK8h=;j~hoLm{Q%1F{UYptDUL)5% zcgK1KR|MztM#Vw;u-=~!UKNOX@=I7P@oxw@=TN%}z4o6@&FFgqo0_Y=Z!6%A`p!ho z%F<2^Rdtco3|{&ot${*<0d=V_6PXEQ|^u`~Y$% z1^qL(>*<8)f`lNLy@r&a^8T?mq*mfb+;KT5v+PuT924c#avnfca`hyygMlT3o+p7h zb`k6T4D>Sdm9D{SZ?&@a03p#AZ2pXMx!t~^BA1#OC$73HF-bKm+o>iZgN?aA13I2& zo&U-f^uL@NpQ#D@xoVDhqx4S1BGaK-D;=tm?yjHVOEj) zUq1!!ivDD)sh@|nZfG3PbXiSDCd_0JN8FD;MZFm*2nuvhM7!#R-O&p&&a+O<gDixu4?;yJWfgq#kj$EWJitO{dL?X_^Q>g~9IEly1E~a@K0t*fZq_ zNGT{+?y;~U$Iw`IJqU|Jqw0m37X9>+?NSr~;W->*jWvzYl`IRflPV=_n-G&^#GA4i zBeSr$#X=(H5E*o{SW1nS#f|{^*O|NRqE8>sZLuvL-m~vn!vo?bK(AlFQj$<~V914M z7M3x;%{ZS8=)C&%z@yv6K#ah)txBQf)CLs1`N+A=w0S$J6W_oX)3Suq%*Mu^Osj3I zFqojobeT%Y$+Dn??e;~M3fvC43*&ihedZ4y&Q^x_ZrMC&ti{u)i8XzJc%MjAe-mb= z<(GQ*FYH*-7%q3?$3K9Ak7&HL)}F|ndLWWzL3!rW6-;3SEiu51gis3#{GcC>GCq2w z_1bkv-7Ti=`>2;8lB9F+`RJj{`B*cJF(o14JFAd`sXaAGv-!*Bi(4vBbH~AqfE%?x zO2Kc9r!T@dyKX}(l(xn@;4jgqvnzZTdhTtkW^8}QzqR*T=&qnKgc5~$V^sYtei?n* z?{-(gaL_BBi?^7y2a@rtZ=aPr zS762+Z&jUomYZ|Hna6+Yv+ci|Kci;fc;C`(Eb8jfg?a7C>&mMUMJz&UMB>}{?XGop z80U#$wHU_AJk;D-X40K|;o8bl<(K{3o}s>0zGoyf;^#AUk=i9KgFK!Vo4=pi(w6|1W}{pl!F z2pKA4gqwB&-KJz3BLOMiGUhUqAou8%k6QXYV5ZbwAUa0!q&G8<@pFFOZ%Y>DXHN@+ zbG|1z8tcmT&}o^<`?rjP$-r<7UdY$sFADGpA!>T^$n*&CIu=egz0&y1#FXRVezpD; zjF?Y{^C1C=u0tORrbrpy;LGYxoi)%*l6gDNgJIgz4^OYx;!_F%(TCWaHrGfO_ z8X@8{*eSOK=?JD-;1ut1y{*xl#+Lx>iQ%dN+cfn8pdAu&G66@~)9^jQsKD*Le8z4#MT+)QUGal-C5>5u z&saw$CJbSODK|ot0*dPLSiP57E@GO=Axk{Ou+I=v17U|f)<`Gkdn!zWFa{4d3SA%Wd$dP$BG|B-UwoqvGd8z=E4M=S@%A zcikrwIvKksEt9IPgf_&j?uSMR>t^~XHR+M-!cS99$Wd5IZx@S2hbg?UKCn(+;^I0L#7LZ^N|s9Idpcc6LPPUTFZeysn+fvY@DK6dH6(sNa&5kdpnTYt z)sY|{Sh~l24&R3_g>MV!Q@h+x^60+T^Vpn&e>JJ<`KH_kqy-tF2R=c;sv_jb zphaPA)Xkx$Ya~ri4%Vx+qUDzSj8j1Ua8g(G$#RmOK`*OzS~Z_jpW|;a%i^lC1b2)l z`2xvLRH3NKO;(JzRtAJ_tNc+i3D_GdLromz*!*4UkHye7SflL+IRUJ&21@bP`oTVG zHQOxNx-Ex6D@~(ztnEgxBdn|wmw@jmN`;rD0qFvxAWsK_r4~4$>$k(>2wtdxhB#(H zAF5K`l4{Un7w8X@GJANBH>Sf6pTJYkU+auGiP)}d1Wj@MDg~%KPu38!i>&SL5fxW- zY6CH3$N{g)u}{ zBYCc0JWm2_^y5(iDtWx1URGri-z{75IWqbNq{8v8o0DbIq3NJU=u39YT$kcW2@w3% zm^UclfX({3u)#QABsOO>2+m+uxUIuE$*Wo=8Nxj^x5MwV${QNlUgR^JaQf$h0|!{F zwG>$aw52!QQ^L=7oWA&#(J9)S@<|KcC`}?1RS;~nApCqZYqc$s0V+gHQq$dLcRY7P zIov99R9fB`IMs!a&(;E;rA7xtb-q%!3&PCig;qdJljd*I@qJ>Yzr9gx%6 zKBJKR8Q!nC;%7@vtPQvm&)~L|j2Uz8LR5F%luWJm+1%3mdPm?}5|Od>QV6Y9kWLQk z&`>U+NqZJ3cQ#MHrzLND>y5*(ThKONQ+kZLAIOnF*J9FU6p318=}h{>5ue{KUaK$A zd^D!b+gB-8p1&V({fgVU?~=Rimwk@2A@|XPi@3HTbvp&6aXE*;LQjKNV^u~ZSuMS8J^lfZzP&Qr47yIpsoY;#4!mXG`Iw{b0-~U82$2mpKWrG^ zKuE?Zoo9Edy=I{j-=s{$zpqAT(E&uF6T*RK%(2rZ|3B#grqaZ4_EF%LuTHn%Q@Yw} z6Ijhl#ZCRCsD7`-%lJ~VvjN;?y$0wet5SWwTbF*k4R43^-_<_;J6a*05J2_8f9|LB z4U1y380wq%1-dQ$zDR1h;DZR=colZ}n0aHvs`uPp)jmxfq|7uV?Mn9bm-tw5-coY< zCx0S_0dySj$>p(l)TW1RBc)T(xpM%(X{?1p-h!&a(5w^Q%&lahpSNx9>qncW(C^VO zg;Wr2TeyrXeulpd`Hj@N>utCOR;X`t6PDqQ?gp4i*) zei)0+?Kr9B%h*`{#L9}Wcm3nr7_kNgtAjXXKgPm){`e?;X*R7iGqY=SS4e=@0${1E923CrY zG?bsVrcG3@E52YNWcV$tQugR`BJp$Um1#{BX8xaLli(AEnIV$Z*XktGQ#=+%7@p-4TTpaz3OE~>S1 ziVF{56?e2fF2_Cfx9s1Bv{U898V{z85eWQ*AytJ*`kO@M7HqDlmZWm`<#NYts4%J~ zRfHxExwF`RBVx2Hs5Cj|!w^=M`fRM@kP9&}L>E45`c5EE=>JIcbl$eQ;9_=|z$TnQ z2YZE803QkA(P3noFLZ-kHA>-3C>_)n9{~zrzV^`&sHzWdz8JfF^OWIU6^kwmX6K@c zAKA3q*a+!@zoZ6Xt-6>$bhhk;*sV471TPNR&x=(*R)Uq{-tbatCHquUz;)I&@lQ2v zrO}cLad_MF4M>B+fa97M)03lWk&f=H%oNbG;n`wf-sOl0CD&wJMwCU#KL98>C|OQN zfS~d@bN;N3iP_|u_-)sqe_Z)YbAw`c)1sc!lC4aZ7gwiiN1?w@3^~;G4iv^wO`n@M z>-2srHp^%qO7z$%YDhSD;{rws1F5a^MST{Tk1zqZ>8NB(L@*9w!;E(yAy@WTOT+ST zlsQ~J$5%t*t4aqhNCPXm($NF*M<#*>=yoCg8tsI2nduWFd?inDj(Sb+(yM5tH)lDb z9^j5w1dzu=FF9}!(THpCCCq$g_YDOx`-t|ql5{&FE~aBp_1y2(G|KxrsP#6&@Wj}V za`}b*%nex(%U7Jr<7_*#G^o)=8Bavr`S|bZjgXwM^s~aYwR~$L3BO*yzft^F&RfOwr96COSl{!Ob4vzrmR^RTAI8naMS+&3jSjv4z2K8v}fV*$3E!;M0C$>bNhR$ z6%rh!1gpmiIH)N#Ml3z)J&8x3%9I~iymptiJS7p0aPt3VWxk9!Qu6aho3h#-;C#yz zV3iB{(K!tJrs3)38p{1NnQKMH=mT%jc%%5aqR#DL@6;|_T=8}gI)pD)jo`C;nC_1#X>ZK*k>OK%Buvh^MZ~XO{WW;yDD~@A`N-yK zQL&zr@z%SBEZf}Q-)u`>b*sl;*Y(ox$+o_m>6#qwZp}V^)~mGd=BAf@k|*6#{%rOc z#u&l)?H@q1l?;+7x8ZBMk9lAEumjGry4;em9W2(Uspvo|%aqw@vJGq8Qpc?6O>M+g z9#~3FVisjqzB=7Qy9clN`;69~e_#3s;PLm-^=e1;?B(4%g@3)Gv$v{y|6B^@AijFC zn1ArzJXdKX>65Z595C-ghmf`OpWcMx3iL#MrAC7?P3o#N@aiCgjT=<;;8(^?$-j-j z|4%RXd6Q#6e+#l7+j!e5E+Gk@JkoV6f6v`f4HiC)rqyk~(_m;;8Y)uyF@8m2?xDus zL_~eBNNr3s&oAuLx|bA@y#o>LPI5GluWW&ArzodZ5dql!0nq6o@~T$7~}{4^kMd4Jk;68Zsoi@A&?ms2=$~A^!R8hkW&& z#5%suGP?MD^s$}t0c1}`poo|>!OZfqN=$KVb6z1~u)e`;=O(#?YD_kl`T zmOF8OiyS)_Q4FyBm}jnr40@*ubk8^?rfth1X6Ii|n?KBiKG7P_Y6#eSvR&&aqC4w! z6weE>sv+O1OKW6G*QB{#%r=Ru=QPefq53Rx*P+E6{7UAk7I8j!>N9&ey*3|H>R=L+8X$_6FtGl_7fIELU_ zO{^xiUMDkE*QBh72|~lSckgpfSy)C0{m|7Nk0S|+(L}2c-JaS4*@P5d5RTvniTVz) zvnDNYc!VIB+7^#VRvOXy09x=3@pBAv?tX99eFtwaSwysi{R5CILA3968~6_Y(19kP zuHzY3Ag`0kk<}DByqaXAGWS5rTVCb?z$I38@o0LkiPclLzNzPgBAlxawZkFp&6Marimkn5S#QU!l#Gr8zpHkbZdHN{Gw4z4%LWu3~C{@pl+RXeV zo}_6RcMN*R4b4RRbkG~62i}5g1J7?r(JVMM$97K}$wGd*cAwt`WnfCe6`Jbw{poa* zCCUUi_@Vj`B=Jr)k9Bs5`|hZ9Fyiu;k3k zeIGO!?MQJzSb_aDmevp9m!msg$r^yom`M_gyW%UKO;CP}s(>RVmdvu_PfToLsXoQ3 zE~=R&g6=Rfoh-&hNaGLuzQ1U?*)gkP4&P+s5uaHs`REP|`%>&r4TUxMWu>Ws8yV}0 zh^h-63dG!D#7bS|q8TwAg>Q=z+i(Tc!ib6ISC1$?yr|e|**>&%i=OMDpRI`U{dA|m zGz@Uk`jIwBfJ8$K?LI16i}b$$qZF%Cz`reMEWf87qu!|{s5pG*8V6BPaW`Ro+2yJdac0gbl?uzxQ5n+W;s<3wa#-ucpAXQc^Y*IxBA%#5zItiY>tf4@z ztwoI-pjvHK6J3N{`1~XKIUK9#%9**%Zd~~5Jrl{017KBJ=X01kYBwd3lYIAvl7=Al zr0*^6E5v_s{OyNfZ^jpKC_%BRZFebs>oUKB7jF^`iG_P$ z2-94YPCN=kDDaTj+5O6|(4N+t!h;!@i`us8T+C?_dpH@w+YahO&4h{Abk8424?is$ zYdVXy(}ZTStpfx#Lrn0zBXg@Z9ZH?tEsYG1E*+lWop6|lATWR)@@!E2iQ8|W=98*_ zJDNqN6N5jrQAB6dBvDWeM>6n5=($IDp6MJVQa(=poY|#xml+~eMl4s&UTFkz*lpx! zUbIfXdf?u8ID}&pl6MZ?;`p@s)Bl>xz>bPq9=j)PeG(h|?0aux<=*xj=HQic&io}_ zx(yD!?pm!_(=(f4HAK8ZB40IkGrNax}Z7QaeL-nM}1$EVIfIuQJd!$_cZNLrd zhB_@~Yrm^Q^~VnMPlv zcl*|rkEm2$bgdp9AD<*oqQAeH33XKyADOk49__C76Kc-Szj@aC{_hYGhV{!$+1=s= z)n{dh@kr}&k29~MnD(NTGf#;;-9AmYPr~{}dehs78V8I&)bT}4F1M_Wzf3Nk$?o_$ z=5(7H2KnLPwvReCo{=0}KeNiIIm)&D|44hwsJ8m;T{JiZE$$jz3lxVY6b%-n6bMeS zLXhIc-HH=j(&APq?ohNvQ`{*~yih1bS_(bcd!IY*f8YClIAffA$jHaFGS>RdIiLB6 z<8067*y;gn8wy<12_HQE#AwE^1c{B?e^H8=B*Yo?iztOZ5#fp2_t9l0=7vl zT({_qt@XWtW5zFAn>|%zEa@YZ~fwIk&)Z9@FK_x zXWg>?a?w2eIBXI+BEs0}%22ubULm6H8*!k=@u6vl%i6Rw2Pj<0Cr|sZ!t?TJbYD!T z9RjL0vNLSY!9~)UUKJ({-C-P!X)%A>_tj&!@&5SF`mz0J$3=%>xzf!}@lkE3+Qo`{ z__Ju5GO2WhBl!c4{~;at&-h8KG%DgoDNh4wYxP54!91n278v3sX7JW`cTc%Gg1g|D zAgG2K*heR+vZyzTPrqXi)kc6Hmg}p1FEF1}qi-)bsbb>?!N9`VpOg~RttDARf3uog z7ES+BCXu>q%R2pR?U!R;<%FFnm%jd4Fr7nI*qjoy$NvB~l}-0Q7sJu|e)K`q>8cvy zB3`*U9lv^ZAq}D`KjP`i@j_GYXqbrW_DM4xL*_>mBG6;F$=T=9Ueg$6T^MXhO)?_t zU>vjLQKe;UGN#VIzXjn;hhhv|_+HtYrD(5u7g>2PRs5*n<2w@9!7ZY@?(7q~!wz@p z3qzG}_mQ5Uko|Ymzbl0ff2w0r$Y_JZ-;;0aZq$Mjjkn}-fkt70KY@%_3B;F}2Lrc1 zkFfh0r7C8hha8Lz#$!CfBz9+B#2WVd0&)L+A0HN_odhmnkAMhsGAl+B^HgPTg#$5@ zIgBvxp*Cv+a{xM^+rU^uQ}O*r^eZH{xtAvD6F*g!qBjEu0UzU26qjU{uM`uP+X{ zxCSt&x-&$jz3SUj?C=-{oBw$cy~+neD)!pA=uG4MWo_$H4az6lRixdoma`l`?D^bnLsE{i7U zjqD4GtalgbWazWqJK4`~S|QFtpm(A*?Hh+X$0*3(795+QoO53&Xx1*2l)T_W{mPix zzkIf;cNY8L-e4CIE%p5iAAfuOV4xGX$75BcYGS$I2U`%j7GkJ}`T)jJ3ar5!KS4qc zQyK&Q2aOS0CZI`#zYx3QS|i8oCwblG1B=l|jT5q_)n*zun3Rj{BVyiP>MB}C?Q z{N<#%{U7PT)289{;{w4u@xK6(1hTw?K>Ow8_17&O9Kg=u^!&vFZPx0j*7z`MP!h>N zX1kcnpHF{Kf7~A@{&B3Dy%0NCjgh#>KDTh2T-kJ04HFJ4M~9~A z(g@mhCjp|2@5!y~n#XzojrW2vPY;TLvjQWs2Q`Zjn&=?u#)w0^GouG4S!{bRHri^m z#Bh%?mchf~WmpPM)E1rSf-y;oRh22u%LFxgRuS(0GPihK9+C{^c6~c$E+>&N!)N|x z@J=Ugk?y6jXV_pEPIuAN`?x&G2AeL%E+5&D%YNta0SjSj`*l3Zm*+(uE=87RqeJr7 zEOUTZ3d+(jLTEzRWuab!KN*eL(lzLck;%JACf%ZS=eowKpQa7h?9<#?9=XbchXXR` zS8BE@YMBhriS{849zWkqh%C31V$c{cJH{kPG685g^KJWVROjTaQH^S0Kvw+Mz%KI2 zAE|XII!1J)kq1q#a;orzexZET62bMJz?VI%r1ktT?J%Q~L6tK7TnRuV1iec4b-F=@ z_?xBOwE50rl1tV$Q;R_aX0eE#>&N02G)u2CN&;iGovlfeeyD{Ho^=tsFiCm2Ewwod zOT~k7pkQoG-l05v|17Z>O4v$R0?_zT^TQnOmw^ruX$iIhLFrE+B(dg*x$fBnWi-aJ zkq4;p1%t5hP~X)|cDMERw+h~sL=okDI|d!7L|M$2w7TKSVG(PIWCOzl+EFC z)+93Pb@fS1fqlieb$iSLMv+z%2Teqz<43)b=!XSjhb3`FYW}>4aHF0Q|HMbE0Ze{Q zLC!YJ1yjY3UXdq}cJdIMU}9vbb6*k`${dSIqD@8FfCs`c1^NeSm!;;Q#JSauLW{_K z`dg7H=|;m!qO)!gs*@8gX5f=ni*4Nx*W@k4(Mt4@c~@EF3I4PPq{`RFV0kJ>GDVU^ zGM~o#S@o$&6CGq+mLX{Wzktk`@%p#gOeK@){SUPt-sm;eF+Lx;=zQWV zUKOE0-Xd_pC$zCB=#@sUpRoJr|{GQ=ES+$68fma&nx+suJ|gl-sDA8dEeXm zpq#XG{}nm!6WdVnjtU3tBxO9cT2($+LxG1I-$z$5RS0)!a-$x5`Oz%AaIYi{N67iS zCA0sTr@0|lobRyO@`ANgtF9_H`xH!FbXZ)zQb=B+)!kMW@z8j{IA&<=Bi0KXgVG@$ zpSZO0_hopKL};~U#y}(hCwy)?c5%JZ74Acjr`5?kC>F^{4kXW8SNifS zP<~cvY3ur(cpJ;GWv`}Fdg}V8P1Fkl6OOsaF-U}3>7$~57=bvX3R^Pa?F5+pE^qfx zFn$CnX_b0s1S0x7Bkqw}Or+1xXU(g1NxmyvBL*9^JBCrfI60Od< z+RcF<;wotC%1_GjCNZpxdpHuQ!WXS_#c)<7)GcCSAHAU8GuE(P(S|ry_oLIkT=rp2 zr@4%r@OWejwW041a0K>Yb?s3CM{#R|N~fvs2%tpVsAMCeG-^D25q4oQRs4!WM?0n= zp|y@DcCj2&kvX0d9CRe>*4H29+m!Q-Bh+oECRiXR0JKwqA!)~e=*FPCLF%zUw7obX zCxm5)BG3mjB&B~|ERq1vQZ~_PQ?Wcx;u91=XqYNDvkzmTw!khEXo39j^YkDm>@zDI zR!P>1Rwtf@#J*!jzt%uVinnPL^5>`MZ})(ig?!)HT))@cP%>&h zb_WhY!ttsHAhqupj&f7QL1%BxuSNCQwI5U3JzYV60e-uoj~A!6f@y;_(Z4J#+uRXN zW?ko)oRosUfUQSS-&n`3EIJoHd55;Hy8W{B{cfeTV4Re`hGbBInrn4F7!_A@(sg68 ziofg>w_iNkn#ovsu@P$3+Shq=QSZx|Nb;kpVrE?NcDLhk-^J#6i4fJt3|DWz z!jfxQ;cU$5{W6_Pr-w&66C^6Vj2cOaLh2bsP==D8PgM-`_*q`|FpvBGI^W)uU%3C% z`+cx8q-NH8U#~v1F}UNN%g|x&3t-92Gyr_n; zKd*|6$k4-}GOL~I-k@XPjiJ*35W7H+8vD2^vNV%IhVj?(`eKlyYfyhJ3dN_C6CiS8 zweAPW7xg|~c+oLfmrQxch@sRTHFaMD6RBANPo`cbh={EH<@2>eS3HfAillCAAzZ+FrdIIMK6hXO%f+9p`V? zbXvtkGmjdT?g~uMIDFK^1yFb3Lm1n4uO2qu_FA3LPTI;pd^!J)eI?wdXZvXu)?9>= zdx25ol=1O0l|E(%csUMS32(h&C2h4GpSar`sP%j-weekA{?=h_eLp;3#3_f03Mcx7 z$F#wB;f}>|HN~M1yeWCxp0^_}j6FSB-V%X4Di6LrW*mRCyd^LhA&WjtQalv-US1^+IbXF|>TK+FU!qhuCdc{4=Dw?KLD&8mt@Lz3?{cH;16(Vv-4^>Z0qfN0&tymYYjuu?!<>|X#!Xc(v&`| z@OF6}zLTr&N2T~KxzjA{IZ6AaN${&@?qOUGxYpV3i@hM1(0{jA5u#27p82@#Ff88)XwDD zCwyCnNJ;J&+_I?O<>5~`R3cd=0X&ivj(ezU-2wGrd}5ojPp?Zas9Es7+I=1m)M=yd zo!yX&n3`V375A!?Nvw$|ePhE_T^fVFVJ{NUCbO33@V8X7Zs?NlQ`G#Kz7;v$e0C;D zT0C%`UjQAsY1+$`NPPW{EeMSphfg?Hs4`{F6=YR&&2pZ#*gpg~u$ zcYWtUy~gl^pMChOK^DQLI&e{+?MZirob}Swgo}b0!JA~qm z?`+Z?{8rldCM^?Xz+WDF2a_P&*!C^m zI|t`Oi+KVr?0I%T8b8}i9kZMxDO{nyhU!&rjB|}2PODmW64nZC^<>g%u|=TVlY;I!Cd)$`M1mz$6o!WahZ$i)>h=r$+^4 z*0OePx{+>JJis}Jaer>Q(M{d5h)Qs;i2s}1C|$>(2(1+&JKMD_75Xx)os5%L9IBE; z$bKkC#k-v^e(wE*Vvq$(fFH?^EhWYNG$ zgE<{hTXSQx+DR517?sRxSOrSg6xYOj@kHp3x{W;@b3zL-g!n)N76`0uz}vP+-!@?==t-rY5tczXLABzVfR#>9lwr zL7g5;QD?ACPF?9maPa`6RRDE4(9Y5xcj@K!0_#`}Dm=DcPm0E50CK*;(5cECBMUQg zvy}$45eB7|5L{1Om>uLhkf@f5#-b~XMg``2S2Qv(U_`S6@pPW+UGn4!2g{-Z!HHow z7%xNzRHb)S1c{g3DVnmel><%T!v(WzdLqGGDYM8pj1b!JsTgQW;ww#?Htg5)L{;0i z59SosWT{3;jaQ8|*r?p9kf}JcCy<6*2-?gyeu-xPfO5NyZl)w+j>d*xxWB@ovMNVaxI&hl>K%PPFV zz3+L-qfR@z7I#T=`5v{yOUN_RW;eu8)Peb2!6$&+kFS(#WIPdczz@vL*Q-cSJ2O09 zV~$9lGw||PCEci}UGyq<7LfFEt}IFr#x-O5$0$j!l2ik=m{T@uEEG^fY|tWLFlVo2 zDqdF8o%>jt5LK~hj;uU}&||i$^k`}Z4m^yebq)=e@*@y1(9|u^M71bEGYe#+g^7rO z0nX?s7nDLgS2lngCljr{L!S=U-Fk~{z=?-vbDX|?iOOHT%v3;klqakK8H02Lw<=zuJvKr=W(6|J9&_bZ*ns5LoAnL0PfvNb@S}@kMN%n`| zl^F6w2szukh{?!T{HR=%-RsuqC80`92sC5OL8%F1!4r<*?Z!%*MhV7rA8_Mb^Vz#f zcqM@FBb#>qQlsAj>qQAZAjTJ;)jDW; z3b6ABJmnS;5r*+i^)lUM zOMn40R09aDh?wQiK}UlQ#T0u&k`C4_*&dh87n*K0piM^UTl<;=h3DT-q$`Q-Wvr>s zxg=Iw5e?^z2q&yEFe6lnU5grxWFj}gyUwV=XiU%!ZG+qIc~_ZK<#5#QJEX6@za?KA zdKr*07WvHfMuaUHF0e?^1|6b^Wp{M5Gpb2L`_V6`;`fcb5+6pGPe-=rFJ#tHl;O&x z)icOyU_VNIeukP!S`pi7uP$PJw)!C5>TX zSg3(8)KAI`_F>#)>g>!@|A!y1(C~)s+OMq689U%#AIQo+oVT2zjzig5Q{}`z_$Kd{ ztheZ!z^)zP>FB^|19Jd$#1Zu1(ThQBKb z=Z*iW{pWD5{kxan#j8^ZQQoW@GIIBqHRI--ljL=(s&kD6Gj`!giqr@4cy=Q729xlu z=NS`n!B@g?Q46J*bSgzVsxPv?yIhLuj0=85{m41EMFkgL+?B&kvbelI`jPb0cMx^< z=6>A%DPInPm<_SE!dggT&OiQAoh8t|b)QXMvOpAVY?F4q{DoEH^4#sD4i3O=odKn$ z5{PTgVcZP2*Ao~d#sn}wf{1)vHmvrawdxe7En%s*1h-0xoC@PZrJG3o9SG^#MuglIo>6zx!sA@cn;y ze?X$(Y%d;xrC&x&U5>#(GUy!zY3zshEN_+yD>rynDSQ{MCik_fnHF;4TJ~bP`bfR* z=R~rXAOPSc10JXh93jb$4uHffYo_yYOTnGrpTw^)kybC8>;I9a8MN4hn>VUG7hsPd z!5EKX$`W-Is5F9znoYkuztgYraNkB(YPW=zevkg3dAK&;o1fo{k3XRKlbNZ9uKDk1 zj-jz1jvTH3zU0Ie+b{j6S}J%x?8W0c`1PX=gKlC5wXN;HIgK*%r{J8FAW2 z!OA-LE2!%ykP~b@If`_Lh~j3GssM-iGABieOBm!ogD{7mN51dZqQ+)wlJwttPAGjr z&Bc^xe7vvG6#DEKa78GV9knY-n0k;}hEv;*ngnq0itW_G9M&Lc29yyYqw^-@ixqAm zF4}f`o`AC*{e0}A6iId}$$<7-OxqhuLLMX)yf|9*3vO-`>@$72=zV0udNl@2u7Na{eP%$EvK}4LwL=dJoPzCfK>b-s|S;5dsuOD63R3HlMLld_>&-H33~6b2n@sCr)8I8>ax4|gT}e%N8I^GXY0o8vXAey{{nauNVmS8hrx-3v|iBG zE)x4qFj1(f0HSLOn1?lX%XQ`Q?%Dp-1sT@7S|^X5rq{d>-A9ZwoOG=6Sl$PAPd~WZ z{Ka;o2lbZw3!v%sYTKO((tJ2}dvpy?Y29~E+-su=We#=ze|c~J{`FK2eqScgPL32&wNYO;DyK<%2N&eA|W-u!?l3|S%F2!<*xRK+WHeBUD898pbL9Ja%6V7Qo>M=WQI zEEVQ`0%n~Z2!C`L1!I5q5s1IIaM0cS3geIv5zr#_9t1UFKSO;As3F|hM47d?H@pDD0To+eo zs95^4+nQs`zUp%9i9lJHobf{+8{2Gik2;rv_?Nnf;0C2NC#u^9f!Vd2LM5iZfF_I; z&CbMHWt-bYQtg>?bI$%U_|89Kj+zD0h97D4;a4St5US{{220c=z9b9RSMJ7~EB=}F zkp&a09_JX>yTtfD(wZ9Yny4yLc%5uGe`eM4SZOr89Lx#+IrIl2ZX;Lu1_H3Ddrz(Xrzf}hc)b`&xp!IX zGWvzi)=|A3Zqt-~9Tx_rmx*=UEqv|eqo$@B%3fII=j?}BINCN#S(EFHA_#ZYa~=&1 z_6oyc9>Sdc(G(zQF8ba2GS>@a)3}LxQ3O^R)=(s%Xttl65$K-XQn+#=#dAknFEF3| z5Z~ONJqx`(+@Wmr4hu?J8|K3SOvaB)`X^md;rI*R^@UWh0lGAP3j{Mvot>`X!_5HS zuac2g${fzU0GynoUeSP(Z6nM7#QwH-wDn!tv3@wb+!TWl2sN}2&YC%vt|ah{_z@@H zQre!H+}6v_pzKv!Gk++TQGv`}AFPj_X1U9+uQ)Ak<*sq`HCuNY6;1#Ba%EL9v-!Xv zqfqw)sZ0bd*Ha%o<@jd_hXiNaLSf zO?*RQ^J{Oo#Ha=f2_9NBB8uTE4>Hdr36Go}?L$qt5Y?-!&$$IWmDjiWD?ji*Bh|(x z;tkWm?+cSb^S&H#W8mW&h^X_J+8v1YJ>Yv_%8Z9k%~~d47GVI&BVrO_S=@5d(81m9 zX)->*BHDs*N0*K*esq%Dx%zzoGKct764c7*VDowEysie~f`MNkd1MI(f#aj)A_->; zXF~Q@zO#gm0%onl1^NM`m)=^xYpOGqA(^j-c6nnp=QbCm@)k+c;zJVTkD5&e<)~~| z?yL*XSJaIMo~@W^@uv-HueZooG`2XP@8c>mStW@+0YB@&Yc!57C!rUvQ zdXXjl2J317IzW>{@(CEvDp_POX=qk?R>c)hP5+(32p|EOxd(UIim~QrH|g~SnXCkf zY|povJ?qZTviT`<1PwcCogXl$1ktgB4dTd4GXK?jsh{BB@8EU0%IK3KKeF-Gv9>3W zn%vDNfbx^J-+CKOzl$J$JId6wqIHWal&J~z^5hWU3`rn9T{JCuu>4K=lO_x=z2QxT zDT~c`RH+Vr*ODt%$ajuWX5}Y{swXBHsFb2e*SeaaH`vPyU>x%U-ep`^(9DlM_~DPl zl{v*U-4IlI82EN%GcAu)?QAkLo)Xi-+Y(3kJiJ89{$ulKdc``=b8@^-@S(ytUgh;@ zJV6>j{j^e)&x#9N9q5Et34%R){|7#~D*VR6$B9n>Xpr@`jNyN)eSm}t%KM=nFN@yF zRsEh`?F?@>#dl&^se%F(?DkQY;HmQGDll7AZCEKLyEY7(S*d+K+Zb*Douj1UO2VG_ zN~q|>>7Rf{{t4qB0l-bGO2E<($G5~#T8P+T@&jT8PgsX*8-#c^Lxbbi+MHb%o>%xE zClD!n@r7}#5P`^6$g7vssA9j!=w#tVt)2>b96Ou{=S`Hktspq~bnPj%L0F)SRq#1G zjs%1uX`9Su39)`bS~Z&QdO8!eCp#5C+o-|Y&Pb|tZPj8tRnT7ZK?6ixMTku%cH zb&vB(IAUdUjXc;BBy_l7ps8sbrjqt>%;iyKT4nX3Mj^|$HmJO?Pounr%|5Lki|-nQ z=+*KUjO8?6B+@wppO8JXl3&0;M}7Q0^|!)GQDSTP@pGx(!O8E!zfamDj3&oHso8n@ zIN~(;B-n)fFpPa_j}QcVzRaONUI^Gy8NknEiT%p;`SEdz z*3EqO*r12Sap-kol!JPtrWxHWhX9ShsI9RXHR;13<3X$ech8BZcf(mMZoBK_9Y%Gl zI;B-Fq9U|GQ~(V5`^S#c`FKyo3bUcJ=&F5Jf!X=(e(Fb#=JunpIZ7fBkCCnB!-<6@ zmGyrb3OS|TZcceztxjjL;@gG@RPvuLnM(o_l+$t3Gr${|Hg#Sv}?9>fV7Kd1zH{=*!GK zZqN9##G3AEugN7R3U=H#&2QMTP+0t!Q#awK^H!T%#6iSoseC+pAGZ-JdC%)YaSemW zXsS`&YD#&@>ZII;oLBW%QES``25UTOsEn%OyvPbMxQ$D!f79}dAmMEop@H?5w@u1_!jM-BS^~dfz1Cf=l zI0hD@e+EZ$92<#Ujy?14?y&D~L2|s{iWmO6Qwbo`x7z)_`W>$5cS2A(PI79p;~-JY z(x_d!N$I#gn&{^!A6oqvkg@qBnEcy*#i#<0tfPpZ*~L0yWZlb+rTbTg!LgaS%X$4u z0``AFMgoPxe*p%CO&Eddd$zArPt_-eU-1q!kG)TRC2)yWwXq`ohUzr=LxU6K^<5=o zNhuNn+$`r~wFn|SL)n4QtddxmLzk>#Bwf1Jg{>;@o)DG9ZH7t1C^Aq5WJYpn?v@es z#z#KH(7fg_c~*7akFis}BoN33rc8p5Nln}iuocA&L1(wBxWicBeX_1sBbPN@o`MMQ zNQ1hVT^b|I!jt&2sC-;kjiMtLMy5>RzJbK@eJrK8)7M}5YdviptmQeRBUPz zN1Rk%WlpSbKn)BJ3dT2HZExc&Nhe$|3I!UJ9b)ioZBr2reuGj*qA~#=W(u8V06lFOZ$m6K7tjKJIjiXgm;z;yFbcJ6e0yJTdD64Af1a2BI}x zH!v}oR>`K{7A9>{Z0U>GzhDASP!huWpmc927#B&24F;uR*tpuAI0x_F#dOLxEpx9) zc*V&aefN})@j6}aG{?#0`^~Qmccs_0-muL?K7cftaeDyLR+k~qMjz^jdgcnU+C6V% zVv7mj0saMW<5I{!tslmXrehpRtT7UV0*A+kRnU)koG{u>)~!}(r@u2hBWZkuO`Rz` zzhVrQ397781K`B-B5^M3bR4@nN%t7i(KtqL)g@|kaL=#-yC4CRo?kx045%pa?E~(H zE*iP!!>LGX>l`NpAp__mz$0TBg0Km9L%TAMCLmV=oh0!2Wc?$YhP z)Bk#SQd65t<#IODk@V9&6A>r?KZ4nslJQNOxqaYBfdMrZL%Q_`ijWti73gHDW_d_U z>rxTp0aR=_F}htF|6{ThQ{2w#bgC=4&^KrQ6xACz(3yWcrJ;ju?HZ@8H!|MyAKV6D zD(x#~K2A?;a2}!wG3f&|PRd-2U)F-{Qvi-1@fTn*Aq%HYqkY zZ;iXfuh$ll-A~sCKLdD_8yRG^lN&%R^2hUsucS+o>sCLUKYkipJ7qsRY9OCsEtR~= zJV@o#n9bz*;N2VWV%3i^@Xog*kU{UY>S$;Xobjy*3bBG z0s4Dm1y2*{4+CBgeTCr%pw%tSgrTW7gbR8={IM7F9o$fljByAg%$E=f%e-=~!*-`E z;cX2ElIy;8;_>ye^__MN+BsE!?pfNRD4+g#9u)K|b{Mv^8q^g#z^ zQXB4eG4Mx@u2VjOzO&AR%JwRi17J!`#g>?;^_vKl zXEK5`dN#Yg5jI(doPE&_(-J|pQ#|D+%EY6P6k%u6&^ri`INzuk>ZB?uZrOZ{EZ#eR zr3Z;Eo7z`e@wi`KGf|9hD0t*X`vgl}7B?Enu(d{ImGkMRLZIN&R1Dm1b`^;Cez~q_ zpw*oie%v%5ggCqP=|!0vy0&J`7=r&cDU7Edrsy5^reo;!f-_c(5^-9n? zWv^U~^^~AloJQXw_$zHR6Qa+g&C^C{S1Zg%ziyF@QP=EZ*@9+&0&;%Ku+e&TMnBKcUXD9g;_S z+4Pv;8|w4Dg~`dnw6|uI<#H9O<%Fe6-T(CfY0IarBO1}H_nq~{OXXr$q8_z60})4G zgx;_dVdIjSVO`AdJo9r92zdTm<*6En3aREoB--W)l=S$kPq1C=FZFNslXp9`lftX5 zlx+osnx5m*s|Y}$1pf=DfeexltBRV<@ZX@jO^SNE$?LNV^@{75NG;(xQi?IXfCR$2 z9RDT6Z|schDSQ|>%$_}?!e6PA^y3eMBcquaAT6QM6(hdWhgwrJi#AtoXN7oFDpVIt zN-(i0q{*tkYW}$WaVi}Bf(nnY=mU7Ke|#uJbb*igADbnSKq0gv5%fa$*RTjz>~P9O z$SY#fn&l}2C$?xX$|ioZd>JWJ2;PFIb$7lz*_CUOI|O5PdYGvY+r6XH-h~-FI}*W$ z3E(Bc1lziM#^tMWXQgKhYZa3ctae87oNM`c2LK_n`jvSEgu((^#L$T$9qjP85xOS# zuW-Us*^780DacSi7Q$TXW!VKs!i|uXNUAA5S}ZjhNC75mVdrb;d#)Fqa7V_D)(unF z`OfbP<}Dk|71KS95hZVFsox%vm79o3PNaU1=ZZs7gI%kg9-VI53UU`b!V!<(tfcT} zj5;2)Y-@lS(gBZp7o+hczNg*mKh2xdp3{fa%h?`C+jcti7r!4BGHn?i zgh5&1kmksb*6c|{1X~uwKX~`&KIL)mT^*>Z(IXvsa#G>`8zT3&4Dk< zL>3O&Nw$a$47}J=snfA2N$d@byvI_Fhy;?HaP5oUqdv_ER;q8X*Vc^Zq9GuZB8u5x7&GgnvT5e_pf_8ej?V-iOhxJU=k1t@nR(&eYDb#}o;8Mh|<9SuDr zi+A`JJOT)}EaihAU~0_RxLWYB#Zz;Kn%O;NTg3Ke{R*_RI_vR!f$jl+q2yV@UjRI0 zDoFkgc~-11QsO<(0@hRC;(K`!wE4iRK@r7^LUZJr8cJf0N=0hUB0Ee9kcP zp%g_vAdXleA7y)AQ!|y9M-)8)zoM;tEEV|EN$DWt>jcl`UxZsH3HcUs`^*#Uk}HMvHxZ&>w5Z=b^~l_K7s@mjF6W!%pFpgn z7;Q7MTx*Eu@(B4Ec{-{eOEe=-Q6k1wUB%pwrQh8uT=_8ppP0hwU#==diSpU+uHE61 zn?=i#&nY;!qRN5LfYe-q7K#3fS`v{u*et?AY|nwM0F{;te2^>fo$}Ea2*DF}oEO;P zfm%p-J2hD*-Fn{09W}o<6E9Jp&N!r{FaW0U0ny3Vd$`rr)h9+V)&`RU`VRQr*h^-Gx^UYR zeDh2hnDu}kPq-3^G4StuMRP!4`KNlrr4xVC;y(z?a4)b+|8)IcPhKPz1tW;lO)N*KMsqI9zyC)qHrJI8~c*Q6mAr7E(UFkO4Yy} z(ALE1h6OEkc6Ro5zPh^FT}@1kr9PgPYiwz6VKB%n`4=Hf0aM)9Hgx4-1;oxdHtxHK zMe+86E%q`CQ_v6XXkX{Ci22>mO>ynZin%La*SLXALlzB&kOr-;tEOn=^zemKoJ4V4 z(vyULfYTwg_d+aY%Po|d2Np%VIc&vu&4dw{DC=B>1M!_o)LEDcJ&H;UlL|C4)?+;- zk2sAK;wR%5=3Z>vwNX`O&gjQ}q!3l4Z!p;sJ?|adI{oc_>b=ZBUcd{6L@f=owbSqq zpbEY6`naDSecmoDzO+jyJJJqdtBF<}dnd9Aa1L$Ez-5?u4l4J_Q!nPP+3I=Ew8+%l zw!*}2WD@qn087B>x8?gcmyF`?C6C-po*anN@~Gkqphm)_Gjb&v>B`p&7&qQ@>;>^j zLbNH#DXh^hA;>zo>K@xGU{mMJ3hXO3A*cNB{XNuM7&Uzzhjl527pulPMpIDk1QK&4 zrXM}$@jw&}hNYP$Q*=rg!z5!GYKzIlMdIF?}O(7~Q3U-#Br$ua$uJ`*q zdfuL(`cMg3g(Z0gYhBk~jB^2wuWM*3{?L|R`LXNOBGqU}!5X%#=Hj;vrx zSQ9oTmw*5}M1rVej+T|eelsqGtz7w))H1Z?bkMzCTWi|)Bk303HDC>@8-hSJh+u$E z07^{)c}MiLY7cv7O<~z;K7GQm~7 zZbY2GlZ#Tp>Q|)`5KJ_SAHffi9}&Y3@m<|pjmL@XCzk6)A8PrC&w|XvOhn6&o^|&hP@zm9b$`lp~%bD*pf}F`NL{;pF$!=vy7xS83?x z#^##*J{hOnX-k1*_YgEAmHiWg9h5XW(%b5D(Uh(Bj=bXMjR_mSt6y!>#{Q~ZdSwd*M>?@Z&+ z=wAS7wb9`Epi~Tq%!g)q1596&mBXgFWQ%Aj{|i_%pHlzu)nX>LE!w2*u$l z&Xx6b-;hY1XF-*cvdiSPd*$rf2KM9U3l6Fdks}34f$pBc9>>G(7r`{TCD0TZ@d5tKCcM90_}^Cl&HjWr2wv zFr$KFsIK`iF-|kudqMPb*08B-bngU5EUmDm;pD~`-iS}GqIWq>h0&Nlx55nJ)XHq} z!-m(a=eLF)EQqqy*q6IgMeHBGXe0@0S1$GPxSJbLmZYkv<3O1HW2?EHnF*?b0x)V;|`SFgAm}HD$eJiX!0O8@)u6D$~hidZlAs> zI4O>8Ki|Dn#g59^s;8$0mVOL>L(RGe+vbUEQ%Lajp%+zKikUUv8m@UAN@09*c8a*H z!Qqtacq3~e%@w9!_}m_K(7OI4kHh*}n~~gNfr9VR!h%KTp4i26mI01t>_Re2B}Hdc zgs@~2m*zKA$2U)t0b;08Sw&_hVH^cXpyt(ri@vPBDi%2D1X;xGaL*FABH`ogJ(C+8 zn@@~bm?Jcx&Ul*+VUK)+AE||yPFqyYN5oZ7yAXFTkG5=7V0(7?S{{}0XJtjV#u44O zW@;KFG*NM$NX}pPy*YN+-8mlYd=`+XD))9!&-%?G#acm?!Qde=i~<;8K(s&r?9ySi zW_xql`gZ%Z5fmSR3S($|duq@1u&5w7jP@G=s_@Bpt#H+jho6G2{LE^A^r z=sHVNl7Sr1sE>3+l~gDyCf64 zK*fZ{L#b06-8zv|s3egm&@il^iQ7&J_WHumw*@hm5V^e>vIoxOm5nOpq2vv#9)FT7>~eCjjksAA8pF-qDQ)X~WMry4o1&QY6Vxg2b~bGdKN1W$XSOQDCTx z|AWIu0tw~d$_@^$U!IN)Z3z)Ryki;dVs0#)ef39T%F^#~i6~vDyJ+mK*171F`hcQ( zZLaTbGF|KOtFfEGk@}ytdoJI1-1O=%oBjl0{=@&PG38%ca>3BppURW}i?Oo~Yx4j9 z{pgY!pmaHElt`x=(mA@3mKxm%!U$;)Mo2kggrvlXAxbMH(w)*JNT`UOeSUF%=bYd7 zT<83=xOZKW@4R;-5Q%RC9 z5moa#s-h2ilQk__wCx1G;%jKIz1v!{vS<7YP|N%Nki$)w>7(+pa#)Xr#`M`s+9k*~ z+g-;uM!MC7HSK^F@d|5_XpQ1V#c6_D`mK~x!yT1sWL$f;98Qaw2rI6yklcV~{t_4z zw)&3EmSV~fKYfYJ5+k-71>bMHVkT1!Fi0p-r69#cMvJFXlDtNn`~_@A{z1HJ3z4Gz zGB|DxSDRUDgS&nrRaTA;+L)5Hgg;_(p(+Frsl*~6{yXELrtloHb zyD#B`>cR;~-RJ8nWE}r&ue40%1cOSTAEWc2!~p^dJ!dF0*G9*eTXvME_UaTs;iSieG7BPdRmPuG z8TF+*M*UoAk@5SM;&)ByTep}Os>!cl@T0QJ2bG4J$Xmfm<&E80~5!>m(!Nk_W;7SR)QO70yrDD2K= z1*x`rk*US*Zj8)!@)cBb#j|j7RV9kwIhN6Vg$)!4b&5ZJl|g@4iBS1=%$Gq}gok>w z**0$V0QLP-;5EJJVTr7N)hz@<2Lccg-2--s2;d}6X4d~Eabk}$hTvulRNl=r zsz%M{%x-?FSb~?<4w4ZD2D}nKnhd;;%%J_T!<}O#%-ORGReRqlB6J8@h)+&NwXVz9 z2J)!l=xKL&`$6uR_>R(%#px6JHQfjkqrsRD4v6eYHJ%g9XNRTx@yilR^Vww>eQV*S zO(yLa@CKLWXf4`c7Qo1BR}qtp*)6TBnhyl;Y{W#wyQ^Me-Gxz4hcix!ugU}_GRcgI z_+#*NQ4xsEwDliZ(qkOZ$I_k}a_s7wsQvLAG2TwqbCdqFAUI2Z{m~cCZ=ZgZj086O z%=`9~qvFY@%SuQs%eQ%BV#WT?p$NpW?NCDs&PW)(vE$@ZLm((Yya)_5GoLJ%^M#Vm zMFHIflFdBeGXj?7Md~}Kue+QY^}xzoznG5ZNFCRv@Gbq_i_e@0sT>d7u{eCP?Gkk;mtdE zy4F9n_ga0vnGr*~Q_s5L8l%v|V4ag%-0AE2?u8=L(XudrFi^eJ@!SES>cIa1Mf#GS zzBuzi&>1V!1dI%DhWa{cJH6;Y{Q!DU(^T<$zdE&j`F;A)?$UMmcjjxfJlhGKM*@$C zfazy?R$N%5kh@;KJ2EQ#X28_4UvnEWxV^bt5EuJ>B=1=-;xlfjg;4}qvnVDmq-ZmR zwpluFd3d2q;$$?Sfxa)xYrtvF8F^ZX5AKi{1Xz6KND-xN9{6QB=(*VF?RS%>#J;&4 zx~~a#-i^nhmM!pvvv-(!jf>yx$xS)QJ(@3yYL=3}*VOJpwV3agYvSgGl=)>v$l3Yz zX&{6lFvqysF!7-#>h)zh9PfThxGTXX&gs;1ay8+kppJ=}!X2TM$G!OH<3sjEYSLmH ztOk!H7ZbDczaDl~;8vmKJV&K>VwMZ{FUYP;J>8AMlKx9bKh|>ZE{#lnRVJwqDMgfg zoEwsNF}uML6WvO{M}cKCah~(5C&^8X5RGwOI1|;+T~c^-o-SQiv|3R8=$H2oCFsRr zl5E;VO_DJ7+P1Z?$^ICv#m9RTz6pvlp%z%tIh*J=o4T$45%=T8K<6tjYu{OMBg;8) z+HXhE?*B9skqa#@ z11yS2mLZ%Sfm|JVH7?)EhJT#KIBafu@JR+Sc|MJ-#+n)Uy%iw*qzwl6@Zxc5;(cek zf~&sC@^%vL4N*?KRArzKc%X+=FARZ&gs3|c#W)0|T{}r-kuKIsR0mbWsho5^pSVgZQTh~&GEaU5D;E%}EAoTLvvMU|T^}lE8gjyX)c2w-p75blNNA<> zdB5Bix#heza*}GJ_4mQCNumuOr)CnPgvI+|{>p^h48zd_IX3(0S(iyfC;zhc;6vGF z6wb4CI$7J~G&s}O<9V_q==x&la)W!z(`~z-Xvj4GNkOSW% z@aC-Envvs6kd2LW*RcE&uAL$uf|hHZ4fT_M!BG(PCTYh3qPZ>;{Lg9{xY>{kcp+$nrC{OAJ1*tZBT{jOtP-I!uGU%Nz(}P$-+P>sVVjT zV0Br}6=IU^Rc>@5CqR8lWl~jUkhu)2Itl%42f2DluUu!H^wU6d6!Z#%ogIrqk z1MGQ>DZ~QKX^?0a!o5IxYQ|2Z;ka_YX_yS3jVlkv-{oyYMW+phanY}(aJ+Ma3o|6Z z$%f0eYG8+Cv}yCMEPTC9_WVQLWd2(3f_tF%5pLc-Hy)*46{<@kcRw%o^zwY~S4BSOon#-7|T8(3-x$^&>T z^K-qed(rn+dKv3Hu-N?-2*ZPlzex($_hmj@;;NMzJho!r&BOY`1H%mDF-T+Pyp*re zK*{J@-$deOuc8P0%kNdS*1Ur%N&9s#b3l#R0JN28ZEtM(%ZzX9gbBuaoztr;UO-); zD<#+!CixCr1hB_Nm|JVi@X83aQky^%vMZOyye~Djf17KQzyH)us#?R5a#1j-J{PN> zzrxms9ry<4@?kaJ^J5@O4WtVi7#!$K_^-u`U+L+^5Jvd;TJuJ|HE6_n#A9TD`^#W~ zB|**@U`kNniMfC-2H_&f2mOG9X+^XAE1DU8s#QTYJ>brr#V?LC=1vy{N$keDwQfS2 z!&)kV&{7-*jw~YkvB$udcRJ|%Vwbeg;C-wI`_S7vEJPj3neSeI@L5)fJGV5~xttEMj}eQuO_k!SOH$wU+Dg%G?*Z!sa`e<;4i%}Xi&*NWe5q5#O5YD#Jm3U3R>0Al1W6lfr__Da_2>GF z>r1!3&X_sT`rb&!!(|-bw5!7^M!fu29O1bb#d-$O5=t#f=mV$k#K(c6;dHTXnBG}m#$&xO5v{rG`>JoqJ`xd+;7dx}W6K@% zJd^j2avad(@$Gmrq)A5v{#t%s%!w?zLlcinU&T^nzYQ9Owe%nl;>y2SQcL71Zj#Ey zK!Gg-#Q(IVHU}?{l-8{u($tZg##O*tUJ`*>dpO2OEXnT8+q<^8S`*H%Fo-O;TmNj1 z7sqt3`ym|TO{hRLiGh`jfu5a(HE>lhTP!1Y3_00xPNU!XI2l6a=)n+Z)?Er4J6 zj#P3$EM9N44=Mz9-~TKkfU*!zLx9`KCoi8$^gL%l)eal*2Rs5BgX zopJy@{Y_;O(v=x^4-jI=;_J7kYb*7PS)_^jXk9+|x&iVMQT~BJH6F0GKDUs{S{f&U zd9uW`d3Jn6dh%NJOidk>q9zHI-}~TFuI17t#%{em=m^KV8;zie^k0AUU>Eun-qN&a zsnZ)CTD*9tO7c{*!0(DuhL~zcyUmI`;-X4hKmnLHEtKl?jgYpQkVv0s;7dXii@*AW zT;Dbxn->kJnEoz>V0ie5Re?5!CE~@TRbVBMJ`RN-H>QfEv5SF@*oa>kM0`0B!_638 zbV_*x{VyqQ#@6A!VCSbv8eFQlL=TxNG>myQ#ydcuB`=4o8Ef-JPGnv==mi<}F7ftJ zg4ee0-D$wE=4dt%<2p0%oe964|HhZPe^uwz77)uxk2$o<#@lB~DBfUSBpnnZ!fY6o zsDPbNu|v;%?ql_t$%2+TyWN^S%dNdpe8J-RB&PB%0h@lAgiyKJi7{78fL0c=o;x(= z!w*yAoz?9-odr&aYUU_)v-rv-$gQ#p0ZBGVqPd|zOd5;3U=P$RN_!lzYEP60rYL&~ z51y2UjOUN(3*%TdpHAKL2flewVCpRmZQ;C3rgqd~ip$`}RniXKoC&E(7_eYA>H9M@ zuf!EcKEl3-IGTq>k{5t-^G}*z#J7#$mfr)jsAJ~U3uJn51P0lBDzBwA|F!Xdh@8Jl0C#3+CB%uUp&5z$&dr(~@PZB{A{^x}n zS^Uz4eG67?tlnDrhC@pKU6H!HkW~vN3t3nOu4jJ;;8QC95Ov5Ijti>kf9qt4z?(%> zKX1dBrqRoW#a8(d>*5Oq#5w$GD*d5vKNd%|MKbkN%rH^4_6a*?`pIN-+T>sWqLPBlnfrmevMhcMc*wI2oB*h zcfs8s-3>%x%-7n2qHyl;9G+w$h9xUpj+wThKKsVX5|kPD4H);wGHJrjuD>SfSt2f^ zN_jyY4q8(VLAnXPQ}yrjc(N3EXR$6#Ey_hN!x##y zAzmZ8zR4?cxvhx<=i~CjaJ*1B4w@`t9bimPkBL z%~XEE*likDrI65w<7TrJNsFWHV$fwDBh{TgGpWhOWREt}He*AE8L$x;!=t%HMmTI| z>|ZKs-*jdn%-?%Qhu!Y_+Q3nP`{(vb(LR#jnLw9J&QLe8;C)ope*>&SR?mOTpAFV5RlJYs;g>iVt5e(yy2c1CqT)go|O22J46#S z6rrVv%X~D`hTC8)EKv-U27QS;l79hkC;g?Rcfme0b)DjJ=aY+coLY%dpz8@fXcCep zv+M&*+;>LCsYsTbJpR$I+l0S>Ao<_os)anqk1VZ!XI;SFD1PpJJzR_NtmiG!_-(%# znbiGp>@OhNd*F%56W`5{bnMP>O!?&hqS(NLZUIkvV(G^#`pEp`-9vp+Qtj=#^COK zjiZmqdWkAnTxOaf_=by)Vo{)C&wlDm^N54(pAd_R3-Ra8q7olK z!h>Eh$;@tK0vd8dgB&Ij`JT0O?7dQH9~{hi&PD2mlf*$Zh9&*<8RYr|gg%_#xJyBc z&fbDx5-QL)`p4xP`&mW3Dt@$PnoZSj+sFW@;&WXI_~sEK>;Mt7?2<3_Vo~t7w6jlg z?Q_=m?sHU4YG>EW4}iF!8=xj90F(*A*I} zxPf&Ou5}WG1F~x#l5a^VXCaX_#p40?}Q+ z&*ehUT5T^ekEOskiNijw)Q4y?4R+N18AF@8Z>>l73O8}nPEKpe^)B7voDEKzg;l{Q zxr{8fuO`k@vsA6m6Bn8`5%E_6TPVKf7ILbRd2JP|4SP-FOUT^u3e*{8f(vnfj|>7y zGrBNzJ*-6j(dmNd==|Bc@%UAFuDk!MwxFX{KJhfBe?lD~7p)^?vX z&tG5z&zncsLsw4Mwl5EDL)N-0dKz{c_WqCN5_N&1`0>`t{eY}gIA8J4v6t;87-k$$ zhN!>^U0Y>=bRm$7FAA*vkXJVdPQziaVE;c=7LEBtfw2npGY%*!$v#e|R4a?D+QWP- zqpQ_7<#4>b8XN~IM{9!g@j1_n!_p0ers$U?&L0PJ)60P0C+h7pM{!wkR8w|Vy2O=(ZsF5j-%NrxQ==lSx~@#SBK9_(-T-oIl%t1g~rGZX`LY^!6EH z<$v$(5qw(h20aYQ1eVQd8OG7j&;xlL+%(n-2&P0vj*FILwAilY*^C6*?}}vBeiAPE z1pi28&GSsc%tT%2&NNHs_(oA(pK9Ihuz43Ib0qeX$AC*YKntarN=oR)8E3fBDz#Z) zIU^LUor${AAmtfbk z5UVV-=&9&80k;3DV)sFrQXR(D4=HbV9UidcaOTI`>#%R$unN)2<8w-?~ znP@o4sWtMc@lZWmc_~8>85l3=k80Fpr16dTNkv~cHY4}Jz;Jd&>KjGhR{|WJsI9?Q zf!of`=ynt@FjEKSnu>NCyvm|`TxH}g?NvpDe}^HHI+~Dn*%dUs;6WHjBhhC4=VHRx z;s+E8n%{+rHurjel*7?CJhh*ZFK!?^0d&Ls6e;A3E7@`ov0;9W3$n?3`%kA%MjcOA zes;6@`k%OPn}zO-{%jq3$Iw+aBaA_FZ8DTM6&c|{lybJN(!{&F;9x6}@U27*L*!x< z0y1j|VaDV9G$$2ZD>et*stiJ*0tuN2*$IP^$On4wjN#Mcl5GS{Y!qmSv+9V47E)-q z1bkg5f?<}XEe{v0dm%@tO2_#UUw6Ph)FiZbbB}f2QeY;PUo?dHE=@)&UsP5ln4&fH zeL)+Trj<0U=VQp#giNtobiF_VZqyku$QM-Qf?I-6iDEt68iZK@DyJkWug=JWtNp{J zQq#-6q`(2^lwpHRJ6A~wb}N>gHF(gTK>)uKo;bKjVz-WXZN64AILBd&CaRml$@icm9GMcDBy1Ym&~YR;54WF~zbo=NR?ESqC|D7GyJx zHy#FVtx3k|*yk39dcQL0f)1mU9IsAM=FhmiLN4Qo-Qnb#%CT|y)NzD1#gvKNDC{%E zA$*-U`b#oms>;U=;P1|_jYR4CjxN4ktOz_D`OJFyo9}1m?k6+4{oJCyGjFc zs(tVUDyedWAyq}p6F7;E4({5!CwH!;lc%`s%5VN!BX5--%{>E#$UXJx4`SScS_d5h z`#CJVy;(CfhqI9S)Ql38r?r-D**P#|x<*)g(vYDy^YQ-q@xhjd)p7mI(GFYOnt2Vq z^GNQipyh|3Rs{r8%E5|^e1$$@AXU9$GlA{*MpJ#bfyn#cl9U0VFGCUqLI^9!fI6Rp zXP|3OO4gn`?W%6UTWv<3}UlL{0BJ#woHK=FD;vKSU?Zkdd&cm{p$D`pc zF_2?DkXS@x_j|1ZLx#YYty0clI3XADQwuF<@vpJqUJngVKAQJ^zDq;j4iA&f=u_f6 zJInbictPwyl178jy7XxH;I!5JhMP=HI$G7){^AAs2f|*Yns>2Bkgj;z!xiC>$d%3O z5cSu%U`f{1SY=r4+dS&*HS@rCLQa|vH%1BeKl;qWaS_d}+MKlE19T6*33Omfy|YkFJr zy)&*QgPGK!1$nSbay=N5|538a)Epwh}gxH|OyVTHR+hGzom}@!ZXBf~nA` z=CRu-38=!*xSl`{6cuQF=EF>HSk1r^d~Yv=*m}V>`)+IMrefbmdFPRi8d=dP8?Kba zjkbB!%e03yJ~zovEwSSp%E4ewifnvxH5|mAt<^eBj$pwnHR$Qe+T^9wl2EX;pe`HJ)lutR- z+?`5@zKu&0aP*CL2=cVGSe3wt2(Nj{OpOWAS5s(}3xI&6+@xaAGm$TA5)t<(!PZbD z@Kwym=q0GkK9NP%heUdIGKDdc4$ZF-NQy-nOvgevls+$Pb)kY?ho4|35M2?% zn4!U$F?}pN3%om7Vw6vsfs&>DkhY~Eq$?JGk2!MuFvwP`$OtsP7YET)xCu4Q(!|Y4 zYTx`fIU&PJ+55=VpA{J;S%C!t%s@?cg*bdu#y7yPrF#pfc#o5Z?`5-U0$%dz5!epT zPOQ=On|B9@#kcvbB-7?b?l{*$+*{S6igc*x`lq{%D@dFpTIP2+n)7&~JNkXKD?B|H zM9}g>h33k1uV631FrWs0paff7GrNYobKH8Kl5pCwVgcigmdobW9V1nED;2(#Nw2ZL zF#o0@BC`=keMaV}i^oY1N@D5|tRc zhATm;g&MVbk>ezmffLK`$%FNNfZV>!Y*ItR(nWF>MSCO>Kh4jnkbzmYkUty=mWm#M z?wdF*Uj}ST57e7c{!#$OiJ(Fyk>8#$rl`|(cHHA>`hFNJqB+9r;DT6+JxXoep~ox^ z*jNpK(3oR?x=Jq}et0#eclO#@%*5UtoqTLVPm-~eIBbg0AScvFB=ns?$V^Y!e8j5P zH_$_yg?-q6tgEw+eo>&52<8#?Nj8HQws#C33m3vQ$?P?JJ^Y-2nXyQ>{vE@B4F!Sn zg}N=%eK%73T~>2&;aF@X(gSp^@TNd=RRBE0tm0eJRIpjiL#ue9CU6+2ha|@gRxpUI zsJ3}d_KfUvJSFEcw(4PX9BPX3{Hb`XCfHTn91PBc4!@w9f;hL5mLDxE&G=}X9VUP|4bqAde; z0M>l0uSZ1aAQV`9zc@R8pL}J@3~>v^UIT}7UdqS1AmsTDOBaLTX*S8mm_mbzyGH`N zEA1($7;%MA)0cY#MUQ`GC5fsajNy}uPZoZw%!|DiL0h4U)BW8$KB~a-Dkd zB%U>A)T{nX+OQR^CkHk1q%GCL*J4%50P|mH-I>oG%dXHpW2G&$9BAUYN28ABxho;h~(rifMONRqx2WRNg0VZT-*7Wqzy7y zmowSK1#Eo^0szt?C0I_Mc0zk=>r|WAlyM0b#k>gn?#u_RwS4knR~);j9B(+zE>acl zD$$^~q%tU_I@mi$(M(X%}LbmL~=oU(E>Fp@lyP_F1nK5fY62}IG+kiV=pPLCn5VEA3|)AWbr zrBZt3nO4t@*Pcy%^oIizjoM>=?0 zMa+M;`R`?o@3f6QCwh+hcXQ`|%FsR1`4zjp%f^$=QVgg&XZ~<5^nTkMNrv|?cVz=w z>NvOgAy!fQJne))aDPLQWQDEZ7bSXz6#p+~^$0=oAKuPHlSAuOEL*R`?qBs>Fq4|z zib2i~*VW?)c^_ofD15qKg(|y<2%rw~Cm8g!Zd-gf)9$d~tmSs~T|mW^?xnKqXfX}x zEGO3D>bf-8=SCjh*(XNi5TYhUF}9g9FY7fJvAHBvO>tpL;lU(c8(YqLnAyZLWo2zA z4a!(@dpQQCiD*%HfawzpLejtol|$N9| zK>eK0i!+KBUWHop_{z%$7G#8Uz<|tvT_as@O>64XcUkZ4^&J?~I1`w8+Lp)-PKcUK zq)Oo!jyTVi>w=AA2OUhwsqG$*fK`kEuA${Ni0H77cpg^eKH$Mh_Sl_E3FIo1rr1J< znb)04@Y~;BY-A<_Kc3UYd<8nt=moM#0)T{cbkOXcK1L(Mn>5roe676rvj*Ov>^JdY zQWa~Nq9aV4^DCxQVlr_)uBE5C~Ky8sA65Z4h3yjKsfI zWK9oKa@twt>U)hI=SnRd8A(ts!b15J;SD|^4dtt-O zZSRdOq)N*bN};U^{`wzz`MwsnMCU7y4-VP|wNDI)-Ls? znSe|p5(W6@+^ZhDyiCs^I_HKUG;;jc+1xn$CuDhLz}>}VQ?#3D05^HS=$(lv2z)4K zO%H42`rwdN|IWhT>`0wbE&D{tQ06**aJs+%ro3mkVwj#h@f8_otL0wb@MAPp8s?om z>|}B?Ssq#Cj>`MH&n1K^Y0{Q+;IrPGc~ zr3NNeN`j@F-R_xc8Nf&*P?~VVxM)QaXC59+gvQGy;bLz$%u`?ws~Z&yHjoQ%fFID! z&np>)q9mcTlM2Fws7+u)R;F@tK0iRP=ozkG_xC8gFsCE*`)U^-y?>9=Wfv}b+W3|D z*tEhAQ>xW35fvW#S&p<`{$kmhhGv1FC5a+u-18^7PFerNlRSH= z(O3|KAOVFKI)lXKWHd07D;|Fed}>Kpw_uda472iK=wis7Q9vbiXbpTz=iznYQl0*sw3O6x!_a;$juXb6y5%&U|H{ zL3Y$u0r6vNRL6a`C@VTT+OW@wA{P#W>)4IVggX&&CHc}n|cPS z*Qu2{&jpGK`L!q1E?t^W!UE}ePWFta5zR@In9BL-{)_~DOm8$%CUqRFl*1D03C270 zSr32y$o1s{E@i?q*5`P8Va1|cW4%EbTRH*EC4SfM^T@0omFGK+mYpcC)|>{^D-9D7 z9D7Y36lxjP6K3#B-R%jFNm-BPUZ{N1>Z=hf!<2%Pb#Ku)=(uMsSf;9dS&$F3`{B{B zu}}vMe)u?yh!J07cj2Jg5Pc$+Vz8Nd{5@&7v4qoAU5SBaqhRT`vSmkis3s%>zv;#y zI;-u6Es?_?fh47sx_2nSz?t6$z4DrT5aRL-;ud-#tI8r|U(QX4WYG?&#d$@P-#Pmm zUu}JRls>(?x_!O~vM{)E|Zmhx&57qw6%^fy;z%-X6LDHg2YpXWnh*g`J z!N{hp+GN-1$9A44;c-(LhY2K3004RT;DMy?ePH9PkJDB?V=?6|RzLZ69yzLMZa#ez zBj-Q0a5)hqx(6>8z3AV(znuPio5X4JgEYKEZo;jo3v4r~56VNmp_5?8>GcrmZJN2Vv=X$Qk3o3Z^3%f8q3h5gD)C4Y9Y#6hWLgO0Px37 z-+K4lkK0cJo;Zg(JRe|FsTE8f8%3MAAwXe}8hLF1nTsYrdt>neGnwbY@)hlawpuPj z7x2RLj@M**Z4PO(f~FN)GF=tZA+H>~z{;`nussN49ZFfzrT zELW`M3g0mGv%jM-Ctl~u@!-^?hLMs`l` ze>%w(5`BOD{9Ls=L7~9wjD)5Ayf~sZkw}^<0H?r47t_3aM^4+nqj3V-w>o+q!9j(?Hp%r;iULB)UB9I_BF>yrn#V-Hli)tL){s zJ{2oQ&JbiaD6KYjPeNAZ8#?oR`L}eRy=5pg0P8em>bfK?E%X41I7VZWq5#>#@NE98 zY@j~SO(7&MORy_n8V#>o)a_i1gDXvKo<3Rbp0t4a0h!^&ZlY{L%zfADqV2RYrGt`_&HypVWx_*+M?> z>z80=^_Ak&=M5cGUD`2M`ggwmp2;=+3s^+QS_!K+#i(vxEBS|QW;zQz;Ai@$-SE%7 z^*6&LSaPJV`|w=teIcB}n5|-^MdsY zL?B6K!AMFd)9z(OFatTMCyg<5MnG#e( z?koIZW*aFNXDU6Ki<~+OYtmwNW8W$>KD(*=U}Z--!P-HZvN1C!^Ke{XfRG5N3^j<- z6k{%yxMPz6oL4C8b&oq*3wmT<5+XOj7g|wV_en{h_wwS(UhPmSdk ztkG|>wuL_-3UvoXOQig4*JNKAgMAiN8UnYoB9qGs)_ z*a{m-6%be`z}9@l;;cO&Y=qX7C$8STLtp3S2YBE>g&_2$>^~k^RaEq;KfD;zBlH8xkV!-xEg36*LP(U{0Ewd&q zq{)iY*&OwGjFlf*qRN*?Z)5VgOoBxy^!f>uOe#sEczN&l%so@7W@>RCLkrj_(1>+3 z#-OZA5_bM0tt0U$#vo!U$OA7nO7d0lI7e}_4VTr7v)|K96JvB9u2=Krxp9Pv#;3mh zNcG*SYOBm=U)*jRVj&J~506;L`t(Cq;i)cEm61V-S(|`;+xN>7+SeqA? znZL6S*p9#*hKrwAaK4e@kxd}ddXNFq#Q6e(7I1ai^j7eXRgpcL?eD|S-WVIcT94fU z#e$R}SpdA@lrs~BH=2gVoaH?X)!J0YgpJWFm$Rzso)5k|C!#N!TDbQczao3J+8KW) zo}HFyZLfWR8Tmemznaimk4%a%z8mlh#}a;vSvwQ`_4&dTeDTjhrFZ0znF1%b(h=e! z>g$GZ64Eq5Ikz7a-|vf-{9Jv}c@bH`0_%;R+pKM@Jxf^T0khtb@$gOQu(`VXXN_!e zRPNWA1(S9XTq^_LABE!2ga8=u_3d!dYdW{_D(-;YO@21Q9Duf-FdbdCljc<8#8a>1 zMf;0YrOeESm!HnIpsxnc0y2oXPeneDL6c6r8lr>taRSagvNZNLw?ju9$80~S`z!Tp zoc1m~hvWmdikI6wr*r-YJ_|Y>y!f|xV#!CYN=#uz0^U|-BIX{EAtytIHcNaPS)YTt zKDjaf1?W5)Da9p{#%<=sQzVEb*#~Q5Ix(g}%jz_d2+|Db1OhrSmpl7QRR4@a|26v3 zT&Ho^edKpY^Q)(?o_!WIE4f@P+vqN%Hrp3(4}5^ldCu;6oC7)<8JfN#Jd-WgC!mE2r^3B>;x4Nrs1*A|A}+$0zH7>a*YW+q9IVxiID)j3ef*DPHMmC_?!6j~Bq>#F33o`|i7hEe%Z}gtrxP1U=>}af-O9}eM*>YVia{^pi^PMi`ejpwR*5DGcV_pL|!p(SL}%qIgZ#T#lti)uF$7dvBfk}(LzySk>{O5 zVUljC(eoqPs>h6Nyw^1CTwg7v$}?uwb~k>=o<@~}IJeFH->{k_JGPHcTE9<$6N`o? zIZzM&I=R~L?%FYqt$aAEl>!2Q_5iF^)9XEN_&S{Ex>{_o?A> z4;P(|O?$UaH)QfHtcYeO@{)QSr{S%%AqAka9%QRTUh&Sh9~v) zqOn}X9Kw2)$4f5HaB{ozqu#A7O=*>eA-PGO^Dvr(ck>oxwG10ko6BJA4lzgqbg8otP6v5mA!R_n=p? z_fy}X)EqF9$BTGspt8>mmd*7{M*!N|3Cu*}GV13ea7C{Kjmgg{(39p?td>!r*HQ_| zL*@P+1Sl*K6(8;p6mog|0PB)XJL5`SiV!}|bwgiT5PX0=YV9*{T}I1INDee)xqi|x zt?WibCq21m8a7Rm-QZw>cq=0MMWL&tfj1G^l=DpbV46ZrVL!9%NC#^2_%l& z7aVz1vVsU*mL_}m+(Qf`(S)=oqG;8A1+19FX8Jjs+L7n4BDakb@jw!oFOdmpQ`QzG z?~r?+@ARD#pz4+%)A(IBEi-96c6Ex=Gb#|HA&q&6rZGjbhC2ewv`<4i6 zGo|?~eCZ=Ov#_%!RqdYh*?sF_N{W!-RXhQD+CN*=FChoxV?iU#fv#-blU|IzaUZo4 z_(8r1?iia1(4K-SJ|wF_>7c||utuRLy{%^N6b+nBj@ao7s^e+Fo3)JnbaGt9=s;!d zJ>54<6NADh@kNEkm3>B7SXHoWk`>{yqJOyXL^LM^j&grps{VjKN<;*mRE}oro?3$B zU%hv?vTK>0cBs}^N3OP$u#ZkNM$E$vwptn6ZZAJyRw?Q&9Q)lV^AHQjT8P}k?dA|- z9^o{dM(N#cPeO6t8(~!~%hAkIz4EO7iIk&nhXwr%QZGwl1|yRs6`F#H!=pxnkP>85^NUo6O|0o^&#C8h?cOMDb(%WHL(Y^E446xp^Z0J+FQ zC7rShTNm9RyWH;!-RR(5@QS2wKsLX+MKAPZt2h3Dh0z|pankvH^>-XTlA2NcSb|}g za^UOtDL4*o$hcXb?c(jDV|G6T-2{|I^BXqFO{Nd21@>wVqe}0v*68MHx~yF7OnY8^ z@uVD|S)YH`I!@~!|K4Y1-q!Tmo_y3qETe)HW=x*}1t7p3H{;r67k4alZIfom6NZ($dbFQ`%c3zv5GpELIV zcts|JcRtShvFL6UYSl`{nVv4fYnVFyRu;3r-%yTEC*CU4@aUIS3r(KDlYIJ)3X=@N z@r*~s(YN?lQqt{3$K5RP3-5zNgAN$m+U%RQ(q&3<`KSV!XdndOu8I2f_UrLPJkx}? z`qj;&%)u@8uIt|(v~BRmT|2lG*Wwl+cqy(WNFiu&hvM!IrMOFRDVE~y1gFJYyf_3YP`tPmDBNG} z*XEh;50lI!Gfa}}+Iz2atz+G3oF>>COl@}h8_o94Rc)|yodx0zCjBz9QLlI<(F_v% zV*9uA0?)~XckPf6#c~sEhuxU&iHDfvS$7MiYEV4D9rRutk-}x9 zwU@Aa!~@fqQI})C@(@F3kgNH1cNc+$1FH&Jaw}CI#4o10(kr|kG6l88VKtTI zppvH@Sw5`W+w8kFTN)04g+vO%m1KvA!8ZT)dkH;VeGk0dT1>X)S*T)1;^Cndt{XSM z;PMewODQ{gSfV+>723{^Dh~Ek8BvMV=%YkI#hG-|4>S^D!A{Kxm$oVK{+6Mp7ph{V z7<5Oba2Hom9cEOeZdYvJH=Qt4%dTUx_pP}wn`pCavoU+N_@BdAlZBZNG`+)tS_oP- z0;#Mkh9L%`5~A+Rn&WyuuJ#IA*3?qr9m`W+k(X+5Zk#F(Ug8;~z-bq?PbU?Nk1CP( z>1u3S#oOo{RJ!c#1|JJMj!ri0l9LTqoq_cX!4QI>$~d&f{9>#9Dv#1>2INS3kpRuD zHql$1@OGFPFf1bqIR-4G1rDp(PiJyzLhdyX4Tm4g z46D7s(9?DevZe2@?V7g1Jm!@oz|Aaiv$OHRaq&ofejHIDE5`?H&mrqz;VkLFSM;x1 z*ZY>c!cG3vhM;A!{^2`W?ZG~q%}YUZ7fs3;Fdx;iYQo{d1$7fw9+M^U0^!bgt4ROg zgCiN1>B2+sS5A@|E)U>gKXvhn^URfZ!dWT=(Zelyiwy}0M_pS!Wf`)oZw;qD&sz1F zz3=+84HA7`{JlFuJA3PfubVgK!3lgY?y0EuVNW)*iy`1B^UG7jxH1Ei; zCBmWhXQ)}&)Fq@jB&2I~CpWE3lP5xV7th@py|2uZax0~)TrcCXbcDo(W8uG9(bo*B z6$vRVX!P)`Rq8(qWQm#6R`jVQp7mX|1*x+G9ATQ%M>}eC^IN8DE`io!@!x@A*t_Ll z#LBa~@(VM37hEE_DD)H#l%Y6DVh(C_H%DEn2q6}hj^d0$QsjQl{&r3=SaHMUbZ*V; zz9c6+D{ECYl!JCG+-Fw`S^rhUS+Kwm6u&LPVRUM)<8bJ8_RxAlPmcfjl#eVje;5n_ z%C?GoUh@X6X3=nzam4=yN{k-zEg;bDW5r~9TevPtLB|v)F?loQ7b6IefRf4`oZIo_q z2Wr!$+Yt_>U@l}S4m-H&ES^=@#CQK?2ma5* zm@qoKD_LmncF3zGIejCAPlLFwKT28mMNZ3E2bis*^Q#3Lyff{y-GhQ!o6C6D&+`W? zu%QByu#_YXKNrlVPKdUl7BC%5R?8wDpOMQJW^9aM%&R2`%l-FK=b}L_1js~WEt1U> z-tg~T4kO*#JqYn5QF6{n@zYkdcV#;ZXMsb@UmLHZpbz!y^lpdG3G@rj^*rA0be$A6 zF1-ys!)_T|H(H00kIyGEIr-Z`7-Dh zHznSkt{+rLuRs63Ne1fuMkeQoA3wzl(kD)f`C^+`(e0**G{-?i(nhLj*B@Q?A+hUd<`_$}QfnV-_0#LhTe zwh`IyFNV^+HhyuxuRCl?ngF&f<=U z9n>s=$)nzjG>0Ero$FAoH|+~g@xRg$yx0bDp_8R$qGG=S@BaH`0zguz0W(xV2Q;qy z4J(efOVaxvzF9t%trlrFFpcIzP*kow@NPTA6i>Pr9Q# z<68$Klk~6+M+__)w}^HJ9nsaJ#E*~e zk4_JTk}CFzR`y$jYt0GLau%*x%_j#3T6(e#nki`niA>+JM5PtWf&*|_B1clM9y;f` zS=tG|aqgpj2YC^4D3W**74A?I=$w9+@Oae`Vn?fNB)2G*2I~aNKT2<^IohO|xc^P6 z-qy#JpM%B$ zBizo7!mjljP=_odD}e@aB^+dPo2Z0%Ko_ujXxOX=GSPELuQPW3jo?xZoupe_r;vI2~Ucdeg9 zpfRIn5%nkiPbJ#;jsoAs57v)-y?7_jWle{E{Us}k!v(BMrL*k=096FOrRfFyK}I}O1*Ex$+rXe&Yp*5 z`Zkc%*rDgpswlIY9MV3&B1Hf!{@`Z7l;1&3+~1=En203od4w11j7nKqj4(8UG0QIt z4;2dI#OX(b!_aBf|KRaqLsXw@eK^N@p{{r*Mk2D?b#&cOZGB9Qzr7DnqyC=&aFo{86;M&_i7mX(DQ);$)9w z&#fi}oZ+x25reVXvQfH&d~t(?GAGW*Sf2Pkg?EjIb})x)wtQ7X@0&_JjUkYYaI*Nn z$$8BxD#k@2vQ0@q^n{E7@;6poPeVzHq{QZ|U^3yig&RRo4bAv#!cPtItjt7FZGbAX zi`=(*AaTY*9eP#w9dMR>g93_FD^W+mZg1Nld?;y0jcKl8*bvGfj*t0ev`O|j9>oZ% zXQGvFiXKh%u0l_|mGUnko{9rWA#I2dM%U`5dpKcf343=V!4`Nx+E^NDzsghY^*JeL z$jptPpFYuHqzG*Ld`eQ&w>myxFp)({nQrFa1W0ao<=h%iya0WB&+>*BLKplhiuIf5$ zN-A}A7B38BQy`IHTyoY2p9qT{Z5ki-f1C=|6(G3De+v+)*!v5&u{sz#{%qwzFLRiQ zgD{d+(t!bt2e_!=VR6r$rq3Ju=SgS^ab)-l#pRX#FQUG`A|EY6q$VHXB+~t^r|=3i zijBB>>d>LuNt`;}3nBXGz+j5TE&j`BooP5w5+9>+*VrqC2dJdsf`$@gdz6OI3&Z79 z+vb~ue-7cW*jNaMHabABEcn1-qoe|6sB}8_1xQ#elry( z6J(EVT4D>?z*uz^n$t=PvI{?R?w zkU5O{|2r7{`&9HF!0DEirgP^7!}K+Ecb!9%i#dDuo;u9 z?SgIrGCY*9irgNZ3hKUvcQyGD=Ez1mEz%0I^wUnm%|)`dao~(jOa+JHD_K}hfn95Grw-9l`yC}C zygLOGh7QWT;0F^KX=;v@99D7Fh?fjS1lMEW zy^h9`k>#Z&jG#DnBot;gcsA1Wp&HX*EudhOLFI`FY=mmh>O%ZbK>wvYe95)~F+kO* zJD6ZmLFrD##fsx$!Q_aOgC5C9A{xow2z6m#Q%@6aDS6I;`;OXP(86gT@rD*J%SuA4 z@}f-xKG12O0)OS%ly_uBI`R0@@+2t#|IsyK6?v4!kt%32 z-QXS|!DBVd+yeL9`ZQ;i&Zt4(_gzle4BsoCgr{j^tvw4oqHZLVR}3l)7(=})7(-); zcjP5uP2NH9rC!>TLQ41_SJJ3${T#Wn$DsFW;WvF(%xRe!We~9xB_k!qG6%>mxYex( zE?LTZ=E_@ldy>Fb=;O+~lE^#(AAkUb!*`SomET6Z&ZwkL^MT1dt;=sBp4)=`y<6TC)aiF+_J)Llnw$=OSaG)>*C$uCdV%t*M5r1NGuzt09 zhbPKb2AE!kHNMIHvt^e9PP3`;!0_hoMIgSAGeDDF27`j%AnK)nZ0T)qD=nnCY?lLR zJjx#t^>bifkT=Tu<|C%#4bzw~f?XR5;w1}Gtx4=HPQA$%K5XvD$sq+dU~@=0V(DR< z*@)sX$h@D^LpO65J<24)nd{JDQ0WQxwOeCgA6M0$M#c=i{p(KIyVrNuY@lu5UwdhM z+RvfSf14&3xbp=IOc_DC&oUA|bjW0_^iw(>AE!0P(PWidbI^5VGVs1|qqCkedj<)U z*_!5lyWV^#yV4xGd?(aQl3Gz(Kek9Z7-Kx5hU>cUx_r8pVcHnk3?Hy*P-|Ogs$CJ? z=8e9N{G9XSsg=+*{7BVka65h8>bh6`SuObBNK>2c|1*tui9J{A`vXUb&tZ?J`1DjL zsux3fOWC@mt6oTbnib?zms+pd+|Q_(F%9Cyzt{63X61XoqsZ3zYFQMeH-&`o7dI|# zI^H1h_RlO?2Nnn^KksiIOvu2_B8iIELFH#xHhJ0_gP$d0V~{#=?~~0;g25Y`ooQ}} zx7{nCQ=O}r%`Wq9NivX;2TBlHz~P!`dzd*#iDRtynVO4#LOqf|F8_Gt+xe{RZPx;& zTs1`$*Xxf2->b9ew@xIGb0GI@(_k=;E0COy1nc#C5M5YqNvw$dMZ3d1(#%iMKFn!s z&z{Qk0!rGC9ybn^+t=pf@@Krb?$q7I75Olm|2pYyq<$lJxdy9<*nTcH0&{u6q8nOIr}h+(R>?O z0ob_VB)_KIXaU_#_*fQiJJFAaLj5+ zP}n!70FhiA)uBt6Y0cLk=z@X*pFdWI>k}YMLNF~)5m;SUI%ciWyo|QI!kHMq^c>J_ zm30T>NjJIvls8=bb*c62IA1Zvc-O5D_b(gZcN%}}VX^h~BlrED(7vXvx8-}pse+>! zX*->>8@Fxi!#2m@<@*ny(d6mk@3k!akEOd`db}}wxA~-O^7axHK%LIU%x0&Q3o9H5 zv|3(M`(?CY&N=yevc&&b8Ly*^p2=tzE!Pan9*1hrcNmEMvkFX`s`F;!1Rhu7!X!II4*&+xlHf7>!112&KT z0r39=;CTM{M(t5y{%GH}D`zWXX;pptP2u^M5b7s3^2hzFEg7iGG`oq4Pm<-Iw|npR z7APeqHj)nmJcpbl4s+-D#OCf9E;|n%pD4?33O3*B(>WF1_nuw;-ZAq#X?U~zC3VyI z^2x92I{1qjDbHE*c%9SL+5QKivoAEOUn1Xp`48Qcfc&!ZFtaaJxQvFUWhv=R%Q9O0 z`WM&B`SqKzG}Lt#`IO{lA{lY=N>JHX%u?IM#Om;ff7}1UsgL^gxiaxVB#`C|MgV$gX<*-lu_r@_@_2eijr~8H5j9kE-`JbHqcoy9OsZ!Ob(KNgT{!Bug0*BHI zjEZbC=0#+ixE7Qsl}ShR$>!CTq91mZCu$~!>{;gzujZiZ)_ME;{N5yD`{Y8Lryt*R zgp2(3Px={gRQ`G0;QpjvT#71)4Bu4FyP4m_R9q#)28=%aI(q z+5Yxm%}cQ6JsfI1p9pO=l57Q`F>-Lp>b#-ikgO5=&K})3wpKpjJ9gh=S1Rdx-=4AK zwoOT;)0u|)4a?LYWfOpVNHukumjINR%hZ1jpX{~qT-eP!<#!*LJyvfm&V;w-DyMy} zWDEt9(H%E0KlRQ3-lJ(1?r$w2g1cNsuM=QqDH`?+0L!$}VGHcwf$-7DEr%hBc3xLR zYpdN>ks%fnho%xvijKM#BLue6ExkwDN};jbWWD{WTc2p5ZD0{M?MOoxGNBwsm7YP2 zPC^jFgAs#0pjXDz4Zjp0i`QKUZIaS0MN)vBNUWefnBl>2go79jF*p+id}TLoS2pqh zKD1fS9y|pP_;Pngi!cjpWD-i48{$BtKJ&;|Nnhl$QP_*!hUt=1Ae4Tk1(!ZMqQ@dD zoo4UpxATkmp-G#kY9ASSiblvcvcHI``qA=I_ zDxq`GBZ-ZBUCWD4p2zIA75%m|o)i44tRLioqJWEJKoq8DYhl^Xhg0}_C0F{` z^ZXGe?dCZ0Ny3;TXj9>d+9i^r6FX-=qVFOIxLmr73@T2FceA|JC;EVJy!~9}T3_c% z6yuJNuVWgGU2xEjkZ`F)KcYpNMFmj^KQU(HV&bDAUObImN>%G#eB{I_t>aSC!i$iB zvX!Y}LGQT&)LUBIR-_bO-RK1-oyR^!6(^KSJw6N^%@b+y@|OOTGB$t0-+?HZ2;)y`WEMa`ULi3z2KWqB!|{jitNMQg=YBIoUH& z26&B2podWZ=(|)he!bOg*OKjTJf(i94&icqGDI8~|I~moG8D5Zd?lux2 z_X*#)4RTx^{?Su>B&=!&y!(HK$$uS5|K*=_SKVgdknTb%J|m;oNs$)qE~9>qi!kbmgY${YAZG#8MH#)21OOcQ zLenhjR5&5B*S4;_>B6U|ciWBNdJMYLW#R~!C_~2)gO;H+_%kcguRB$Us<>$KOO>pw znK}|Ix7khdzQz?SbSHGNU2|(<)on=ioE-QxXhx|PikGCwM{r?sT7mCC>bdc{%m&1P zCYwT#Dbn^MYPq`&I-y=s*mXsYFD19cgoN)w^upNXesX@YW$*?RPsROECZ^v&L&$|o z`?uK_>xjnNuWY=OEz)F3uwKkRB*Jr7!-`@PCDg?fe6bw-XX)dD%pAFmhA}cVt{ex% z-ogA(jf(&oCyYgsa|!|=$Yp-jSjEAum?Zs`|BQyQ@fY9Aw5fNq6Vn1)GUfdC32dtt zsEpq)BEUDDzqX76T6_)mNImvNKXBPDtk-msB^?vMcyPyHWUQQ+*yvtl)OmEv6UI0J z7TtFA)`6T#X_5-)IBlJ{-}g?ZZRG?BdE9BW4ie!tvOzk`;bxmw^~@#^_JOdFj+>%m zb0JLJF7Aan6s#;0OtnI35|%2NH?sR!W{v%eRfo>!nqW*IE9bUfg6h zyL`fdnMI^`nJp)h5*=nUjJ#a&b!$>g%B%5juE>YDt|O@|)W4GJtI$FV?7QusbF<@2 zem@wh54oTTXPq+dt||N#-(HC(7bD4ZGbR=L_NOZYEFMpTfc*IPhZ`VikHb=cDK>4J zK_3B*^8mjiF2nqB>C^>pJ#4o%?dq~!$MxJTty_pJt@EAwjFUd8tfhrTqJ*XmUZwFK zJaC=bW987A)e!^rGk|ZQE~fdx`Udzl{q7=`s&{HwlZ4zuufK56H8RcUJ`v7SVclT# zVrFpH;b%H5&JckyBhZ20E?~hiU-sH-`zld5qeyT&z(MfPV3D6Q${3*F zLL*_-t~6v|phaqn(2|Jzd(&fE_yMl@e$`BHR9i26!;%Zgla$u$j6>xKveksf ziMJNgJpG{5DT z0UWO}`$d>K)2pMjR%;N~PD*HCu@HM#`|Fk=t9HNdw-YBUf7GI9R-{}fcl^sz;f$3T z90OM>4rU-Nuh`gmI>Fk_=CNAKcGrZjXJh^igxtIDbuK@nmTl^QtY zXtxbihP+i6Fw$BeZvg#QF%Qg29=`1N=WTdp!)eNX4k&g?00K{S7=fK8wJ=LPMZv(Q z4huE1Iu%)3M?!;eAGWlsxJB;5Yca=G zeC$*>PhlOG$w%mOgNaVyZ_k%{5HYzE=rfW* z#R}0ps2qwXW9oj8g@W+M#8L*q}~Sy&%a=sonw4bU3wD>q8D;-Mp!VfH?k>> zG3NZ(TZJL_yZg4ZHtiy{SqqxvwqEMa6SNN2g{ZiZ~@WB&3?ksV!Wz7}?o+bnJ z`=^_Ql?l&|Ei^7GHuE6$cVxO;=K36&xZz&5zDo|mkhMR;%&o8W3&w43R=jj3UUjeg;W?1exTc2_a0jK?z$o2Siir_s&35X@(TVEUJV4Jt>wy(?B(A}6)nE#^f# z-B-6e>zvO$&%z*F{0JnlYfs`m64>>oOSl0E?4n}C@{)Ht*QE9+goYF%4|y9O@29`M zKDu+-wMjPd>RxFWKi>Fz(GWa+u=(At?%C;4?xRY3hzMTOev!gsp zqQlSsvnL?Kz>*Fyz8<_|XfZF_!+tigvUiy-$TZ$lG4LEfn1Bu_wjeU0l}d(3`O&q? z+eUND$lng~dokdv3gKX=&1j8etF2EoS>1D+If>* zl2!T854}T1)u`Qf`&TZ9ZcEZ(g;PX}jFZ@tP!D^iF}`v8pPTWi$TPjidQO70GIDzQ zH$tvryJPmQKmB!W&U$CO+tY;?T0&a%gMd%-Yg=v{$G!_GAIjaokJH)6<&MQsyAiQN z0p1@boS#O1kOqC&&h7tA)|RoSHIu`kwW{o8tHdFlQb;?AQ83qm+|+Lr4jX$}8U0=$Q`tdC9jLNu0N`Codyk8!Q?(ezN{wD%QByuY zeo{6v&jf*{D4?^@Fmjt})vav`mZ4@eY|&6p8}D51V8sE?VVTW?o&+ttA{)iI$p>uV zEpzP3IqY&$4BHYuiB0>`PN{hkK*{Lr0QVMb2Mn_|P-t-mQa{%-fZbEJb*r@++qL>V z>bB+7{K?{p6F2MZ@=qMskpW;MqdBY`|BhFY5giaS2p3CFf4o&p!w@U>_c<(A?xbhN zqfP0J5atVZ@Wc!#W0x4b{QR~T$%3oly;f{{3IDT#h-qY}hZ4AIo@aHAl?A-j6;4Uh zitGTg;wTZ6Y!DxKNFLA`8S+dAdx2N&fhXUPq@6vMkJLD5xPbEu*w^pW_C@7k$;h*k z=t)F}x>(ezr7+*_2Ew#4`;!-Ec(gT$=v}CMG9xvC;APz7MR35An&A&8NcaXxxtXL?RH;EI0{3uq$nuytoO$+ZiD(z-;CBvd}hRp-?g@ z?Hf|CW&h?zQ#a@9B&@JXDl0uiUdoX+jrX(vi($5RmQ+hDr6d z6~x4@P8M}A5!~-U*afRvE753wP9qWUZfCc$$FE+-i=w_>70r?6zjEJFi%t>>6`!Sh z*}{i;%@GX7-5M99x6AM!*1_8{2%hUsP*uZ5r6`VyktbkhkK17kvUkA_`tFs*e3KDgGqJ+hakQe6QKW5r%{ zqF%5RxZ?sc@teWeky3%JYRfNvdm;G3!e6Y<%U{bAG^T*DIEbZC)@d}u%A$O`wlUim> zkdq+EcReOjbXEK`)UJXkv}1hjANvks(VT}~-zS8l{-e>Gmxj**I${z`uHQM&p?^yo5A zT>-qU8&fOtTlxq{+CIQukoqzkK_;9=A~pT-9{?p{#zClNlLR=RP2bY6S54{6BGRW( zlPR;s;bK+Y3CsU_fl->k6@#K0G#j`0L1XXM7YeZyO?c@Pqz=AF`{wBW3)gMN0}%iPAiTPfS%?^2%jf5I7eQ7@%;hiBJ$>?;|bFWgtjST53}8%d6}UF6~h41uK{zJ@y8qe_znmA$;Bv()dUURfmhp{G_>hD4oru6-R)x~1A_0th z!>6Qz<=%RVKG%GLD}ne-QtJb)`H+_v^wWlQs!fkAD;c*k(R{D2zWA;<0*G+m#l_D1 z`Y#@XP9DFpkuSX#+7tUhqw+m&n5%p}7xKI3`RxtyH5Z{5?+bUv!(eB-mW_?az)Io5 zQ7!@Q!lM`MOj|clmR=QmPR%euYKgIIybu2X?A()J7Q9t2O~(_(BjHLo{_LA%pASOI z(+b{}^;iCs`vl!itK05y50g1gE)FZ(e|PJ9AF^(MFKj zRk+Euv_0Bl%1%>D>tr=TEfk1B7Or1~)N0;c)|9R)|A_D&<8>>rS)vG4|CO@*H&=k+ zF#M>-1d`=7Rn|%c09pV9W4L|5hh=xrh|I(mTWu@V3(B*h(;TQZqU_<1EM5|tj3|5 zpnsG9Xiv9g4F32|WOCb|UL+*OOwgt~K_#>K2yZGLg6@db9A;X)+FOZuF>e`U+?rD^ z;y(wDL}!yeW;&7rrnhsm>7Vs@rhPaY_1if?ek!RU-1Hyup6L#sOxwF@PX$hDFW_fae@V?g z{C%`A-(c9kkbxQ^`2xLTh~Ff~UcJ-aJk5LKG(U|dU-{eR>=Rc||NU}OQSuyoPN+M3 zy4ZBO6QYoNj3``pLj+w7-k3Mhx8KK{5SAX@o(0@qHPoAkoQ?Y4oYnd7F8Dm_gw#d- zuY{@KVmr5GOx0qLwP5Au`nz%5XH5cEN$aP5q%9+P<$x9rNg2viwY0N$1l;e5$)%hR zZjdJ8y6uNC)W#u^6^i4~iKC?Vb~bV^RNYWK-N?r5-(5u5TLX_98)x_J09+h47ou-O zar$E{CuA?z?Nh~}La7KDr4v|E&x%vbx(LM*{^KDRho`)H7ZKjob0GG356R{CuZZ2I zydO}#_^so8nKWlD%FLV8^4t(HSlZX$dbOHq!D4qz;i{%GC`Xa&>I(YAOQCb$ggXDFu<|#3L%BUq zkjPz4QPziauwVp|4BUf{HSvbqHNP&<;*dks7rVH(U`6Vg!E)QgVQ9V2B<3`w6^*CC zcUfivrnRc~IJeB8)-!LRwyQAY zDd$nx_HkbN(|-ooKqU-Ws#qVexgxO&CU& z`5BT@ngT|*2YvB6}e$R_IO6oBp7`Y!-VPa8itLcFEIW%ItKr%`9Et zsA6UO936)-tUNJg(b&9BiQvl_B#WfhM9j74q=?9$8pk*YZm#E9Tal(gjU}=8tUn26 zYRQv*o^TxOtdlh?H%Z-$l?4V=dGr_cgA%Ay5;j5^cPj0bKkf?>-`yr!WqsW0h)NgH^HZyeIoWXLsW3KRQZiDF0)~UJWZ5Ei zH8kjmw}WxLlR}#ADgvy3ZEW#nr)?KC8ZBmJG^1Mdry?8U3!BMgI5;%%eIZCTi$G^2 z$U`gR9eN!53OK>Hy_#vEZSPx(%}%D`on&y6j>=X;K-=u=4qQFPTc^J_=u_;ryX$G8 z*FTn&WwsUhtY`FJh8`(*pn=8B2zwp3W2e-$j|6Gh?WFH+pehYB`eCp|gw^4Pqwvbo z+!?6LROtIc_-Mt1CX!-*+BhzJf~zn*`FJEt%$SP8p_L57C-H$wq9j?d{@Rvsvj~xG zu}qDrxSlK+54%|CZWJmi;UX3$?aTiYV*^gEqA;0*4okjnq z7YcI@QPj)IiCRcH78Y4@lM3u+FSJl15YEmY2LU-Gv7zW7IyonYAsL`m z9f&tKMEg7CRjPFZG|x=UUQ?eB2M^353!;3#KIp6eHM|c9&XH*Le`M!cbcTChH&Fcp zFl+cAcpsn`w^Hko8AB8uo)?87;{T0tD$-}qmZeDCZ?J`BJUDliX05WL&B1XDSEmN9 z1uMdveH)`RVV8d#wC!u&ES8|VvaL@s_13pN7D^lY%Bl8>)-B!^Ga{zB8dXqID&r;8 zc6w0cUhWX4LN&R6s_287l#Q*zWPLyiZoIWz!|d0>3=a?7|4F%pq^3rk{rLHz`o(_w zl3GqS_%Yb+<9=_)*ZQX&s=>N7rK>CpFc*rc){di|_feXK(nLnx+lZs6q?;^u8@D)% z_C(WF)7F@i)0gg|h`LJD%+Ip2X<&3>WH0xdM0)~n`gj2H!bdKZfnv}=QK+Rq@)=gu z7C03-4Ft%~xVL9yXS~^5r*W1V-EzK2SSxCO{Zx3e_z!^9c%G|+o~^FNDeH*wzg9$Y zvOUHk7feA(MWxQhL4p6xBA zZG&%#BfrFZKI}oNO_R0mVrVV^fSw6TBgrTw=a6S*M3URSZDa?6I}hKK;g=!GBp*Hv zUtrO;61GOKyZ(?;@m(Zdz*XUJVZ%vFgJ=R%DkY06UX#88MCjNOH~@#{>37dy-*|=` z$-H4|OY{LYOD0;2^_-e%_OA+mfVVSbQtHK_Hum{PTJxcmp+E40>x{y?FYn`Da6a+UWiSA{oZ&`Ywul9EI^QC)H-8bC*@o{y%Qf%N(Z7q4Fbm~Wk9H9| zXyGP8lwL_3aZtME`(%9z;3NP7ic1c2H7C&VieJa34+Q-1+loleGF?we$wWafr3<3I_lFy&E}vcTc8G^-hjK<4DKO0km|j)yGxOU>@KM?2?yc?x z!0Gu%ovn@C3y)1u&l_tGLP_TJ0ra>4B_^PHBwFc#ccD>%{OJuFd|%uz(6H9`?Lu2Z zce}p#pC~ue`Eb0%lI>71vnYg?tI$-%)Z`5ai#$M_!TGDQ-OY{6GiuPj2z>q%0=N&qZ0FYGtcuJ8GcMrwgj`i%ZC36ucw1wg{H|+m9O{n57|5U-|*_I8(w#NAR4*97@W5L1Ndn4 z4*=!i_s`WJiV*D zOhFgTpi_0IPY3t6i>7nq3vf^PXleWaYp<%+3_<6FYvEU7iDe4If>lLBjHwMc$#j`j zRBfpIG$S@V9pm^ZI>t7wWx(71omX5+jx(OSzj!ow)_UJpvqGh8Bb zxH37`thtz8s+D`J+T8lYS(X&Y32QJ2J_qsUxb;6&N~Z^~h4f$9gp7X4`T}m^J1I2U zCCqq;!t}Rk8>7v3)oC5Yt74FW-K))!K>PB258G%5Pb_nAPe{`Q(~I5iC*@iNcbB#p1|5yRpB5Otsxv)_u@n~VO%TnZ@k~f?irjY@ za%VYW{Kkmn_8pra{sT}r4t_HfEKOfCyZ?HSqtotUdy2cy=HmUAv5oGThmX+@iBIe` z13U90N8^73vUBYcglwAgm#TKj2;Egx)|?#&Dc8<=Mh;zxw*Le<6?7!w*O=! zqh0n7yzM2YC-*tK$v3@zDk2Rui+|RF`lyaWR{FY2jwOQn%=~xjj)UQ*Zd2{`KBfug zJK2v)|GREu2?RJ?r=HrPS^P+*|7BuD<#vHDMWeTLrnCU0J%v?k!9I6{Gx=ER(=F!y zyKJ`P`J-{T zOIEAM;X;u9{>QxzRslmMxc2YNE%jjE&iL&B54Cz^WRbqXVg-R;2J?@zlzMVBuYjI* z9?>*pDDGYiHLz2LI8USuSQ)_rM$gK2rl?zSCJLn}K-%ELj;Md25|KfawkpD4x;%w! zAOQ$!C~vq7>_SDFOh3$%8B`ZDv;O!ecxq|WNHWXZ%IZSI(2x<(N|BXbpUy!4~ocb zSJo?do0iIqJre=8UU|-bV6|Nz>YYvg23P)$VzA!07eXHvy%3;zP1TGsatgnlChkyc z>U2qDMNP=UdTF&Hp%O~4LDZajit4dnSElpcevhctNO5H+u#g0CUiFu z>K-(l^ei{|!KBfd3m#>Rfbc|`zC*-vz17;XBk``5{VKj^Q~?LMfZv#-PWjE_?* zEY~TMlO%<)5I~?qOj)UZUY06QU(DzWea(S%I$r)eaV6AJR*fJd$n7(FC$>b_b3iY6 z<(gdF_In?E?e*=1;6bSp9(aIu|ch(*-3@HaFDVBgnRSL>~b7gGfM|zvQ63ybKKl0V(-gT;wT-J z0ts}e1;+M2>vfqP{CNEP`o|qS+h#TJ4qHXpkPo=ahd7#E}B#68ErV5?fKA-Vq@a%!8BkA9=yq>Cok!jil%nFM zH?h>E3RgZ%^w9>W{7#U-pDSE-o~#RPwOpbMaDF9X!P9uS(Mm$RpzP<$Oacf4go4TQ z#ui&#T07Kj!jK6=W=*B<@5bWUaL|-?2KQi(VhK-2_Cm??Ng$BESuV`6{$JMUznl2~ z{DU^G^19gP|MB&eac%7FwgG|` z*W&J0T#6(V3mV*uyB96)1&R|~8d_Y71q!95Xz}2MAO%Wsmli19H{JVv&wbB1zk5G0 znF(K#%*=n*v!1oqv%&Rl5wguP<_X*;<_+6mk9V{^kOr9%H^5=TR2&qm6xTDYh;m44 zyoDsx5~B}~teV;LF`sASTq}<`Mb1mh>=E{Z>bVrJW+19u>=}UFbdmxVIFeW=Qon5P zj0n~zuTyJwSDjzY!QLW`aG3+tT+c;JHDMpAoPa&dNp3sj1(uCyL>tCg?%|Y?!C0rT~2<2LPd= z`B1yf1Zz5AwS4I^aD{yybRUz@pp;dLKT(~kJ3A1{Z;2C-IsFuDA#r>HW31%e=}vz) z&i8|2_4va3g2Vh<0j>RH>o~I#yBWr1UyLx*PddDMnv+bhqjd#(wK~tMbf#l`cZ()7e5EkFMkQ!D?R9Hx6b6p{JO0A->VMW+=b5&pPOYOi*yQ0~CjrJ7&{+x;OA(v?8ItX;6 zD33dCa;7C8U5DzYAS#|c*tl5uVjP%o`E=Vy3dYhOas|J>lQD|n4~Ae8Tj{*=rYmz7 z@2_E%!NuPUHl(+AS|zqQq+(Q#-7;-ZZ5fVydPZ_w6`A11_vU|=3|Ti^6u);?bC_4x z$E@K?i#nWqF)oxXrgB8Mqf7!@L45$7aDTcVkCpi&Ef!9x6GjtCh?ySNHd`#tRD*HE18bEm7ODa*c-G zGz$Qo%#DpZp^$@EzZ}{lVL*waj_C%3aElOnIpBnu+~r9z9_Q6ET6kumy*d?wN)|1= z@O5|Eo|aM9z@=iYjqyw{>+q1Aj*>6GE+pJm6pDiV>LS$b!zA1T!+s*U_S^6m&4B|| z=7hbtPc3)ptyY0}xL`2#_JX4?e0Y)wV+SXOWbLtv?L1==Y|2EB&iIWKOc34IA%jW; zxIsOun0!6kIT3R$(3k*D-mmy_>Ra0BSS2cK6gl?1*en+%+%JgPtvxYa(R~knavnK@ zVioa6Qw;mN_QhvhvE)6{b4*Srua6>ji-I>LSBY2zpV*6Vf^S$oaw3bw8|)f9TC!%m zC=`n9Fc@rHjb-NGKA^=MW7X5ZWL#sx6G|&Na+_eJ!avdz*GQYyeJ(%%d+nP`rhS5o zL<1q-D)Z5{d=_NLg8rs08oI#(SUTU`sO`aZS--i6zC+ILycs!u_69{dK!RdY%Iw@q;IhGgFF2rT0HHhhtjXmu28-2NvRK|Mz-)w=7 zk2>xo-Yohb=zH1_*7yIdo-<9R)muk25+vWQ+X}`2(Y_RjgwBHsk~S7JeY{wdnAF ziEdKCl=)4$qv2T*t27ugS&rQ5JFDRQ4&SyDEL$1b{&_>|YpcPU=KS+&?!{gHUZlI{ z+slsuU?X!#A|*X8oY1qUbT8CNxRFjswC?(-1hi=px|WBd{LpN{wMQadxQ+gCl%4R` zYc>2qee);v)zA0E-g(4H=R_@M;atRQg;3Y{hDS70Ejo-Hzgt#Sxt(}>_Y)fI#Vzy#RT;ChPv}&5>+%ycuFsT4O+u*Cv*I=~muqT?aNH{){ z!z+f}4Oc%VHfXO9C;6X(;crFMe{B?uy;o$N#jTnhZL5&`mE`a@4E81X8{vJ88JiRz zVQvv)WN%&Y5d7@Q+w40G5kt+D+ex^AIr!>qOEB0$4PQE4VEamH7plXY zPmq@@_!tEU|0r)Zo3d7+w0iV(`stN9pDR{^J@+eOg9iV6^})$GY~+B~RoC;ycPaZE zB;Ew;#6kXFEEKXZ)R-t$o#uB-maeA#vAbWyI)%EpvBMg+y2f;x3_sb2M7pX3#ri2oKiZYbbbk8@#&#PTE2r zF;&ImsQu}f;12Ws{d<#8f*|5#lU;7G1tj1-Ed$!BN(1G z%soNYboFNzjx08556a!=Vf0Wejtw@`EaijvG`rX($PPI9MPuwk%7>Yh_;KDPntHF( zg`SjPq2_scHJ^Zj(@8oej1#id$e@AgyY62*t%jsJid2sf9;!nNeIqYgs~sG#-gg+} zJ}VyWa2Nrm6q0d0>Dpy$K8c|uGZkKEiy8l@xdcAftQ-dH6?v<6c`EQu{m$KfhB(?C z(pI59(qA_DBC*ge*9=qsaK`aT&Rs9t&e^=CqabS2MTD;m!KvgN4gaKO#p4;13z$hB z(lSI|(pF|VFWtYsU`#|c6dK&fFZByH3QlKK_xQQ`qiU3+=YLdK@T; z&ufbqgq)Ho+jthSX<(GDQ7R=l!VnfKNgVFuL4hhXT19O(6`B@4u*~|v@sP{PMX(^M zOo<#D$B`&Q{*d+$|G(u~Rj~pn2Sgf0at5~3js^!|XEJSA;W0-pAE4$Uj}97SBrAtV zf}Q(fj-^R3z%jUFU>NZ<_yQ|X0d#-mDju`k6l%8y)R+=mGUhbVe^aO*kl4Vcmw?>* ztWiePdjL$Ei1^rCEg3P%L&)2f3ernr?7a_2o^#joyE-BLy&v?`>2#@{`)t@Go9%`3)QIR1>k;&STnSTLXBX^#*{ys7I3n2R!z%F7uazvi_ zzVX#>G6`$4AODo)I9cbdd+f*DZyXQrUl#bv*RGjLm49moJRiM+Kwve30~Js23%K-* zIeo%iGr?J;9n_?8IXtJBF-j;xtcGVzk9Put*RFc&rsjWAAzK1nK&YIVVp(S;Tl-T6Kt!gw!E zHSrf<%S5n8zB#_HwY5;I{MUTVc1jgYyZ>ArXk;^?k)J2q``DseRL3mG%QHS5Wv|0lZ&w*bDzR+@Bwog^v{)6-y~Ft+x0|y2 zk3<)5{Mksms5dFV9FO3aZ9l571NOs-t=>S&6B{4fC?V^CxyIaca`kJZeTn!(MhF@w zJ;yd4$GcJ6fuH3<0ATV^9xn0>SX>$aP3JC>j=4V{R3go)c=#2Uj>r!L#Y#m3r1l=% z?gKdLq4!!MT;%Vf;AAoDW;Hnavap$#=tpp^i+A@R5qhWW%>X7j#@1v@ef6JD#}=Fn zwCo_rLJvnM?U3CA4c__T>QIt3NoD5%a#Ng4Spv_Q#F;v$i$~z9Xd>>h=B2cVrReBi z0MEDGhpG!}Kd634jSH?m=LtOVFKUKsi9dRFL`M@+Uk-GG z^^rat3}ggT;z1vEyJ=%7*<9%o;Pc}qtFxT4>|LM2TSU=QW1)HqT{vaKm6V&EpMXe@ zlANC+8(>>&coP=50WmytKaXu@KnE3kvD#zrKaWzzr876qA(K%T>)ku5FblADzh-yq zS=-fEcbPfn`58*wI$$_oH;J-RSdO8r>}!~*sL&wz`b9M4HAd#Uo%md>_lU|VL0p{v z*+k(h&%sv5DOp;k=TF$gcmxq>aPt=8iDOv$+JP&#wTdJnXqG1XAnj)c}l~Wt#CfRzns8Q zf!hC5BK;@%#w-|w|Hi|*P1F4WI;WXSoJumufv>O)1(%WO4 zESzrYUn$k5jPeRpF#Ty;{{cJ{L%91tBo5*Jy(E_6*;N*a@Fi0$m2TI9ndmjnAFp>M zas_{!|59iLq5WSMJcsaubdD*0;dhauyB!q*y0;JJJNiU|7H`)_Bu}dU0+@cwc@=|X z4vj$u*}#eZCM0p+~-Z(mPv}1BCaud>z7?i z?Ha!B9SrU58Wm&llI;!Hd_1dw>a2FOjcXob#4LS89LN4#8zcW$Hpoel11a_1m#Dp< z&jS3&5V$>?qS}R2Q|P00pCnp-pxkFH@d^*_=H=N7u=)#7*fas&h={lzKkv+dG0M46 zyH6TpNKVFn(RZO#I)9gA6Hm-?2G1i+c*aW6ql2DT^XO%$(>)e_t(vB!HuAlOhP~W-ca63>h2hP4s`CG87#&P&6($M|cveMeqof+8%h$r${fJwH zgKn1IMzy3($(K!yk8mCiS20jolA!2I_(D5tP8fw&VbFbgUG-M(;mTJFgEp`D1j$fb zs~M-cuGtQut^_()&EkeyM&EB)R0>|Irks#5gX1wAd%x(mxExaQOzsp6s!Ae6d=*2B zk_Dh-SN12JQ6}cZoBfiDcQ*MNK-YD#3l+x(W-*UZJaco#_dHb%+&qa%RCF&qRZDUx z_i|f%xpl};P`)}4zMjYwqH*F8As$Oovd8SqXALkz_gq+<${G`3^&phAZn0un7^uGsJ2 zm%m=qOSS(z#&EEDwoW+ESifYDQBgzGRnAcz1?;7OQ!Jqa{yh~;1kFty$~k*65({uI zjNeEeSwUbUQ3m}Vk0hYqmlmHy_u)EFK;&K# zmGP3tgUD)>APOyz>RKU*-P)KQ+aJB~F58c|=ygZ)TM_ed*pm0z$#xUc;w=4xZYtL5 ztIK=U*zf4!(qd@F)Bkuus{VWbdxg^uc>Lcj3<~jo(O4piAB*=VWB0^~obRA;?*Gr< zmpjf`A;APe>LQKhvj^hkQRje*xLyp|EX<+8DT{g?d(z12-;bS4R&_Zgh`?&#iWQ!g?a(+$-ig_7K0izn=^>4BeceemZ1nIsH(0 zaVgOz;Hj(nSTWW7{n)sSo0+Spx<8UGQW+-rYYozeIpw}?Y$iZKZ1Et3;qLbN zQt`*Dk(}$od4$`AndSjf4U4b%+9}9h~>D_ub>=&D%+7{vbnIV`DB9%b-IwwY*CqD z({-tHZF`;j?>|hGuSi+hKN=XTijKKl)rlrenAvT=y52Q-Kr(&GDqS;q?y15L? z%8@8c2qmDDk}0}@%Kl3j`45_5WVcG!Y_I`|J&i7+3TkRMkG-9Nn5mF#cOXJkV})#i zVB?8zhwXnfeXZOc0M;Ci;WGgEI8-ae*$c`ww*@k)>CS7%B$1ZBJo)3GLj2`_SNLkA z0fJvXRJcevgiOZnNHl(%>3NaWJp^Z@lE_g2ka9eOU$DUYqTuG+gG9Xr7|j(}b;efv z0=FF4zE?=O%w-Z51Fbz>q4#9(niThhQg)XAz{~MPwMtye^ zfrY+IxjUg0D?DPhGHXgUz6&m#JpbT5%vdS}4QS#nTpFtK&Lb-*jkx*|59NhTD(U+X z*`&oCxYw4bKN2b7TOglIi5DkO&BBpG0l=scr|5J7!icVJF$}LP3b5V}GZQmIb(fy5 zp`~wj(gCQ24&%m(@63*UFVHZDvVo7T0u%+Ni{X)~Qu%Fq&vVG6NmL$s{E!ccLjZcvK@6b&yX(n0|mi<60BOFEq znV8qcC4C-p$?EHz*fAS{lXAUS^pemMCb^%B`ou|OnFG z^W)M6YL=+6p#%S<+bntT>5yiRI_3~R9QI3>;8(r+H@Mr{I3r8eu}qZIRJR1D;&dpF z;NSZ(bsX*>P7VDJwIubCWj6>Dls3|d%=Lw(#7@5GtG?XsIHDzesuKLiEtCLP7mC;A zE3zwgjKa zqu)t{ahU{pMsC};m=t*XW|wz!RM|f%F3a+&oOLrrMJK@F4;iPJ*I3NCB zfD1hwoTHJ%0UGx4!aYs9vUQ`S{!8jIIvB9h=KJh-fS!Y*Yg?6aIpnx{de%PA_H_wD zI!ca@7bOr+8nec+99%+A3iSphIE9h-43HO zcw+v};8{)h)BMMbogR&y?u(@uLLbTN5)h`N)fw!8d9FT!>Ag*XMXt?~KEK3BT)KUI z&SankQ2@Fc{E8I2w{ zJq(rxcc_M+3brKK`VpL!@%J+3zjx4S0J?>I-05OqL;YfnAes3rKgSYo#ABC7=ubib z{i+T(s#?gy;0m{DqxM)|o!lCAgfvs;8frW-@s@e^MHFM4^jzr$0B(~BOjw2|4}W+t52lH^Kj#tn<_5ubiYd&G~D5~lHKL$|0X8ySDq(T1cn zceyibrx|#dyrq}xA91~UpHcJTK?ZJGp)Z}$%?gm7FBZ7h_z`|oB>oDIKKZ7r+0Xi(6KW9U6iSmj;S0CCUC9+ZO*lNZBv^ImeD z)|0aG3*w8~WLI{%vbC;fUE8#6xj7S@`wZ&EvDO)R5-&(3Sl*3NZjFog36T^0+}2El z#rEc?z7%`!b>l39lH>hitQRfnK-k~W*Y*Bzp|^{^NBqFBE}hFnlE5K9c7HbB5xFW* zAzSiXg<5Gz)eH}M_BvO66!W!OJm@UPCF?Op^^;gWY=kYvqs0vIogJLiJ{sHCY< zLV&dpNb!nlc9>6hT~qcapUY3JH-7>4&?@Woig1I--&y!Kj6QR2rDs;@5N7Z8Q+_jMfs^&)%$tXN_B znFF7YMmYjT%Pw)=E%D_scnqC)(#DwwwysYt%Q=;a)Y#NsTp&Fe6HP7!ZJeg@j)N-FT!Vc*_i3a=kN1z7*UuKU;{U#|A{4M{h{q{k^BSk}II$V^T z{An;9Nl}C;I_B@<&GJC+<=bQH`;!iM;(tSub!XYP@18Q7!R^I?ND7cP#=l?ahtb3v z)@9Lh)uYvl?)Szc_KX&YBAHod9}Ok1K9=e}RiiktzWSqWq%4{ocDXP z<%lk^FZ_o}lY4Djc@4EFJcnv$gCPumjtWphOlxsJFDowxRdO@`&e%f@Kv6ueTC*&{ zEcZkk3i5fGK+T4dHsW{G{XNFrE!K}q+>>3BbtLmg`0(xSR(}a*A(WLnAAU9u6h)KX zRv!Zm1K=-xM&RgT@$Q!d*$-FUo%&US%W6Os(@qfux@2yNKp8YDwe3? zMApB;2G;i}8;~K}<-7BH(pt7_E#c7?(e83TnJ{nnj%fRUK(zd?#}W&bPv5lrUViy@ zwU*}dG9c>eE}G96THYWNULHiJ)AM2Q@=IU3zr77vfmH3N0jq`&ARtWyvQKl2(MNhP2!*W+dh+sOfcWcka|$_S49M{zt^7IX1@r1Oz+}nKQ2>=A#S-Ja6K8xE`du7{F%Ks7+Vab{5FzqV7{KX0;i{JJ- zkn>SWp8)MhTH(RP(nbl<$p|#s8RaaQyq+vbbqi8YR2l?psRB2uMm1VFrIP32Q=4GV zJ@XZN_7}-08C}}^ue#4ENrOuP6R)47SPJtRo0a8KP|=WM}ap!@6O)rk_MD&&^;3;M+^I2`oCD! z>IzoBM6-t(=!Ykv8U?shR^S}Ir}&0hsy}@CM-Y}XoBYIpu}Qa!1Fc!mtQ%=cjjmbS zckV!KTw{OlZTo3!b(td(fhWhtS1+B`10MDtiS{SU3KA(8im{U{i!V=8CXNx;ROmOXs4%juO(!fDNe ze+K{3&3|g&7t{Bz5QlWe2qSF6Xa*O#IUo3mBJvB0P(@l{*~2J}#VBw##ZHpi#TT)n zUrgXR56^(4q{J8!fYGA{Cz}_3wI3caRt~=9M^}a9o$fB)jh+I;9BmdT8LtFSE5V#{ z>*`jU3m$CE&lk14qZy{2c>W`7yL> z)Gd{iVj$#M7;>#a{nTzBnEW$aPCTBj+23*9w$|YfcnMg>bU%3luJ;B>=}e8@ zR@1`*=}1JYpTW=ZHva(9F1d8MT7hN@0sgYa3~RfY-_wCIKF)h z>v~y99I4Pv1gq(75myrHjN69Q)xRGlP=)SHNqS$)TqBu0)(`!T;BreJzwDqu&s!s# zrw~yWXtkgHD^H*oQZ(U^L)2gq)43C=&zLfVjq_*WBNnHg3cFET0%Ip$H8HRn^oI4t zju|p+xG@^;YiU9G-sW^x0Au_q)*^!}_#eRo4-x$yzyrGb4=X%mb5PoD7X{>@(D?n} zq0W>?Q0dK1r>RjT?at$#wL70ti>WLfvoR4aE{-#J(I4oF2mNCiN~e1O-U6RwI$x0Y(+?R^P8*1dVU;cBq0CE)%;sivFUMWK zb_j=UXy$`d@}az#6ddo1yPg4}>FCCHKd&BmGT*vbSIp!Jzdi97Hu*2jBM#Wk=P|~j-;(Z zJ*i?9I66ZM={nFTl*UtuO7b696(9;5zj zw;5zZ44@Y{a$2PiHMeb1=QA+g1)Ck|XJP1_6*3fa9Un@V==}kq)-cciV*l!C6xOgf#_*-`)hXFI_x>6ADh@-Js|y zK0UiR?XUx1g|Dtf+6Duz@CBpFsYGOG{a$a)Q#x%d)8Pnro4w@qC!dC?~Qc|Jv#CVVr+~yeK=*jhrZ?;pv zp}Um{o2z1%;qIQ^;dW!42}s)=e$Q3$xSa05C0Wk7D8sf>AI!3oEXESv;hTNn9qGrwkDg;1CIAX?!JrJ zmk+j=Xg}|1Ns39`%*hY@MaytAD6AHi-PDL5QQ+qH$l_%TgjdH@LHve$vOaIdzNksk zqq?oJ1)0Nv8U9g4LAT_U!YSx7AE9rd(w3f8Unw8aYVz%sqG~d#t?NgL@Fe-S&n$oZ zU`?ZEl@VUYBkvH#Y3Y$xs9M=XJf_u%b$JD|ka}hmKY*g!@oE=;5|$`ZJ*}!d*%fSb z6CkWlU(%xEs**T&CSQCXez9M7KKos$h(EO>(O+!F-bB-Y-~3c{Sp&>#{%dTDTp9(}I5u+C(}t(=_BVB2YJsK^GLdeptL-medVZRRGT02y8`(Gi z%6VUy6RqevBL$)6H5SNX>N_1)ektS{jtuUZ;QifECLc^x(0&5z$T~lL;NF-WBH6!# zr`7Y)7Tw}zatnv0AIQx`pN6UReD+BDI~f9fh0<=3`|LbBL)Tk)&?g&-J`IC>vJL1o z_UGUv^%%QYbb5q)JIqQT?c{Zg#wsg9a``o^lLZ$1F6wbnQ(tX*0rg^s28CMZumv2W5&B0FHDnURV$<2{sX?m($GJt z;qhe!or{y17!zACZYeh~HrIwl%46n-JlJ33afv+=C-?vJgtmK*bX)@O@DXKBr^AFb ztSBhWJ=WxRr1hO|DH1X7;l(@E1qAN(o4G-5s*V^%kI2BQ@&uQ6%_Wk{AJ#~j`kP;J zA-BKN_?Mqxs_Qt@K^1P1W;_%4EZgI-?^+2n#>#IRZG0H#nEEW$h-9>}0$3{jNHY{d zh|SKAcELUMUz%qY@SX1RzmK;icthg_Lsx`lN7IgYq2n_vYg8HlkN1W;h5%;yUAi?% zN-iFD(YWmVkZKO(v06rU*=iC~D_Hu4VI{3TJYJm)+!AQ=bvPb7J|gBl5e@>ytog%` z$^||YTOJmTct`(ub~}yw#zv%#+T@|#SR*G(b<`#R7?5OO%gU0(&k#)6)onHy&V&k- z6vp#&zJBHA^AgvWpIYckzu=lby^*nE^&e