Skip to content

Commit 2b3c491

Browse files
committedSep 19, 2019
Added a back laser to the ropod model
1 parent 2e9c099 commit 2b3c491

File tree

2 files changed

+119
-68
lines changed

2 files changed

+119
-68
lines changed
 
+27-26
Original file line numberDiff line numberDiff line change
@@ -1,33 +1,34 @@
11
<?xml version="1.0" encoding="UTF-8"?>
22
<launch>
33

4-
<env name="GAZEBO_MODEL_PATH" value="$(find ropod_sim_model)/simulator/models:$(optenv GAZEBO_MODEL_PATH)"/>
5-
<env name="GAZEBO_RESOURCE_PATH" value="$(find ropod_sim_model)/simulator:$(optenv GAZEBO_RESOURCE_PATH)"/>
6-
<env name="GAZEBO_PLUGIN_PATH" value="$(env CATKIN_WORKSPACE)/devel/lib:$(optenv GAZEBO_PLUGIN_PATH)"/>
4+
<env name="GAZEBO_MODEL_PATH" value="$(find ropod_sim_model)/simulator/models:$(optenv GAZEBO_MODEL_PATH)"/>
5+
<env name="GAZEBO_RESOURCE_PATH" value="$(find ropod_sim_model)/simulator:$(optenv GAZEBO_RESOURCE_PATH)"/>
6+
<env name="GAZEBO_PLUGIN_PATH" value="$(env CATKIN_WORKSPACE)/devel/lib:$(optenv GAZEBO_PLUGIN_PATH)"/>
77

8-
<!--<env name="GAZEBO_MODEL_DATABASE_URI" value="" /> THIS VARIABLE SHOULD BE CHANGED LOCALLY,
9-
see http://cstwiki.wtb.tue.nl/index.php?title=RoPod/Tutorials/GAZEBO_installation_and_interface_with_ROS/Faster statup of Gazebo -->
10-
11-
<arg name="robot" default="ropod"/>
12-
<arg name="model_name" default="ropod"/>
13-
<arg name="model_path" default="$(find ropod_sim_model)" />
14-
<arg name="gui" default="true" />
15-
<arg name="movingObjects" default="false" />
8+
<!--<env name="GAZEBO_MODEL_DATABASE_URI" value="" /> THIS VARIABLE SHOULD BE CHANGED LOCALLY,
9+
see http://cstwiki.wtb.tue.nl/index.php?title=RoPod/Tutorials/GAZEBO_installation_and_interface_with_ROS/Faster statup of Gazebo -->
1610

17-
<group unless="$(arg movingObjects)">
18-
<include file="$(find gazebo_ros)/launch/empty_world.launch">
19-
<!-- <arg name="verbose" value="true" /> -->
20-
<arg name="world_name" value="$(arg model_path)/world/$(arg robot).world"/>
21-
<arg name="gui" value="$(arg gui)"/>
22-
</include>
23-
</group>
11+
<arg name="robot" default="ropod"/>
12+
<arg name="model_name" default="ropod"/>
13+
<arg name="model_path" default="$(find ropod_sim_model)" />
14+
<arg name="gui" default="true" />
15+
<arg name="movingObjects" default="false" />
2416

25-
<group if="$(arg movingObjects)">
26-
<include file="$(find gazebo_ros)/launch/empty_world.launch">
27-
<!-- <arg name="verbose" value="true" /> -->
28-
<arg name="world_name" value="$(arg model_path)/world/$(arg robot)_movingObjects.world"/>
29-
</include>
30-
</group>
31-
32-
<node name="throttle" pkg="topic_tools" type="throttle" args="messages /$(arg robot)/laser_sim 20.0 /$(arg robot)/laser/scan" />
17+
<group unless="$(arg movingObjects)">
18+
<include file="$(find gazebo_ros)/launch/empty_world.launch">
19+
<!-- <arg name="verbose" value="true" /> -->
20+
<arg name="world_name" value="$(arg model_path)/world/$(arg robot).world"/>
21+
<arg name="gui" value="$(arg gui)"/>
22+
</include>
23+
</group>
24+
25+
<group if="$(arg movingObjects)">
26+
<include file="$(find gazebo_ros)/launch/empty_world.launch">
27+
<!-- <arg name="verbose" value="true" /> -->
28+
<arg name="world_name" value="$(arg model_path)/world/$(arg robot)_movingObjects.world"/>
29+
</include>
30+
</group>
31+
32+
<node name="throttle_laser_front" pkg="topic_tools" type="throttle" args="messages /$(arg robot)/laser_sim 20.0 /$(arg robot)/laser/scan" />
33+
<node name="throttle_laser_back" pkg="topic_tools" type="throttle" args="messages /$(arg robot)/laser_back_sim 20.0 /$(arg robot)/laser/scan_back" />
3334
</launch>

