@@ -10,24 +10,20 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
10
10
<include>
11
11
<name>#{ _name } </name>
12
12
<uri>#{ _modelURI } </uri>
13
- <!-- Diff drive -->
14
- <plugin filename="libignition-gazebo-diff-drive-system.so"
15
- name="ignition::gazebo::systems::DiffDrive">
16
- <left_joint>front_left_wheel_joint</left_joint>
17
- <left_joint>front_middle_left_wheel_joint</left_joint>
18
- <left_joint>rear_middle_left_wheel_joint</left_joint>
19
- <left_joint>rear_left_wheel_joint</left_joint>
20
- <right_joint>front_right_wheel_joint</right_joint>
21
- <right_joint>front_middle_right_wheel_joint</right_joint>
22
- <right_joint>rear_middle_right_wheel_joint</right_joint>
23
- <right_joint>rear_right_wheel_joint</right_joint>
24
- <wheel_separation>#{ 0.525 } </wheel_separation>
25
- <wheel_radius>0.129</wheel_radius>
13
+ <!-- Tracked vehicle controller -->
14
+ <plugin name="ignition::gazebo::systems::TrackedVehicle" filename="ignition-gazebo-tracked-vehicle-system">
15
+ <left_track><link>left_track</link></left_track>
16
+ <right_track><link>right_track</link></right_track>
17
+ <tracks_separation>#{ 0.525 } </tracks_separation>
18
+ <tracks_height>0.258</tracks_height>
19
+ <steering_efficiency>0.5</steering_efficiency>
26
20
<topic>/model/#{ _name } /cmd_vel_relay</topic>
27
- <min_velocity>-1</min_velocity>
28
- <max_velocity>1</max_velocity>
29
- <min_acceleration>-3</min_acceleration>
30
- <max_acceleration>3</max_acceleration>
21
+ <linear_velocity>
22
+ <min_velocity>-1</min_velocity>
23
+ <max_velocity>1</max_velocity>
24
+ <min_acceleration>-3</min_acceleration>
25
+ <max_acceleration>3</max_acceleration>
26
+ </linear_velocity>
31
27
</plugin>
32
28
<!-- Publish robot state information -->
33
29
<plugin filename="libignition-gazebo-pose-publisher-system.so"
@@ -54,6 +50,8 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
54
50
<smooth_current_tau>1.9499</smooth_current_tau>
55
51
<power_load>9.9</power_load>
56
52
<start_on_motion>true</start_on_motion>
53
+ <power_draining_topic>/model/#{ _name } /link/left_track/track_cmd_vel</power_draining_topic>
54
+ <power_draining_topic>/model/#{ _name } /link/right_track/track_cmd_vel</power_draining_topic>
57
55
</plugin>
58
56
<!-- Gas Sensor plugin -->
59
57
<plugin filename="libGasEmitterDetectorPlugin.so"
@@ -62,58 +60,6 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
62
60
<update_rate>10</update_rate>
63
61
<type>gas</type>
64
62
</plugin>
65
- <!-- Wheel slip -->
66
- <plugin filename="libignition-gazebo-wheel-slip-system.so"
67
- name="ignition::gazebo::systems::WheelSlip">
68
- <wheel link_name="front_left_wheel_link">
69
- <slip_compliance_lateral>0.086</slip_compliance_lateral>
70
- <slip_compliance_longitudinal>0</slip_compliance_longitudinal>
71
- <wheel_normal_force>41.47103925</wheel_normal_force>
72
- <wheel_radius>0.129</wheel_radius>
73
- </wheel>
74
- <wheel link_name="front_middle_left_wheel_link">
75
- <slip_compliance_lateral>0.086</slip_compliance_lateral>
76
- <slip_compliance_longitudinal>0</slip_compliance_longitudinal>
77
- <wheel_normal_force>41.47103925</wheel_normal_force>
78
- <wheel_radius>0.129</wheel_radius>
79
- </wheel>
80
- <wheel link_name="rear_middle_left_wheel_link">
81
- <slip_compliance_lateral>0.086</slip_compliance_lateral>
82
- <slip_compliance_longitudinal>0</slip_compliance_longitudinal>
83
- <wheel_normal_force>41.47103925</wheel_normal_force>
84
- <wheel_radius>0.129</wheel_radius>
85
- </wheel>
86
- <wheel link_name="rear_left_wheel_link">
87
- <slip_compliance_lateral>0.086</slip_compliance_lateral>
88
- <slip_compliance_longitudinal>0.25</slip_compliance_longitudinal>
89
- <wheel_normal_force>41.47103925</wheel_normal_force>
90
- <wheel_radius>0.129</wheel_radius>
91
- </wheel>
92
- <wheel link_name="front_right_wheel_link">
93
- <slip_compliance_lateral>0.086</slip_compliance_lateral>
94
- <slip_compliance_longitudinal>0</slip_compliance_longitudinal>
95
- <wheel_normal_force>41.47103925</wheel_normal_force>
96
- <wheel_radius>0.129</wheel_radius>
97
- </wheel>
98
- <wheel link_name="front_middle_right_wheel_link">
99
- <slip_compliance_lateral>0.086</slip_compliance_lateral>
100
- <slip_compliance_longitudinal>0</slip_compliance_longitudinal>
101
- <wheel_normal_force>41.47103925</wheel_normal_force>
102
- <wheel_radius>0.129</wheel_radius>
103
- </wheel>
104
- <wheel link_name="rear_middle_right_wheel_link">
105
- <slip_compliance_lateral>0.086</slip_compliance_lateral>
106
- <slip_compliance_longitudinal>0</slip_compliance_longitudinal>
107
- <wheel_normal_force>41.47103925</wheel_normal_force>
108
- <wheel_radius>0.129</wheel_radius>
109
- </wheel>
110
- <wheel link_name="rear_right_wheel_link">
111
- <slip_compliance_lateral>0.086</slip_compliance_lateral>
112
- <slip_compliance_longitudinal>0</slip_compliance_longitudinal>
113
- <wheel_normal_force>41.47103925</wheel_normal_force>
114
- <wheel_radius>0.129</wheel_radius>
115
- </wheel>
116
- </plugin>
117
63
</include>
118
64
</sdf>
119
65
</spawn>
0 commit comments