Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Robotika Kloubak config 1 - fix cameras, lidar and symmetry #857

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
40 changes: 20 additions & 20 deletions submitted_models/robotika_kloubak_sensor_config_1/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,7 @@
https://www.sick.com/ch/en/detection-and-ranging-solutions/2d-lidar-sensors/tim5xx/tim581-2050101/p/p619344
-->
<sensor name="lidar_front" type="gpu_lidar">
<pose>0.04 0 0.235 0 0 0</pose>
<pose>0.08 0 0.25 0 0 0</pose>
<update_rate>15</update_rate>
<lidar>
<scan>
Expand Down Expand Up @@ -284,16 +284,16 @@
<always_on>1</always_on>
<update_rate>10</update_rate>
<camera name="camera_front">
<horizontal_fov>3.072</horizontal_fov>
<horizontal_fov>2.27</horizontal_fov>
<lens>
<intrinsics>
<!-- fx = fy = width / ( 2 * tan (hfov / 2 ) ) -->
<fx>17.8229</fx>
<fy>17.8229</fy>
<fx>149.01</fx>
<fy>149.01</fy>
<!-- cx = ( width - 1 ) / 2 -->
<cx>511.5</cx>
<cx>339.5</cx>
<!-- cy = ( height - 1 ) / 2 -->
<cy>383.5</cy>
<cy>179.5</cy>
<s>0</s>
</intrinsics>
</lens>
Expand All @@ -306,8 +306,8 @@
<center>0.5 0.5</center>
</distortion>
<image>
<width>1024</width>
<height>768</height>
<width>640</width>
<height>360</height>
<format>R8G8B8</format>
</image>
<clip>
Expand Down Expand Up @@ -388,7 +388,7 @@


<link name='chassis_back'>
<pose>-0.7 0 0.2 0 0 0</pose>
<pose>-0.671 0 0.2 0 0 0</pose>
<inertial>
<pose>0.025 0 0.116 0 0 0</pose>
<mass>7.2</mass>
Expand Down Expand Up @@ -582,7 +582,7 @@
https://www.sick.com/ch/en/detection-and-ranging-solutions/2d-lidar-sensors/tim5xx/tim581-2050101/p/p619344
-->
<sensor name="lidar_back" type="gpu_lidar">
<pose>-0.06 0 0.295 0 0 3.1415927</pose>
<pose>-0.08 0 0.345 0 0 3.1415927</pose>
<update_rate>15</update_rate>
<lidar>
<scan>
Expand Down Expand Up @@ -615,16 +615,16 @@
<always_on>1</always_on>
<update_rate>10</update_rate>
<camera name="camera_back">
<horizontal_fov>3.072</horizontal_fov>
<horizontal_fov>2.27</horizontal_fov>
<lens>
<intrinsics>
<!-- fx = fy = width / ( 2 * tan (hfov / 2 ) ) -->
<fx>17.8229</fx>
<fy>17.8229</fy>
<fx>149.01</fx>
<fy>149.01</fy>
<!-- cx = ( width - 1 ) / 2 -->
<cx>511.5</cx>
<cx>339.5</cx>
<!-- cy = ( height - 1 ) / 2 -->
<cy>383.5</cy>
<cy>179.5</cy>
<s>0</s>
</intrinsics>
</lens>
Expand All @@ -637,8 +637,8 @@
<center>0.5 0.5</center>
</distortion>
<image>
<width>1024</width>
<height>768</height>
<width>640</width>
<height>360</height>
<format>R8G8B8</format>
</image>
<clip>
Expand Down Expand Up @@ -719,7 +719,7 @@


<link name='axle_back'>
<pose>-0.729 0 0.183 0 0 0</pose>
<pose>-0.7 0 0.183 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.8</mass>
Expand Down Expand Up @@ -839,7 +839,7 @@


<link name="rear_left_wheel">
<pose>-0.729 0.25 0.172 0 0 0</pose>
<pose>-0.7 0.25 0.172 0 0 0</pose>
<inertial>
<mass>3.5</mass>
<inertia>
Expand Down Expand Up @@ -882,7 +882,7 @@
</link>

