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

Feature/rplidar a2 urdf #29

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
92 changes: 92 additions & 0 deletions urdf/rplidar.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="rplidar_a2" params="name ros_topic min_angle:=-3.142 max_angle:=3.142 min_range:=0.15 max_range:=6">
<xacro:laser name="${name}" ros_topic="${ros_topic}"
length="0.07250" width="0.07250" height="0.04080" mass="0.250" z_offset="0.03080"
update_rate="10.0" samples="400" resolution="0.9"
min_range="${min_range}" max_range="${max_range}"
min_angle="${min_angle}" max_angle="${max_angle}"
mesh="package://rplidar_ros/urdf/stl/rplidar_a2_simple.stl" />
</xacro:macro>

<xacro:macro name="laser" params="name ros_topic length width height mass z_offset update_rate samples resolution min_angle max_angle min_range max_range mesh">
<!-- z_offset: distance between base plate and laser center (= center of mesh) -->
<link name="${name}_mount_link">
<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>

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

<link name="${name}">
<visual>
<geometry>
<mesh filename="${mesh}" />
</geometry>
<material name="red" >
<color rgba="1 0 0 1" />
</material>
</visual>
<collision>
<geometry>
<mesh filename="${mesh}" />
</geometry>
</collision>
<inertial>
<mass value="${mass}" />
<origin xyz="0 0 -0.026" />
<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>
<xacro:laser_gazebo_v1 name="${name}" link="${name}" ros_topic="${ros_topic}"
update_rate="${update_rate}" samples="${samples}" resolution="${resolution}"
min_angle="${min_angle}" max_angle="${max_angle}"
min_range="${min_range}" max_range="${max_range}"/>
</xacro:macro>


<xacro:macro name="laser_gazebo_v1" params="name link ros_topic update_rate samples resolution min_angle max_angle min_range max_range">
<gazebo reference="${link}">
<material value="Gazebo/Red" />
<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>${samples}</samples>
<resolution>${resolution}</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>
8 changes: 8 additions & 0 deletions urdf/rplidar_A2.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="rplidar">

<xacro:include filename="$(find rplidar_ros)/urdf/rplidar.urdf.xacro" />

<xacro:rplidar_a2 name="rplidar_laser" ros_topic="scan" />
</robot>
Binary file added urdf/stl/rplidar_a2_simple.stl
Binary file not shown.