-
Notifications
You must be signed in to change notification settings - Fork 1
/
differ.sdf
113 lines (113 loc) · 4.32 KB
/
differ.sdf
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
<?xml version='1.0' encoding='utf-8'?>
<sdf version="1.6">
<world name="car_world">
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>
<include>
<uri>diffRobot.urdf.xml</uri>
<pose>0 0 5 0 0 0</pose>
<plugin
filename="gz-sim-diff-drive-system"
name="gz::sim::systems::DiffDrive">
<left_joint>front_left_wheel_joint</left_joint>
<left_joint>rear_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
<right_joint>rear_right_wheel_joint</right_joint>
<wheel_separation>1.25</wheel_separation>
<wheel_radius>0.3</wheel_radius>
<max_linear_acceleration>2</max_linear_acceleration>
<min_linear_acceleration>-2</min_linear_acceleration>
<max_angular_acceleration>4</max_angular_acceleration>
<min_angular_acceleration>-4</min_angular_acceleration>
<max_linear_velocity>1</max_linear_velocity>
<min_linear_velocity>-1</min_linear_velocity>
<max_angular_velocity>2</max_angular_velocity>
<min_angular_velocity>-2</min_angular_velocity>
</plugin>
</include>
<plugin filename="gz-sim-triggered-publisher-system"
name="gz::sim::systems::TriggeredPublisher">
<input type="gz.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777234</match>
</input>
<output type="gz.msgs.Twist" topic="/model/diffRobot/cmd_vel">
linear: {x: 0 y: 0 z: 0} angular: {x: 0 y: 0 z: 1}
</output>
</plugin>
<plugin filename="gz-sim-triggered-publisher-system"
name="gz::sim::systems::TriggeredPublisher">
<input type="gz.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777235</match>
</input>
<output type="gz.msgs.Twist" topic="/model/diffRobot/cmd_vel">
linear: {x: 5 y: 0 z: 0} angular: {x: 0 y: 0 z: 0}
</output>
</plugin>
<plugin filename="gz-sim-triggered-publisher-system"
name="gz::sim::systems::TriggeredPublisher">
<input type="gz.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777236</match>
</input>
<output type="gz.msgs.Twist" topic="/model/diffRobot/cmd_vel">
linear: {x: 0 y: 0 z: 0} angular: {x: 0 y: 0 z: -1}
</output>
</plugin>
<plugin filename="gz-sim-triggered-publisher-system"
name="gz::sim::systems::TriggeredPublisher">
<input type="gz.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777237</match>
</input>
<output type="gz.msgs.Twist" topic="/model/diffRobot/cmd_vel">
linear: {x: -5 y: 0 z: 0} angular: {x: 0 y: 0 z: 0}
</output>
</plugin>
<plugin filename="gz-sim-triggered-publisher-system"
name="gz::sim::systems::TriggeredPublisher">
<input type="gz.msgs.Int32" topic="/keyboard/keypress">
<match field="data">16777248</match>
</input>
<output type="gz.msgs.Twist" topic="/model/diffRobot/cmd_vel">
linear: {x: 0 y: 0 z: 0} angular: {x: 0 y: 0 z: 0}
</output>
</plugin>
</world>
</sdf>