<link name="rear_right_wheel">
<pose>-0.729 -0.25 0.172 0 0 0</pose>
<pose>-0.7 -0.25 0.172 0 0 0</pose>
<inertial>
<mass>3.5</mass>
<inertia>
Expand Down
144 changes: 30 additions & 114 deletions submitted_models/robotika_kloubak_sensor_config_1/urdf/model.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -55,39 +55,9 @@
</geometry>
</collision>
<visual name='visual_chassis'>
<origin xyz='0 0 0.2' rpy='0 -0 0'/>
<origin xyz='-0.34 0 0.03' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/chassis_front.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_light'>
<origin xyz='0.09 0 0.36' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/light.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_lidar_front'>
<origin xyz='0.015 0 0.38' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/lidar.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_camera_front'>
<origin xyz='0.114 0 0.36' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/camera.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_depth_camera_shield_front'>
<origin xyz='0.15 0 0.31' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/depth_camera_shield.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_depth_camera_front'>
<origin xyz='0.15 0 0.313' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/depth_camera.dae' scale='1 1 1'/>
<mesh filename='meshes/k2.dae' scale='1 1 1'/>
</geometry>
</visual>
</link>
Expand All @@ -105,13 +75,13 @@
</sensor>
<sensor name='lidar_front' update_rate='15'>
<parent link='chassis_front'/>
<origin xyz='0.04 0 0.235' rpy='0 -0 0'/>
<origin xyz='0.08 0 0.25' rpy='0 -0 0'/>
</sensor>
<sensor name='camera_front' update_rate='10'>
<parent link='chassis_front'/>
<origin xyz='0.15 0 0.192' rpy='0 -0 0'/>
<origin xyz='0.155 -0.0075 0.193' rpy='0 -0 0'/>
<camera>
<image width='1024' height='768' format='R8G8B8' hfov='3.072' near='0.01' far='300' />
<image width='640' height='360' format='R8G8B8' hfov='2.27' near='0.01' far='300' />
</camera>
</sensor>
<sensor name='depth_camera_front' update_rate='20'>
Expand Down Expand Up @@ -152,39 +122,9 @@
</geometry>
</collision>
<visual name='visual_chassis'>
<origin xyz='-0.35 0 -0.02' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/chassis_back.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_light'>
<origin xyz='-0.46 0 0.2' rpy='0 -0 -3.14159'/>
<geometry>
<mesh filename='meshes/light.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_lidar_back'>
<origin xyz='-0.385 0 0.22' rpy='0 -0 -3.14159'/>
<geometry>
<mesh filename='meshes/lidar.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_camera_back'>
<origin xyz='-0.484 0 0.2' rpy='0 -0 -3.14159'/>
<geometry>
<mesh filename='meshes/camera.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_depth_camera_shield_back'>
<origin xyz='-0.55 0 0.09' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/depth_camera_shield.dae' scale='1 1 1'/>
</geometry>
</visual>
<visual name='visual_depth_camera_back'>
<origin xyz='-0.55 0 0.093' rpy='0 -0 0'/>
<origin xyz='-0.01 0 -0.19' rpy='0 -0 0'/>
<geometry>
<mesh filename='meshes/depth_camera.dae' scale='1 1 1'/>
<mesh filename='meshes/k2.dae' scale='1 1 1'/>
</geometry>
</visual>
</link>
Expand All @@ -198,13 +138,13 @@
</sensor>
<sensor name='lidar_back' update_rate='15'>
<parent link='chassis_back'/>
<origin xyz='-0.06 0 0.295' rpy='0 -0 -3.14159'/>
<origin xyz='-0.08 0 0.345' rpy='0 -0 -3.14159'/>
</sensor>
<sensor name='camera_back' update_rate='10'>
<parent link='chassis_back'/>
<origin xyz='-0.17 0 0.252' rpy='0 -0 -3.14159'/>
<origin xyz='-0.185 -0.001 0.269' rpy='0 -0 -3.14159'/>
<camera>
<image width='1024' height='768' format='R8G8B8' hfov='3.072' near='0.01' far='300' />
<image width='640' height='360' format='R8G8B8' hfov='2.27' near='0.01' far='300' />
</camera>
</sensor>
<sensor name='depth_camera_back' update_rate='20'>
Expand All @@ -227,9 +167,9 @@
</geometry>
</collision>
<visual name='visual'>
<origin xyz='0 0 0' rpy='0 -0 0'/>
<origin xyz='-0.0132 0 0' rpy='0 -0 0'/>
<geometry>
<box size='0.04 0.42 0.04'/>
<mesh filename='meshes/k2.dae' scale='1 1 1'/>
</geometry>
</visual>
</link>
Expand All @@ -242,19 +182,13 @@
<collision name='collision'>
<origin xyz='0 0 0' rpy='-1.5708 0 0'/>
<geometry>
<cylinder radius='0.15' length='0.08'/>
<cylinder radius='0.147' length='0.08'/>
</geometry>
</collision>
<visual name='tire_visual'>
<origin xyz='0 0 0' rpy='1.5708 -0 0'/>
<geometry>
<mesh filename='meshes/wheel_left.dae' scale='1.431 1.431 1.569'/>
</geometry>
</visual>
<visual name='motor_visual'>
<origin xyz='0 -0.02 0' rpy='1.5708 -0 0'/>
<origin xyz='0 0 0' rpy='0 -0 0'/>
<geometry>
<cylinder radius='0.08' length='0.04'/>
<mesh filename='meshes/k2.dae' scale='1 1 1'/>
</geometry>
</visual>
</link>
Expand All @@ -267,19 +201,13 @@
<collision name='collision'>
<origin xyz='0 0 0' rpy='1.5708 -0 0'/>
<geometry>
<cylinder radius='0.15' length='0.08'/>
<cylinder radius='0.147' length='0.08'/>
</geometry>
</collision>
<visual name='tire_visual'>
<origin xyz='0 0 0' rpy='1.5708 -0 0'/>
<geometry>
<mesh filename='meshes/wheel_right.dae' scale='1.431 1.431 1.569'/>
</geometry>
</visual>
<visual name='motor_visual'>
<origin xyz='0 0.02 0' rpy='1.5708 -0 0'/>
<origin xyz='0 0 0' rpy='0 -0 0'/>
<geometry>
<cylinder radius='0.08' length='0.04'/>
<mesh filename='meshes/k2.dae' scale='1 1 1'/>
</geometry>
</visual>
</link>
Expand All @@ -292,19 +220,13 @@
<collision name='collision'>
<origin xyz='0 0 0' rpy='-1.5708 0 0'/>
<geometry>
<cylinder radius='0.15' length='0.08'/>
<cylinder radius='0.147' length='0.08'/>
</geometry>
</collision>
<visual name='tire_visual'>
<origin xyz='0 0 0' rpy='1.5708 -0 0'/>
<geometry>
<mesh filename='meshes/wheel_left.dae' scale='1.431 1.431 1.569'/>
</geometry>
</visual>
<visual name='motor_visual'>
<origin xyz='0 -0.02 0' rpy='1.5708 -0 0'/>
<origin xyz='0 0 0' rpy='0 -0 0'/>
<geometry>
<cylinder radius='0.08' length='0.04'/>
<mesh filename='meshes/k2.dae' scale='1 1 1'/>
</geometry>
</visual>
</link>
Expand All @@ -317,59 +239,53 @@
<collision name='collision'>
<origin xyz='0 0 0' rpy='1.5708 -0 0'/>
<geometry>
<cylinder radius='0.15' length='0.08'/>
<cylinder radius='0.147' length='0.08'/>
</geometry>
</collision>
<visual name='tire_visual'>
<origin xyz='0 0 0' rpy='1.5708 -0 0'/>
<geometry>
<mesh filename='meshes/wheel_right.dae' scale='1.431 1.431 1.569'/>
</geometry>
</visual>
<visual name='motor_visual'>
<origin xyz='0 0.02 0' rpy='1.5708 -0 0'/>
<origin xyz='0 0 0' rpy='0 -0 0'/>
<geometry>
<cylinder radius='0.08' length='0.04'/>
<mesh filename='meshes/k2.dae' scale='1 1 1'/>
</geometry>
</visual>
</link>
<joint name='front_left_wheel_joint' type='revolute'>
<origin xyz='0 0.25 0.18' rpy='0 -0 0'/>
<origin xyz='0 0.25 0.172' rpy='0 -0 0'/>
<parent link='chassis_front'/>
<child link='front_left_wheel'/>
<axis xyz='0 1 0'/>
<limit lower='-1.79769e+308' upper='1.79769e+308' effort='10' velocity='13.333'/>
</joint>
<joint name='front_right_wheel_joint' type='revolute'>
<origin xyz='0 -0.25 0.18' rpy='0 -0 0'/>
<origin xyz='0 -0.25 0.172' rpy='0 -0 0'/>
<parent link='chassis_front'/>
<child link='front_right_wheel'/>
<axis xyz='0 1 0'/>
<limit lower='-1.79769e+308' upper='1.79769e+308' effort='10' velocity='13.333'/>
</joint>
<joint name='rear_left_wheel_joint' type='revolute'>
<origin xyz='-0.7 0.25 0.18' rpy='0 -0 0'/>
<origin xyz='-0.7 0.25 0.172' rpy='0 -0 0'/>
<parent link='axle_back'/>
<child link='rear_left_wheel'/>
<axis xyz='0 1 0'/>
<limit lower='-1.79769e+308' upper='1.79769e+308' effort='10' velocity='13.333'/>
</joint>
<joint name='rear_right_wheel_joint' type='revolute'>
<origin xyz='-0.7 -0.25 0.18' rpy='0 -0 0'/>
<origin xyz='-0.7 -0.25 0.172' rpy='0 -0 0'/>
<parent link='axle_back'/>
<child link='rear_right_wheel'/>
<axis xyz='0 1 0'/>
<limit lower='-1.79769e+308' upper='1.79769e+308' effort='10' velocity='13.333'/>
</joint>
<joint name='main_joint' type='revolute'>
<origin xyz='-0.35 0 0.22' rpy='0 -0 0'/>
<origin xyz='-0.321 0 0.22' rpy='0 -0 0'/>
<parent link='chassis_front'/>
<child link='chassis_back'/>
<axis xyz='0 0 1'/>
<limit lower='-1.222' upper='1.222' effort='-1' velocity='-1'/>
</joint>
<joint name='axle_joint' type='revolute'>
<origin xyz='-0.7 0 0.18' rpy='0 -0 0'/>
<origin xyz='-0.7 0 0.183' rpy='0 -0 0'/>
<parent link='chassis_back'/>
<child link='axle_back'/>
<axis xyz='1 0 0'/>
Expand Down
Loading