forked from ros-drivers/urg_node
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathhokuyo_ust10.urdf.xacro
87 lines (78 loc) · 3.05 KB
/
hokuyo_ust10.urdf.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="hokuyo_ust10_mount" params="prefix topic parent_link min_angle:=-2.35619 max_angle:=2.35619 *origin">
<xacro:macro name="hokuyo_ust10" params="frame:=laser topic:=scan sample_size:=720 update_rate:=50
min_angle:=${min_angle} max_angle:=${max_angle} min_range:=0.1 max_range:=30.0 robot_namespace:=/">
<link name="${frame}">
<inertial>
<mass value="1.1" />
<origin xyz="0 0 0" />
<inertia ixx="${0.0833333 * 1.1 * (0.102*0.102 + 0.152*0.152)}" ixy="0.0" ixz="0.0"
iyy="${0.0833333 * 1.1 * (0.105*0.105 + 0.152*0.152)}" iyz="0.0"
izz="${0.0833333 * 1.1 * (0.105*0.105 + 0.102*0.102)}" />
</inertial>
</link>
<gazebo reference="${frame}">
<turnGravityOff>true</turnGravityOff>
<sensor type="ray" name="${frame}">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>${update_rate}</update_rate>
<ray>
<scan>
<horizontal>
<samples>${sample_size}</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>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_laser" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>${robot_namespace}</namespace>
<remapping>~/out:=${topic}</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>${frame}</frame_name>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
<xacro:hokuyo_ust10 frame="${prefix}_laser" topic="${topic}"/>
<joint name="${prefix}_laser_mount_joint" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent_link}" />
<child link="${prefix}_laser_mount" />
</joint>
<link name="${prefix}_laser_mount">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<!-- Origin of this mesh is the base of the bracket. -->
<mesh filename="package://urg_node/meshes/hokuyo_ust10.stl" />
</geometry>
<material name="dark_grey" />
</visual>
</link>
<joint name="${prefix}_laser_joint" type="fixed">
<!-- This offset is from the base of the bracket to the LIDAR's focal point. -->
<origin xyz="0 0 0.0474" rpy="0 0 0" />
<parent link="${prefix}_laser_mount" />
<child link="${prefix}_laser" />
</joint>
<gazebo reference="${prefix}_laser_mount">
<material>Gazebo/DarkGrey</material>
</gazebo>
</xacro:macro>
</robot>