This repository has been archived by the owner on Jun 14, 2023. It is now read-only.
forked from stm32f303ret6/livox_laser_simulation_RO2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmid40.xacro
88 lines (77 loc) · 2.67 KB
/
mid40.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" encoding="UTF-8"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.14159"/>
<xacro:property name="laser_min_range" value="0.1"/>
<xacro:property name="laser_max_range" value="200.0"/>
<xacro:property name="horizontal_fov" value="81.7"/>
<xacro:property name="vertical_fov" value="25.1"/>
<xacro:property name="ros_topic" value="scan"/>
<xacro:property name="samples" value="24000"/>
<xacro:property name="mass" value="0.4" />
<xacro:property name="length" value="0.1" />
<xacro:property name="width" value="0.06" />
<xacro:property name="height" value="0.06" />
<xacro:macro name="box_inertia" params="m w h d">
<inertial>
<origin xyz="0 0 0" rpy="${pi/2} 0 ${pi/2}"/>
<mass value="${m}"/>
<inertia ixx="${(m/12) * (h*h + d*d)}" ixy="0.0" ixz="0.0" iyy="${(m/12) * (w*w + d*d)}" iyz="0.0" izz="${(m/12) * (w*w + h*h)}"/>
</inertial>
</xacro:macro>
<xacro:macro name="mid40" params="name:='' parent:= 'base_link' topic:='mid40' *origin ">
<link name="${name}">
<xacro:box_inertia m="${length}" w="${width}" d="${length}" h="${height}"/>
<visual>
<geometry>
<box size="${length} ${width} ${height}"/>
</geometry>
</visual>
</link>
<joint name="${name}_joint" type="fixed">
<parent link="${parent}"/>
<child link="${name}"/>
<xacro:insert_block name="origin"/>
</joint>
<gazebo reference="${name}">
<sensor type="ray" name="${name}">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>10</update_rate>
<!-- This ray plgin is only for visualization. -->
<plugin name="${name}_plugin" filename="libros2_livox.so">
<ray>
<scan>
<horizontal>
<samples>100</samples>
<resolution>1</resolution>
<min_angle>${-horizontal_fov/360*M_PI}</min_angle>
<max_angle>${horizontal_fov/360*M_PI}</max_angle>
</horizontal>
<vertical>
<samples>50</samples>
<resolution>1</resolution>
<min_angle>${-vertical_fov/360*M_PI}</min_angle>
<max_angle>${vertical_fov/360*M_PI}</max_angle>
</vertical>
</scan>
<range>
<min>${laser_min_range}</min>
<max>${laser_max_range}</max>
<resolution>${resolution}</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>${noise_mean}</mean>
<stddev>${noise_stddev}</stddev>
</noise>
</ray>
<visualize>false</visualize>
<samples>${samples}</samples>
<downsample>1</downsample>
<csv_file_name>$(find ros2_livox_simulation)/scan_mode/mid40.csv</csv_file_name>
<topic>${topic}</topic>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
</robot>