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
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131 | <?xml version="1.0" ?>
<sdf version="1.9">
<model name="uav_simple">
<static>false</static>
<link name="base_link">
<pose>0 0 0 0 0 0</pose>
<inertial>
<mass>1.0</mass>
<inertia>
<ixx>2.0</ixx> <ixy>0.0</ixy> <ixz>0.0</ixz>
<iyy>2.0</iyy> <iyz>0.0</iyz>
<izz>0.2</izz>
</inertia>
</inertial>
<velocity_decay>
<linear>0.1</linear>
<angular>40.0</angular>
</velocity_decay>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.18</radius>
<length>0.12</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.18</radius>
<length>0.12</length>
</cylinder>
</geometry>
</visual>
</link>
<link name="lidar_link">
<pose>0 0 0.07 0 0 0</pose>
<inertial>
<mass>0.05</mass>
<inertia>
<ixx>0.0002</ixx> <ixy>0.0</ixy> <ixz>0.0</ixz>
<iyy>0.0002</iyy> <iyz>0.0</iyz>
<izz>0.0002</izz>
</inertia>
</inertial>
<collision name="lidar_collision">
<geometry>
<cylinder>
<radius>0.03</radius>
<length>0.02</length>
</cylinder>
</geometry>
</collision>
<visual name="lidar_visual">
<geometry>
<cylinder>
<radius>0.03</radius>
<length>0.02</length>
</cylinder>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
</material>
</visual>
<sensor name="gpu_lidar" type="gpu_lidar">
<pose>0 0 0 0 0 0</pose>
<always_on>true</always_on>
<update_rate>20</update_rate>
<visualize>true</visualize>
<topic>/scan</topic>
<ray>
<scan>
<horizontal>
<samples>90</samples>
<resolution>1</resolution>
<min_angle>-3.14159</min_angle>
<max_angle>3.07178</max_angle>
</horizontal>
</scan>
<range>
<min>0.1</min>
<max>50.0</max>
<resolution>0.01</resolution>
</range>
</ray>
</sensor>
</link>
<joint name="lidar_fixed_joint" type="fixed">
<parent>base_link</parent>
<child>lidar_link</child>
</joint>
<plugin filename="gz-sim-pose-publisher-system" name="gz::sim::v8::systems::PosePublisher">
<publish_link_pose>false</publish_link_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>true</publish_visual_pose>
<publish_nested_model_pose>true</publish_nested_model_pose>
</plugin>
<plugin filename="gz-sim-odometry-publisher-system" name="gz::sim::v8::systems::OdometryPublisher">
<odom_publish_frequency>50</odom_publish_frequency>
<dimensions>3</dimensions>
<odom_topic>/model/uav1/odometry</odom_topic>
<tf_topic>/tf</tf_topic>
</plugin>
<plugin filename="gz-sim-velocity-control-system" name="gz::sim::v8::systems::VelocityControl">
<cmd_vel_topic>/cmd_vel</cmd_vel_topic>
<initial_linear_velocity_x>0.0</initial_linear_velocity_x>
<initial_linear_velocity_y>0.0</initial_linear_velocity_y>
<initial_linear_velocity_z>0.0</initial_linear_velocity_z>
<initial_angular_velocity_x>0.0</initial_angular_velocity_x>
<initial_angular_velocity_y>0.0</initial_angular_velocity_y>
<initial_angular_velocity_z>0.0</initial_angular_velocity_z>
</plugin>
</model>
</sdf>
|