Skip to content

Commit

Permalink
Merge branch 'master' into master
Browse files Browse the repository at this point in the history
  • Loading branch information
Khaled Hazime authored Aug 13, 2019
2 parents 1b1e86a + 6cd3fcb commit bc20851
Show file tree
Hide file tree
Showing 5 changed files with 371 additions and 3 deletions.
4 changes: 3 additions & 1 deletion butia_navigation_description/config/sick_lms_1xx.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
<node pkg="tf" type="static_transform_publisher" name="sick_broadcaster" args="0.108 0 0.68 0 0 0 1 base_link sick_link 100" />

<!-- robot_description and robot_state_publisher hier evtl. einbauen -->

<node name="sick_lms_1xx" pkg="sick_scan" type="sick_generic_caller" respawn="false" output="screen">

<!-- default values: -->
Expand All @@ -22,7 +23,9 @@
<param name="max_ang" type="double" value="1.658" />
-->


<param name="frame_id" type="str" value="sick_link" />

<param name="use_binary_protocol" type="bool" value="False" />
<param name="scanner_type" type="string" value="sick_lms_1xx"/>
<param name="range_max" type="double" value="25.0" />
Expand All @@ -31,5 +34,4 @@
<param name="timelimit" type="int" value="5" />


</node>
</launch>
Binary file not shown.
205 changes: 205 additions & 0 deletions butia_navigation_description/meshes/sensors/LMS1xx_small.dae

Large diffs are not rendered by default.

77 changes: 75 additions & 2 deletions butia_navigation_description/urdf/pioneer3at.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -576,7 +576,8 @@
</link>
<joint name="hokuyo_joint" type="fixed">
<!--<axis xyz="0 0 1" />-->
<origin rpy="3.1415 0 0" xyz="0.08 0 -0.03"/>

<origin rpy="3.1415 0 0" xyz="0.08 0 -0.03"/>
<parent link="base_link"/>
<child link="hokuyo_link"/>
</joint>
Expand Down Expand Up @@ -614,10 +615,82 @@
</noise>
</ray>
<plugin filename="libgazebo_ros_laser.so" name="gazebo_ros_head_hokuyo_controller">
<topicName>scan</topicName>
<topicName>scan2</topicName>
<frameName>hokuyo_link</frameName>
</plugin>
</sensor>
</gazebo>
<link name="sick_mount_link">
<visual>
<geometry>
<mesh filename="package://butia_navigation_description/meshes/sensors/LMS1xx_small.dae" />
</geometry>
<material name="blue" >
<color rgba="0 0 1 1" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://butia_navigation_description/meshes/sensors/LMS1xx_collision.stl" />
</geometry>
</collision>
<inertial>
<mass value="1.1" />
<origin xyz="0.052811 0 -0.008195" />
<inertia ixx="${0.0833333 * mass * (width * width + height * height)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * mass * (length * length + height * height)}" iyz="0.0"
izz="${0.0833333 * mass * (length * length + width * width)}" />
</inertial>
</link>
<joint name="sick_mount_joint" type="fixed">
<parent link="base_link" />
<child link="sick_mount_link" />
<origin rpy="0 0 0" xyz="0.108 0 0.28"/>
</joint>
<joint name="sick_joint" type="fixed">
<parent link="sick_mount_link" />
<child link="sick_laser" />
<origin rpy="0 0 0" xyz="0.0549 0 0.0367"/>
</joint>

<link name="sick_laser">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.000001" ixy="0.0" ixz="0.0"
iyy="0.000001" iyz="0.0" izz="0.000001" />
</inertial>
</link>
<gazebo reference="sick_link">
<material value="Gazebo/Blue" />
<sensor type="ray" name="sick">
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<ray>
<scan>
<horizontal>
<samples>540</samples>
<resolution>1</resolution>
<min_angle>-2.357</min_angle>
<max_angle>2.357</max_angle>
</horizontal>
</scan>
<range>
<min>0.5</min>
<max>20.0</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="gazebo_ros_sick_controller" filename="libgazebo_ros_laser.so">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<topicName>scan</topicName>
<frameName>sick_link</frameName>
</plugin>
</sensor>
</gazebo>
</robot>

88 changes: 88 additions & 0 deletions butia_navigation_description/urdf/sick_lms1xx.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
<?xml version="1.0"?>
<robot xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="sick_lms_1xx" params="name ros_topic">
<xacro:sick_lms_1 name="${name}" ros_topic="${ros_topic}"
length="0.105636" width="0.102301" height="0.161782" mass="1.1" x_offset="0.052811" z_offset="-0.008195"
min_range="0.5" max_range="20.0"/>
</xacro:macro>

<xacro:macro name="sick_lms_1" params="name ros_topic length width height mass x_offset z_offset min_range max_range">
<link name="${name}_mount_link">
<visual>
<geometry>
<mesh filename="package://sick_scan/meshes/LMS1xx_small.dae" />
</geometry>
<material name="blue" >
<color rgba="0 0 1 1" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="package://sick_scan/meshes/LMS1xx_collision.stl" />
</geometry>
</collision>
<inertial>
<mass value="${mass}" />
<origin xyz="${x_offset} 0 ${z_offset}" />
<inertia ixx="${0.0833333 * mass * (width * width + height * height)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * mass * (length * length + height * height)}" iyz="0.0"
izz="${0.0833333 * mass * (length * length + width * width)}" />
</inertial>
</link>

<joint name="${name}_joint" type="fixed">
<parent link="${name}_mount_link" />
<child link="${name}_laser" />
<origin rpy="0 0 0" xyz="0.0549 0 0.0367"/>
</joint>

<link name="${name}_laser">
<inertial>
<mass value="0.001" />
<origin xyz="0 0 0" />
<inertia ixx="0.000001" ixy="0.0" ixz="0.0"
iyy="0.000001" iyz="0.0" izz="0.000001" />
</inertial>
</link>
<xacro:sick_lms_1_laser_gazebo_v0 name="${name}" link="${name}_laser" ros_topic="${ros_topic}" update_rate="15.0" min_angle="-2.357" max_angle="2.357" min_range="${min_range}" max_range="${max_range}"/>
</xacro:macro>


<xacro:macro name="sick_lms_1_laser_gazebo_v0" params="name link ros_topic update_rate min_angle max_angle min_range max_range">
<gazebo reference="${link}">
<material value="Gazebo/Blue" />
<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>540</samples>
<resolution>1</resolution>
<min_angle>${min_angle}</min_angle>
<max_angle>${max_angle}</max_angle>
</horizontal>
</scan>
<range>
<min>${min_range}</min>
<max>${max_range}</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="gazebo_ros_${name}_controller" filename="libgazebo_ros_laser.so">
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>true</alwaysOn>
<updateRate>${update_rate}</updateRate>
<topicName>${ros_topic}</topicName>
<frameName>${link}</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>

0 comments on commit bc20851

Please sign in to comment.