‎simulator/models/ropod/ropod.sdf

+92-42
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,13 @@
11
<?xml version='1.0'?>
22
<sdf version='1.5'>
3-
4-
<model name='ropod'>
5-
63

7-
<link name='base_link'>
8-
9-
10-
4+
<model name='ropod'>
5+
6+
7+
<link name='base_link'>
8+
9+
10+
1111
<inertial>
1212
<mass>0.01</mass>
1313
<inertia> <!-- inertias are tricky to compute -->
@@ -20,14 +20,14 @@
2020
<izz>0.083*00.01*2</izz> <!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
2121
</inertia>
2222
</inertial>
23-
23+
2424
<collision name='base_link_collision'>
2525
<pose>0 0 0.15 0 0 0</pose>
2626
<geometry>
2727
<box>
2828
<size>0.6 0.6 0.1</size>
2929
</box>
30-
</geometry>
30+
</geometry>
3131
</collision>
3232
<visual name='base_link_visual'>
3333
<pose>0 0 0.15 0 0 0</pose>
@@ -41,9 +41,9 @@
4141
<diffuse>0.5 0.5 0.5 1</diffuse>
4242
<specular>0.1 0.1 0.1 1</specular>
4343
<emissive>0 0 0 0</emissive>
44-
</material>
45-
</visual>
46-
44+
</material>
45+
</visual>
46+
4747
<collision name='base_link_collision_left_rear_wheel'>
4848
<pose>-0.25 0.25 0.05 0 -0 0</pose>
4949
<geometry>
@@ -106,7 +106,7 @@
106106
</sphere>
107107
</geometry>
108108
</visual>
109-
109+
110110
<collision name='base_link_collision_right_top_wheel'>
111111
<pose>0.25 -0.25 0.05 0 -0 0</pose>
112112
<geometry>
@@ -136,9 +136,9 @@
136136
<radius>0.05</radius>
137137
</sphere>
138138
</geometry>
139-
</visual>
140-
141-
139+
</visual>
140+
141+
142142
<collision name='base_link_collision_right_rear_wheel'>
143143
<pose>-0.25 -0.25 0.05 0 -0 0</pose>
144144
<geometry>
@@ -168,10 +168,10 @@
168168
<radius>0.05</radius>
169169
</sphere>
170170
</geometry>
171-
</visual>
171+
</visual>
172+
173+
<!-- ********************** laser front ***************************** -->
172174

173-
<!-- ********************** laser ***************************** -->
174-
175175
<visual name='base_link_visual_laser'>
176176
<pose>0.25 0 0.25 0 -0 0</pose>
177177
<geometry>
@@ -186,11 +186,11 @@
186186
<box>
187187
<size>0.04 0.04 0.01</size>
188188
</box>
189-
</geometry>
189+
</geometry>
190190
</visual>
191-
191+
192192
<sensor name='laser' type='ray'>
193-
<pose>0.25 0 0.25 0 0 0</pose>
193+
<pose>0.25 0 0.25 0 0 0</pose>
194194
<ray>
195195
<scan>
196196
<horizontal>
@@ -213,20 +213,70 @@
213213
</range>
214214
</ray>
215215

216+
<plugin name="gazebo_ros_laser" filename="libgazebo_ros_laser.so">
217+
<topicName>/ropod/laser_sim</topicName>
218+
<frameName>/ropod/laser/scan</frameName>
219+
<robotNamespace></robotNamespace>
220+
<gaussianNoise>0.01</gaussianNoise>
221+
<always_on>1</always_on>
222+
<updateRate>30.0</updateRate>
223+
</plugin>
224+
<visualize>1</visualize>
225+
</sensor>
216226

