-
Notifications
You must be signed in to change notification settings - Fork 0
/
robot_test_diff_drive.urdf
167 lines (141 loc) · 6.16 KB
/
robot_test_diff_drive.urdf
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
161
162
163
164
165
166
167
<?xml version="1.0" ?>
<robot name="device" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find skidy_description)/urdf/robot_diff_drive.xacro" />
<!-- Robot Base -->
<link name="base_link">
<visual>
<geometry>
<box size="${base_length} ${base_width} ${base_height}"/>
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<geometry>
<box size="${base_length} ${base_width} ${base_height}"/>
</geometry>
</collision>
<xacro:box_inertia m="15" w="${base_width}" d="${base_length}" h="${base_height}"/>
</link>
<!-- Robot Footprint -->
<link name="base_footprint">
<xacro:box_inertia m="0" w="0" d="0" h="0"/>
</link>
<joint name="base_joint" type="fixed">
<parent link="base_link"/>
<child link="base_footprint"/>
<origin xyz="0.0 0.0 ${-(wheel_radius+wheel_zoff)}" rpy="0 0 0"/>
</joint>
<xacro:wheel prefix="drivewhl_l" x_reflect="-1" y_reflect="1" />
<xacro:wheel prefix="drivewhl_r" x_reflect="-1" y_reflect="-1" />
<link name="front_caster">
<visual>
<geometry>
<sphere radius="${(wheel_radius+wheel_zoff-(base_height/2))}"/>
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="${(wheel_radius+wheel_zoff-(base_height/2))}"/>
</geometry>
</collision>
<xacro:sphere_inertia m="0.5" r="${(wheel_radius+wheel_zoff-(base_height/2))}"/>
</link>
<joint name="caster_joint" type="fixed">
<parent link="base_link"/>
<child link="front_caster"/>
<origin xyz="${caster_xoff} 0.0 ${-(base_height/2)}" rpy="0 0 0"/>
</joint>
<link name="imu_link">
<visual>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
</collision>
<xacro:box_inertia m="0.01" w="0.01" d="0.01" h="0.01"/>
</link>
<joint name="imu_joint" type="fixed">
<parent link="base_link"/>
<child link="imu_link"/>
<origin xyz="0.0 ${base_width/2} ${base_height/2+0.01}"/>
</joint>
<gazebo>
<!--<plugin
filename="ignition-gazebo-diff-drive-system"
name="ignition::gazebo::systems::DiffDrive">
<left_joint>drivewhl_l_joint</left_joint>
<right_joint>drivewhl_r_joint</right_joint>
<topic>cmd_vel</topic>
<odom_topic>odom</odom_topic>
<frame_id>odom</frame_id>
<child_frame_id>base_link</child_frame_id>
<wheel_separation>0.4</wheel_separation>
<wheel_radius>0.1</wheel_radius>
<odom_publish_frequency>100</odom_publish_frequency>
<max_linear_acceleration>1</max_linear_acceleration>
<min_linear_acceleration>-1</min_linear_acceleration>
<max_angular_acceleration>2</max_angular_acceleration>
<min_angular_acceleration>-2</min_angular_acceleration>
<max_linear_velocity>0.5</max_linear_velocity>
<min_linear_velocity>-0.5</min_linear_velocity>
<max_angular_velocity>1</max_angular_velocity>
<min_angular_velocity>-1</min_angular_velocity>
</plugin>-->
<plugin filename="ignition-gazebo-odometry-publisher-system"
name="ignition::gazebo::systems::OdometryPublisher">
<odom_frame>odom</odom_frame>
<odom_covariance_topic>odom</odom_covariance_topic>
<tf_topic>tf</tf_topic>
<robot_base_frame>base_link</robot_base_frame>
<odom_publish_frequency>100</odom_publish_frequency>
</plugin>
<plugin filename="ignition-gazebo-velocity-control-system"
name="ignition::gazebo::systems::VelocityControl">
<topic>cmd_vel</topic>
</plugin>
</gazebo>
<joint name="navsat_joint" type="fixed">
<parent link="base_link"/>
<child link="navsat_link"/>
<origin xyz="0.0 -${base_width/2} ${base_height/2+0.01}"/>
</joint>
<link name="navsat_link">
<visual>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
</visual>
<collision>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
</collision>
<xacro:box_inertia m="0.01" w="0.01" d="0.01" h="0.01"/>
</link>
<!-- IMU -->
<!--https://classic.gazebosim.org/tutorials?tut=sensor_noise (High quality IMU noise)-->
<xacro:include filename="$(find skidy_description)/urdf/sensors/imu.gazebo.xacro" />
<xacro:imu_sensor reference_link="imu_link" sensor_name="imu" update_rate="100" topic_ns="device/imu" topic="data" vel_mean="0.0" vel_std_dev="0.0002" acc_mean="0.0" acc_std_dev="0.017"
vel_bias_mean="0.0000075" vel_bias_std_dev="0.0000008" acc_bias_mean="0.1" acc_bias_std_dev="0.001"/>
<!-- GPS -->
<xacro:include filename="$(find skidy_description)/urdf/sensors/navsat.gazebo.xacro" />
<xacro:navsat_sensor reference_link="navsat_link" sensor_name="navsat" update_rate="1" topic_ns="navsat" topic="fix" mean="0" std_dev="0.002"/>
<!--realsense Camera-->
<xacro:include filename="$(find skidy_description)/urdf/sensors/d435.gazebo.xacro" />
<xacro:sensor_d435 parent="base_link" name="camera" use_nominal_extrinsics="true" topic_ns="rgbd" topic="camera">
<origin xyz="0.04 0 -0.18" rpy="0 0 0" />
</xacro:sensor_d435>
<!--<xacro:include filename="$(find skidy_description)/urdf/sensors/camera.gazebo.xacro" />
<xacro:depth_camera_sensor reference_link="camera_link" parent="base_link" sensor_name="realsense_d435" update_rate="30" topic_ns="rgbd" topic="camera">
</xacro:depth_camera_sensor>-->
</robot>