Skip to content

Commit

Permalink
Merge pull request #8 from LCAS/sim_fix
Browse files Browse the repository at this point in the history
adjusted simulated camera and laser parameters
  • Loading branch information
gcielniak authored Nov 21, 2023
2 parents f9af7f7 + 0fb93aa commit c6acf0e
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 14 deletions.
25 changes: 12 additions & 13 deletions src/limo_description/urdf/limo_four_diff.gazebo
Original file line number Diff line number Diff line change
Expand Up @@ -101,10 +101,12 @@
<ray>
<scan>
<horizontal>
<samples>375</samples> <!-- 0.96 deg @ 8Hz so 360/0.96=375 samples -->
<samples>292</samples> <!-- to cover 4 rad @ 0.7826 deg -->
<!-- 0.96 deg @ 8Hz so 360/0.96=375 samples -->
<!-- real sensor: 460 samples @0.78260869565 deg -->
<resolution>1.000000</resolution>
<min_angle>-3.14159</min_angle>
<max_angle>3.14159</max_angle>
<min_angle>-2.0</min_angle>
<max_angle>2.0</max_angle>
</horizontal>
</scan>
<range>
Expand Down Expand Up @@ -192,18 +194,15 @@
</gazebo>
<gazebo reference="depth_camera_link">
<sensor name="sensor_camera" type="depth">
<!-- <pose>0.0 0.0 0.0 0.0 0.0 0.0</pose> -->
<always_on>0</always_on>
<update_rate>1</update_rate>
<camera name="limo_camera">
<!-- <distortion>
<k1>0.1</k1>
<k2>0.2</k2>
<k3>0.3</k3>
<p1>0.4</p1>
<p2>0.5</p2>
<center>0.5 0.5</center>
</distortion> -->
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
</camera>

<plugin name="gazebo_ros_depth_camera_sensor" filename="libgazebo_ros_camera.so">
Expand All @@ -216,7 +215,7 @@
<remapping>limo_camera/points:=limo_camera/camera_points</remapping>
</ros>
<camera_name>depth_camera_link</camera_name>
<frame_name>depth_camera_link</frame_name>
<frame_name>depth_link</frame_name>
<hack_baseline>0.07</hack_baseline>
<min_depth>0.001</min_depth>

Expand Down
1 change: 0 additions & 1 deletion src/limo_description/urdf/limo_gazebo.gazebo
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,6 @@
<depthImageCameraInfoTopicName>/limo/depth/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>/limo/depth/points</pointCloudTopicName>
<frameName>depth_link</frameName>
<cameraname>depth_camera_link</cameraname>

<pointCloudCutoff>0.5</pointCloudCutoff>
<pointCloudCutoffMax>3.0</pointCloudCutoffMax>
Expand Down

0 comments on commit c6acf0e

Please sign in to comment.