/
/
/
1<?xml version="1.0" ?>
2<robot name="simple_bot" xmlns:xacro="http://www.ros.org/wiki/xacro">
3
4 <xacro:macro name="black" >
5 <visual>
6 <material>
7 <ambient>0 0 0 1</ambient>
8 <diffuse>0 0 0 1</diffuse>
9 <specular>0 0 0 0</specular>
10 <emissive>0 0 0 1</emissive>
11 </material>
12 </visual>
13 </xacro:macro>
14
15 <material name="black_ros">
16 <color rgba="0 0 0 1"/>
17 </material>
18
19 <link name="base_footprint" />
20
21 <link name="base_link">
22 <inertial>
23 <origin rpy="0 0 0" xyz="0 0 0"/>
24 <mass value="5"/>
25 <inertia ixx="0.0875" ixy="0.0" ixz="0.0" iyy="0.0875" iyz="0.0" izz="0.15625"/>
26 </inertial>
27 <visual>
28 <origin rpy="0 0 0" xyz="0 0 0"/>
29 <geometry>
30 <cylinder length="0.15" radius="0.25" />
31 </geometry>
32 <material name="black_ros" />
33 </visual>
34 <collision>
35 <origin rpy="0 0 0" xyz="0 0 0"/>
36 <geometry>
37 <cylinder length="0.2" radius="0.3" />
38 </geometry>
39 </collision>
40 </link>
41
42 <link name="wheel_left">
43 <inertial>
44 <origin rpy="0 0 0" xyz="0 0 0"/>
45 <mass value="1"/>
46 <inertia ixx="0.0007" ixy="0.0" ixz="0.0" iyy="0.0007" iyz="0.0" izz="0.00125"/>
47 </inertial>
48 <visual>
49 <origin rpy="0 0 0" xyz="0 0 0"/>
50 <geometry>
51 <cylinder length="0.03" radius="0.05" />
52 </geometry>
53 <material name="black_ros" />
54 </visual>
55 <collision>
56 <origin rpy="0 0 0" xyz="0 0 0"/>
57 <geometry>
58 <cylinder length="0.03" radius="0.05" />
59 </geometry>
60 </collision>
61 </link>
62
63 <link name="wheel_right">
64 <inertial>
65 <origin rpy="0 0 0" xyz="0 0 0"/>
66 <mass value="1"/>
67 <inertia ixx="0.0007" ixy="0.0" ixz="0.0" iyy="0.0007" iyz="0.0" izz="0.00125"/>
68 </inertial>
69 <visual>
70 <origin rpy="0 0 0" xyz="0 0 0"/>
71 <geometry>
72 <cylinder length="0.03" radius="0.05" />
73 </geometry>
74 <material name="black_ros" />
75 </visual>
76 <collision>
77 <origin rpy="0 0 0" xyz="0 0 0"/>
78 <geometry>
79 <cylinder length="0.03" radius="0.05" />
80 </geometry>
81 </collision>
82 </link>
83
84 <link name="caster_front">
85 <inertial>
86 <origin rpy="0 0 0" xyz="0 0 0"/>
87 <mass value="0.1"/>
88 <inertia ixx="0.000004" ixy="0.0" ixz="0.0" iyy="0.000004" iyz="0.0" izz="0.000004"/>
89 </inertial>
90 <visual>
91 <origin rpy="0 0 0" xyz="0 0 0"/>
92 <geometry>
93 <sphere radius="0.01" />
94 </geometry>
95 <material name="black_ros" />
96 </visual>
97 <collision>
98 <origin rpy="0 0 0" xyz="0 0 0"/>
99 <geometry>
100 <sphere radius="0.01" />
101 </geometry>
102 </collision>
103 </link>
104
105 <link name="caster_rear">
106 <inertial>
107 <origin rpy="0 0 0" xyz="0 0 0"/>
108 <mass value="0.1"/>
109 <inertia ixx="0.000004" ixy="0.0" ixz="0.0" iyy="0.000004" iyz="0.0" izz="0.000004"/>
110 </inertial>
111 <visual>
112 <origin rpy="0 0 0" xyz="0 0 0"/>
113 <geometry>
114 <sphere radius="0.01" />
115 </geometry>
116 <material name="black_ros" />
117 </visual>
118 <collision>
119 <origin rpy="0 0 0" xyz="0 0 0"/>
120 <geometry>
121 <sphere radius="0.01" />
122 </geometry>
123 </collision>
124 </link>
125
126 <gazebo reference="base_link">
127 <xacro:black/>
128 </gazebo>
129
130 <gazebo reference="wheel_left">
131 <xacro:black/>
132 </gazebo>
133
134 <gazebo reference="wheel_right">
135 <xacro:black/>
136 </gazebo>
137
138 <gazebo reference="caster_front">
139 <xacro:black/>
140 </gazebo>
141
142 <gazebo reference="caster_rear">
143 <xacro:black/>
144 </gazebo>
145
146
147 <joint name="base_link_joint" type="fixed">
148 <origin rpy="0 0 0" xyz="0 0 0.05"/>
149 <parent link="base_footprint"/>
150 <child link="base_link"/>
151 </joint>
152
153 <joint name="caster_front_joint" type="fixed">
154 <origin rpy="0 0 0" xyz="0.24 0 -0.11"/>
155 <parent link="base_link"/>
156 <child link="caster_front"/>
157 </joint>
158
159 <joint name="caster_rear_joint" type="fixed">
160 <origin rpy="0 0 0" xyz="-0.24 0 -0.11"/>
161 <parent link="base_link"/>
162 <child link="caster_rear"/>
163 </joint>
164
165 <joint name="wheel_left_joint" type="continuous">
166 <origin rpy="1.57 0 0" xyz="0 0.2655 -0.07"/>
167 <parent link="base_link"/>
168 <child link="wheel_left"/>
169 <axis xyz="0 0 -1" />
170 </joint>
171
172 <joint name="wheel_right_joint" type="continuous">
173 <origin rpy="-1.57 0 0" xyz="0 -0.2655 -0.07"/>
174 <parent link="base_link"/>
175 <child link="wheel_right"/>
176 <axis xyz="0 0 1" />
177 </joint>
178
179 <gazebo>
180 <plugin
181 filename="libgz-sim-diff-drive-system.so"
182 name="gz::sim::systems::DiffDrive">
183 <left_joint>wheel_left_joint</left_joint>
184 <right_joint>wheel_right_joint</right_joint>
185 <wheel_separation>0.531</wheel_separation>
186 <wheel_radius>0.05</wheel_radius>
187 <max_wheel_torque>2000</max_wheel_torque>
188 <max_wheel_acceleration>100.0</max_wheel_acceleration>
189 <frame_id>odom</frame_id>
190 <tf_topic>gz_odom</tf_topic>
191 <child_frame_id>base_footprint</child_frame_id>
192 </plugin>
193 </gazebo>
194
195 <gazebo>
196 <plugin name="FakeLandmarks" filename="libfake_landmarks.so">
197 <landmark_topic>landmarks</landmark_topic>
198 <ros_frame>base_footprint</ros_frame>
199 <threshold>10</threshold>
200 <landmark_identifier>pillar</landmark_identifier>
201 </plugin>
202 </gazebo>
203
204 <gazebo>
205 <plugin filename="gz-sim-joint-state-publisher-system"
206 name="gz::sim::systems::JointStatePublisher">
207 <topic>/gz/joint_states</topic>
208 </plugin>
209 </gazebo>
210
211
212</robot>