217-
<plugin name="gazebo_ros_laser" filename="libgazebo_ros_laser.so">
218-
<topicName>/ropod/laser_sim</topicName>
219-
<frameName>/ropod/laser/scan</frameName>
220-
<robotNamespace></robotNamespace>
221-
<gaussianNoise>0.01</gaussianNoise>
222-
<always_on>1</always_on>
223-
<updateRate>30.0</updateRate>
224-
</plugin>
225-
<visualize>1</visualize>
226-
227-
228-
</sensor>
227+
<!-- ********************** laser back ***************************** -->
228+
229+
<visual name='base_link_visual_laser_back'>
230+
<pose>-0.25 0 0.25 0 0 0</pose>
231+
<geometry>
232+
<box>
233+
<size>0.04 0.04 0.04</size>
234+
</box>
235+
</geometry>
236+
</visual>
237+
<visual name='base_link_visual_lasertop_back'>
238+
<pose>-0.25 0 0.275 0 0 0</pose>
239+
<geometry>
240+
<box>
241+
<size>0.04 0.04 0.01</size>
242+
</box>
243+
</geometry>
244+
</visual>
245+
246+
<sensor name='laser_back' type='ray'>
247+
<pose>-0.25 0 0.25 0 0 0</pose>
248+
<ray>
249+
<scan>
250+
<horizontal>
251+
<samples>500</samples>
252+
<resolution>1</resolution>
253+
<min_angle>0.79</min_angle>
254+
<max_angle>5.49</max_angle>
255+
</horizontal>
256+
<vertical>
257+
<samples>1</samples>
258+
<resolution>1</resolution>
259+
<min_angle>0</min_angle>
260+
<max_angle>0</max_angle>
261+
</vertical>
262+
</scan>
263+
<range>
264+
<min>0.01</min>
265+
<max>4</max>
266+
<resolution>0.01</resolution>
267+
</range>
268+
</ray>
229269

270+
<plugin name="gazebo_ros_laser" filename="libgazebo_ros_laser.so">
271+
<topicName>/ropod/laser_back_sim</topicName>
272+
<frameName>/ropod/laser/scan_back</frameName>
273+
<robotNamespace></robotNamespace>
274+
<gaussianNoise>0.01</gaussianNoise>
275+
<always_on>1</always_on>
276+
<updateRate>30.0</updateRate>
277+
</plugin>
278+
<visualize>1</visualize>
279+
</sensor>
230280

231281
<!-- ********************** bumper ***************************** -->
232282
<sensor type="contact" name="gazebo_base_bumper">
@@ -244,7 +294,7 @@
244294
</plugin>
245295
</sensor>
246296

247-
297+
248298
<!-- ********************** Other parameters ***************************** -->
249299
<gravity>1</gravity>
250300
<velocity_decay>
@@ -253,24 +303,24 @@
253303
</velocity_decay>
254304
<self_collide>0</self_collide>
255305

256-
306+
257307
</link>
258308

259309
<plugin name="Odometry_Plugin" filename="libOdometry_Plugin.so">
260310
<updateRate>30.0</updateRate>
261-
<veltopicName>/ropod/cmd_vel</veltopicName>
262-
<odomtopicName>/ropod/odom_incomplete</odomtopicName>
311+
<veltopicName>/ropod/cmd_vel</veltopicName>
312+
<odomtopicName>/ropod/odom_incomplete</odomtopicName>
263313
<robotBaseFrame>/ropod/base_link</robotBaseFrame>
264-
<odomFrame>/ropod/odom</odomFrame>
314+
<odomFrame>/ropod/odom</odomFrame>
265315
</plugin>
266316

267317
<!--
268318
<plugin name="Odometry_Plugin" filename="libgazebo_ros_planar_move.so">
269319
<odometryRate>30.0</odometryRate>
270-
<commandTopic>/ropod/cmd_vel</commandTopic>
271-
<odometryTopic>/ropod/odom_incomplete</odometryTopic>
320+
<commandTopic>/ropod/cmd_vel</commandTopic>
321+
<odometryTopic>/ropod/odom_incomplete</odometryTopic>
272322
<robotBaseFrame>/ropod/base_link</robotBaseFrame>
273-
<odometryFrame>/ropod/odom</odometryFrame>
323+
<odometryFrame>/ropod/odom</odometryFrame>
274324
</plugin>
275325
-->
276326

0 commit comments

Comments
 (0)
Please sign in to comment.