Skip to content

Commit 9a2bed3

Browse files
authored
Merge pull request #245 from YoujianWu/master
Add slope world.
2 parents b32c088 + b2ca29e commit 9a2bed3

File tree

3 files changed

+105
-0
lines changed

3 files changed

+105
-0
lines changed

rm_gazebo/launch/slope.launch

Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
<launch>
2+
<arg name="robot_type" default="$(env ROBOT_TYPE)" doc="Robot type [standard, auto, hero, engineer]"/>
3+
4+
<arg name="x_pos" default="0.0"/>
5+
<arg name="y_pos" default="0.0"/>
6+
<arg name="z_pos" default="0.0"/>
7+
8+
<arg name="load_chassis" default="true"/>
9+
<arg name="load_gimbal" default="true"/>
10+
<arg name="load_shooter" default="true"/>
11+
<arg name="load_arm" default="true"/>
12+
<arg name="paused" default="false"/>
13+
14+
<rosparam file="$(find rm_gazebo)/config/imus.yaml" command="load" if="$(arg load_gimbal)"/>
15+
<param name="robot_description" command="$(find xacro)/xacro $(find rm_description)/urdf/$(arg robot_type)/$(arg robot_type).urdf.xacro
16+
load_chassis:=$(arg load_chassis) load_gimbal:=$(arg load_gimbal) load_shooter:=$(arg load_shooter)
17+
load_arm:=$(arg load_arm)
18+
use_simulation:=true roller_type:=simple
19+
"/>
20+
21+
<include file="$(find gazebo_ros)/launch/empty_world.launch">
22+
<arg name="world_name" value="$(find rm_gazebo)/worlds/slope.world"/>
23+
<arg name="paused" value="false"/>
24+
<arg name="use_sim_time" value="true"/>r
25+
<arg name="gui" value="true"/>
26+
</include>
27+
28+
<!-- push robot_description to factory and spawn robot in gazebo -->
29+
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model" clear_params="true"
30+
args="-z 0.5 -param robot_description -urdf -model $(arg robot_type)" output="screen"/>
31+
32+
</launch>

rm_gazebo/worlds/place/slope.stl

2.82 KB
Binary file not shown.

rm_gazebo/worlds/slope.world

Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
<?xml version="1.0" ?>
2+
3+
<sdf version="1.5">
4+
<world name="default">
5+
<!-- Target real time factor is the product of max_step_size and real_time_update_rate -->
6+
<!-- Negative real_time_update_rate means that Gazebo will run as fast as possible -->
7+
<physics type="ode">
8+
<!-- <type>world</type>-->
9+
<max_step_size>0.001</max_step_size>
10+
<real_time_update_rate>1000</real_time_update_rate>
11+
</physics>
12+
13+
<include>
14+
<uri>model://ground_plane</uri>
15+
</include>
16+
17+
<light name='sun' type='directional'>
18+
<cast_shadows>1</cast_shadows>
19+
<pose>0 0 10 0 -0 0</pose>
20+
<diffuse>0.8 0.8 0.8 1</diffuse>
21+
<specular>0.2 0.2 0.2 1</specular>
22+
<attenuation>
23+
<range>1000</range>
24+
<constant>0.9</constant>
25+
<linear>0.01</linear>
26+
<quadratic>0.001</quadratic>
27+
</attenuation>
28+
<direction>-0.5 0.1 -0.9</direction>
29+
</light>
30+
31+
<model name='slope'>
32+
<static>1</static>
33+
<static>1</static>
34+
<link name='slope_link'>
35+
<pose>-2 -0.6 0.05 0 0 0</pose>
36+
<visual name='visual'>
37+
<geometry>
38+
<mesh>
39+
<uri>model://rm_gazebo/worlds/place/slope.stl</uri>
40+
<scale>1 1 1</scale>
41+
</mesh>
42+
</geometry>
43+
</visual>
44+
<collision name='collision'>
45+
<geometry>
46+
<mesh>
47+
<uri>model://rm_gazebo/worlds/place/slope.stl</uri>
48+
<scale>1 1 1</scale>
49+
</mesh>
50+
</geometry>
51+
<max_contacts>10</max_contacts>
52+
<surface>
53+
<bounce/>
54+
<friction>
55+
<ode/>
56+
</friction>
57+
<contact>
58+
<ode/>
59+
</contact>
60+
</surface>
61+
</collision>
62+
<velocity_decay>
63+
<linear>0</linear>
64+
<angular>0</angular>
65+
</velocity_decay>
66+
<self_collide>0</self_collide>
67+
<kinematic>0</kinematic>
68+
<gravity>1</gravity>
69+
</link>
70+
<static>1</static>
71+
</model>
72+
</world>
73+
</sdf>

0 commit comments

Comments
 (0)