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

Updated parameters for a correct vlp16 configuration #12

Open
wants to merge 1 commit into
base: kinetic-devel
Choose a base branch
from
Open
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
18 changes: 10 additions & 8 deletions urdf/velodyne_vlp16.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
<?xml version="1.0"?>
<robot name="sensor_velodyne_vlp16" xmlns:xacro="http://wiki.ros.org/xacro">

<xacro:macro name="sensor_velodyne_vlp16" params="prefix parent prefix_topic:='velodyne' *origin range_min range_max gpu:=^|true">
<xacro:property name="M_PI" value="3.1415926535897931" />

<xacro:macro name="sensor_velodyne_vlp16" params="prefix parent prefix_topic:='velodyne' *origin range_min range_max fps:=15 hsamples:=300 vsamples:=100 hfov:=360.0 vfov:=30.0 gpu:=^|true">
Copy link
Contributor

@alex-arnal alex-arnal Jan 5, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would also add range_min and range_max. I have tested changes and it works correctly, I should set the range_min to 0.06 as minimum (less distance causes it to detect itself). From datasheet, range_max should be 100.0.

Suggested change
<xacro:macro name="sensor_velodyne_vlp16" params="prefix parent prefix_topic:='velodyne' *origin range_min range_max fps:=15 hsamples:=300 vsamples:=100 hfov:=360.0 vfov:=30.0 gpu:=^|true">
<xacro:macro name="sensor_velodyne_vlp16" params="prefix parent prefix_topic:='velodyne' *origin range_min:=0.06 range_max:=100.0 fps:=15 hsamples:=300 vsamples:=100 hfov:=360.0 vfov:=30.0 gpu:=^|true">

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

According to the datasheet, range_min should be set to 0.2m. However, after testing a few different units of the real sensor, this value tends to be around 0.38.


<joint name="${prefix}_base_joint" type="fixed">
<xacro:insert_block name="origin" />
Expand Down Expand Up @@ -61,20 +63,20 @@
<sensor type="${ray_type}" name="${prefix}_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>15</update_rate>
<update_rate>${fps}</update_rate>
<ray>
<scan>
<horizontal>
<samples>300</samples>
<samples>${hsamples}</samples>
<resolution>1.0</resolution>
<min_angle>-1.83591184</min_angle>
<max_angle>1.83591184</max_angle>
<min_angle>-${hfov/2.0*M_PI/180.0}</min_angle>
<max_angle>${hfov/2.0*M_PI/180.0}</max_angle>
</horizontal>
<vertical>
<samples>100</samples>
<samples>${vsamples}</samples>
<resolution>1.0</resolution>
<min_angle>-0.610865238</min_angle>
<max_angle>1.83591184</max_angle>
<min_angle>-${vfov/2.0*M_PI/180.0}</min_angle>
<max_angle>${vfov/2.0*M_PI/180.0}</max_angle>
</vertical>
</scan>
<range>
Expand Down