-
Notifications
You must be signed in to change notification settings - Fork 1
/
scuttle.gazebo
160 lines (132 loc) · 5.11 KB
/
scuttle.gazebo
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
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
<?xml version="1.0" ?>
<robot name="scuttle" xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:property name="body_color" value="Gazebo/Silver" />
<xacro:property name="wheel_color" value="Gazebo/Blue" />
<xacro:property name="lidar_color" value="Gazebo/Gray" />
<xacro:arg name="differential_drive_command_topic" default="cmd_vel"/>
<xacro:arg name="differential_drive_odometry_topic" default="odom"/>
<xacro:arg name="differential_drive_odometry_frame" default="odom"/>
<gazebo>
<plugin filename="libgazebo_ros_control.so" name="control"/>
</gazebo>
<gazebo reference="base_link">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>true</selfCollide>
<gravity>true</gravity>
</gazebo>
<gazebo reference="l_wheel_1">
<material>${wheel_color}</material>
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="r_wheel_1">
<material>${wheel_color}</material>
<mu1>0.9</mu1>
<mu2>0.9</mu2>
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="lidar_1">
<material>${lidar_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="r_caster_swivel_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="l_caster_swivel_1">
<material>${body_color}</material>
<mu1>0.2</mu1>
<mu2>0.2</mu2>
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="l_caster_wheel_1">
<material>${wheel_color}</material>
<mu1>0.4</mu1>
<mu2>0.4</mu2>
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="r_caster_wheel_1">
<material>${wheel_color}</material>
<mu1>0.4</mu1>
<mu2>0.4</mu2>
<selfCollide>true</selfCollide>
</gazebo>
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<!-- Plugin update rate in Hz -->
<updateRate>50</updateRate>
<!-- Name of left joint, defaults to `left_joint` -->
<leftJoint>l_wheel_joint</leftJoint>
<!-- Name of right joint, defaults to `right_joint` -->
<rightJoint>r_wheel_joint</rightJoint>
<!-- The distance from the center of one wheel to the other, in meters, defaults to 0.34 m -->
<wheelSeparation>0.355</wheelSeparation>
<!-- Diameter of the wheels, in meters, defaults to 0.15 m -->
<wheelDiameter>0.0833</wheelDiameter>
<!-- Wheel acceleration, in rad/s^2, defaults to 0.0 rad/s^2 -->
<wheelAcceleration>2.7</wheelAcceleration>
<!-- Maximum torque which the wheels can produce, in Nm, defaults to 5 Nm -->
<wheelTorque>0.392</wheelTorque>
<!-- Topic to receive geometry_msgs/Twist message commands, defaults to `cmd_vel` -->
<commandTopic>$(arg differential_drive_command_topic)</commandTopic>
<!-- Topic to publish nav_msgs/Odometry messages, defaults to `odom` -->
<odometryTopic>$(arg differential_drive_odometry_topic)</odometryTopic>
<!-- Odometry frame, defaults to `odom` -->
<odometryFrame>$(arg differential_drive_odometry_frame)</odometryFrame>
<!-- Robot frame to calculate odometry from, defaults to `base_footprint` -->
<robotBaseFrame>base_link</robotBaseFrame>
<!-- Odometry source, 0 for ENCODER, 1 for WORLD, defaults to WORLD -->
<odometrySource>1</odometrySource>
<!-- Set to true to publish transforms for the wheel links, defaults to false -->
<publishWheelTF>false</publishWheelTF>
<!-- Set to true to publish transforms for the odometry, defaults to true -->
<publishOdom>true</publishOdom>
<!-- Set to true to publish sensor_msgs/JointState on /joint_states for the wheel joints, defaults to false -->
<publishWheelJointState>false</publishWheelJointState>
<!-- Set to true to swap right and left wheels, defaults to true -->
<legacyMode>false</legacyMode>
</plugin>
</gazebo>
<gazebo reference="lidar_1">
<sensor type="ray" name="rplidar_a1">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>5.5</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>6.283185307179586</max_angle>
</horizontal>
</scan>
<range>
<min>0.15</min>
<max>12.0</max>
<resolution>0.005</resolution>
</range>
<noise>
<type>gaussian</type>
<!-- Noise parameters based on published spec for Hokuyo laser
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
reading. -->
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/scan</topicName>
<frameName>lidar_1</frameName>
</plugin>
</sensor>
</gazebo>
</robot>