Skip to content

🛑 [Local Changes and version] #1

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

Open
wants to merge 1 commit into
base: kinetic-multi-devel
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
3 changes: 3 additions & 0 deletions urdf/all_sensors.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -77,5 +77,8 @@

<!-- Pointgrey Bumblebee -->
<xacro:include filename="$(find robotnik_sensors)/urdf/pointgrey_bumblebee2.urdf.xacro" />

<!-- velodyne VLP16 -->
<xacro:include filename="$(find robotnik_sensors)/urdf/vlp16.urdf.xacro" />

</robot>
155 changes: 155 additions & 0 deletions urdf/vlp16.urdf(bkup).xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
<?xml version="1.0"?>

<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />

<xacro:macro name="vlp16_model" params="name parent *origin">
<joint name="${name}_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${name}_frame"/>
</joint>

<link name="${name}_frame">
<xacro:inertial_sphere mass="0.8" diameter="0.1033" />
<visual>
<origin rpy="0 0 0" xyz="0 0 0.0018500"/>
<geometry>
<cylinder radius="0.0516" length="0.0717"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.0018500"/>
<geometry>
<cylinder radius="0.0516" length="0.0717"/>
</geometry>
</collision>
</link>
</xacro:macro>

<xacro:macro name="vlp16" params="name parent *origin ros_topic">
<xacro:vlp16_advanced_parameters name="${name}" parent="${parent}" ros_topic="${ros_topic}" update_rate="10" horizontal_samples="512" vertical_samples="8" min_range="0.45" max_range="100">
<xacro:insert_block name="origin" />
</xacro:vlp16_advanced_parameters>
</xacro:macro>

<xacro:macro name="vlp16_advanced_parameters" params="name parent *origin ros_topic update_rate horizontal_samples vertical_samples min_range max_range">

<xacro:vlp16_model name="${name}" parent="${parent}">
<xacro:insert_block name="origin" />
</xacro:vlp16_model>

<gazebo reference="${name}_frame">
<!-- <sensor type="ray" name="${name}">
<always_on>true</always_on>
<update_rate>${update_rate}</update_rate>
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>${ray_count}</samples>
<resolution>1</resolution>
<min_angle>${min_angle * M_PI/180}</min_angle>
<max_angle>${max_angle * M_PI/180}</max_angle>
</horizontal>
</scan>
<range>
<min>0.2</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.004</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_${name}_controller" filename="libgazebo_ros_laser.so">
<topicName>${ros_topic}</topicName>
<frameName>${name}_frame</frameName>
</plugin>
</sensor>-->



<sensor type="ray" name="${name}-VLP16">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>${update_rate}</update_rate>
<ray>
<scan>
<horizontal>
<samples>${horizontal_samples}</samples>
<resolution>1</resolution>
<min_angle>-${M_PI}</min_angle>
<max_angle> ${M_PI}</max_angle>
</horizontal>
<vertical>
<samples>${vertical_samples}</samples>
<resolution>1</resolution>
<min_angle>-${15.0*M_PI/180.0}</min_angle>
<max_angle> ${15.0*M_PI/180.0}</max_angle>
</vertical>
</scan>
<range>
<min>${min_range}</min>
<max>${max_range}</max>
<resolution>0.001</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
<topicName>${ros_topic}</topicName>
<frameName>${name}_frame</frameName>
<min_range>${min_range}</min_range>
<max_range>${max_range}</max_range>
<gaussianNoise>0.008</gaussianNoise>
</plugin>
</sensor>
</gazebo>
</xacro:macro>

<xacro:macro name="vlp16_gpu" params="name parent *origin ros_topic update_rate ray_count min_angle max_angle">
<xacro:vlp16_model name="${name}" parent="${parent}">
<xacro:insert_block name="origin" />
</xacro:vlp16_model>

<gazebo reference="${name}_frame">
<sensor type="gpu_ray" name="${name}">
<update_rate>${update_rate}</update_rate>
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>${ray_count}</samples>
<resolution>1</resolution>
<min_angle>${min_angle * M_PI/180}</min_angle>
<max_angle>${max_angle * M_PI/180}</max_angle>
</horizontal>
</scan>
<range>
<min>0.2</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.004</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_${name}_controller" filename="libgazebo_ros_gpu_laser.so">
<topicName>${ros_topic}</topicName>
<frameName>${name}_frame</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>

177 changes: 177 additions & 0 deletions urdf/vlp16.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,177 @@
<?xml version="1.0"?>

<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />

<!--xacro:macro name="vlp16_model" params="name parent *origin">
<joint name="${name}_joint" type="fixed"-->
<xacro:macro name="sensor_vlp16" params="prefix parent prefix_topic:='front_laser' *origin">

<link name="${prefix}_link">
</link>
<joint name="${prefix}_joint" type="fixed">
<parent link="${parent}"/>
<child link="${prefix}_link"/>
<xacro:insert_block name="origin" />
</joint>

<joint name="${prefix}_base_joint" type="fixed">
<!--origin xyz="0.00 0 -0.05" rpy="0 0 0"/-->
<origin xyz="0 0 0.004" rpy="0 0 0"/>
<parent link="${prefix}_link"/>
<child link="${prefix}_base_link"/>

</joint>

<link name="${prefix}_base_link">
<!--xacro:inertial_sphere mass="0.8" diameter="0.1033" /-->

<collision>
<origin rpy="0 0 0" xyz="0 0 0.0018500"/>
<geometry>
<cylinder radius="0.0516" length="0.0717"/>
</geometry>
</collision>

<visual>
<origin rpy="0 0 0" xyz="0 0 0.0018500"/>
<geometry>
<cylinder radius="0.0516" length="0.0717"/>
</geometry>
</visual>

<inertial>
<mass value="0.8" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="0.08" ixy="0" ixz="0" iyy="0.08" iyz="0" izz="0.08" />
</inertial>

</link>
</xacro:macro>

<xacro:macro name="vlp16" params="name parent *origin ros_topic">
<xacro:vlp16_advanced_parameters name="${name}" parent="${parent}" ros_topic="${ros_topic}" update_rate="10" horizontal_samples="512" vertical_samples="8" min_range="0.45" max_range="100">
<xacro:insert_block name="origin" />
</xacro:vlp16_advanced_parameters>
</xacro:macro>

<xacro:macro name="vlp16_advanced_parameters" params="name parent *origin ros_topic update_rate horizontal_samples vertical_samples min_range max_range">

<xacro:vlp16_model name="${name}" parent="${parent}">
<xacro:insert_block name="origin" />
</xacro:vlp16_model>

<gazebo reference="${name}_frame">
<!-- <sensor type="ray" name="${name}">
<always_on>true</always_on>
<update_rate>${update_rate}</update_rate>
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>${ray_count}</samples>
<resolution>1</resolution>
<min_angle>${min_angle * M_PI/180}</min_angle>
<max_angle>${max_angle * M_PI/180}</max_angle>
</horizontal>
</scan>
<range>
<min>0.2</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.004</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_${name}_controller" filename="libgazebo_ros_laser.so">
<topicName>${ros_topic}</topicName>
<frameName>${name}_frame</frameName>
</plugin>
</sensor>-->



<sensor type="ray" name="${name}-VLP16">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>${update_rate}</update_rate>
<ray>
<scan>
<horizontal>
<samples>${horizontal_samples}</samples>
<resolution>1</resolution>
<min_angle>-${M_PI}</min_angle>
<max_angle> ${M_PI}</max_angle>
</horizontal>
<vertical>
<samples>${vertical_samples}</samples>
<resolution>1</resolution>
<min_angle>-${15.0*M_PI/180.0}</min_angle>
<max_angle> ${15.0*M_PI/180.0}</max_angle>
</vertical>
</scan>
<range>
<min>${min_range}</min>
<max>${max_range}</max>
<resolution>0.001</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_laser_controller" filename="libgazebo_ros_velodyne_laser.so">
<topicName>${ros_topic}</topicName>
<frameName>${name}_frame</frameName>
<min_range>${min_range}</min_range>
<max_range>${max_range}</max_range>
<gaussianNoise>0.008</gaussianNoise>
</plugin>
</sensor>
</gazebo>
</xacro:macro>

<xacro:macro name="vlp16_gpu" params="name parent *origin ros_topic update_rate ray_count min_angle max_angle">
<xacro:vlp16_model name="${name}" parent="${parent}">
<xacro:insert_block name="origin" />
</xacro:vlp16_model>

<gazebo reference="${name}_frame">
<sensor type="gpu_ray" name="${name}">
<update_rate>${update_rate}</update_rate>
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>${ray_count}</samples>
<resolution>1</resolution>
<min_angle>${min_angle * M_PI/180}</min_angle>
<max_angle>${max_angle * M_PI/180}</max_angle>
</horizontal>
</scan>
<range>
<min>0.2</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.004</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_${name}_controller" filename="libgazebo_ros_gpu_laser.so">
<topicName>${ros_topic}</topicName>
<frameName>${name}_frame</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>