forked from tork-a/hakuto
/
tetris.gazebo.xacro
54 lines (51 loc) · 1.6 KB
/
tetris.gazebo.xacro
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
<?xml version="1.0"?>
<robot>
<!-- ros_control plugin -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<robotNamespace>/${ns}</robotNamespace>
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
</plugin>
</gazebo>
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive_fixed.so">
<alwaysOn>true</alwaysOn>
<updateRate>100</updateRate>
<leftJoint>right_wheel_joint</leftJoint> <!-- intentionally reverted -->
<rightJoint>left_wheel_joint</rightJoint>
<wheelSeparation>${wheel_separation}</wheelSeparation>
<wheelDiameter>${wheel_diameter}</wheelDiameter>
<torque>5</torque>
<commandTopic>/${ns}/cmd_vel</commandTopic>
<odometryTopic>/${ns}/odom</odometryTopic>
<odometryFrame>odom</odometryFrame>
<robotBaseFrame>base_footprint</robotBaseFrame>
<publishWheelTF>true</publishWheelTF>
<publishWheelJointState>true</publishWheelJointState>
</plugin>
</gazebo>
<gazebo reference="base_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="tail_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<material>Gazebo/White</material>
</gazebo>
<gazebo reference="right_wheel">
<mu1>0.8</mu1>
<mu2>0.8</mu2>
<material>Gazebo/Grey</material>
<kp>100000000.0</kp>
<kd>1.0</kd>
</gazebo>
<gazebo reference="left_wheel">
<mu1>0.8</mu1>
<mu2>0.8</mu2>
<material>Gazebo/Grey</material>
<kp>100000000.0</kp>
<kd>1.0</kd>
</gazebo>
</robot>