85 lines
2.7 KiB
XML
85 lines
2.7 KiB
XML
<?xml version="1.0"?>
|
|
|
|
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="turtlebot">
|
|
|
|
<gazebo reference="base_link">
|
|
<material>Gazebo/DarkGrey</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="base_scan">
|
|
<material>Gazebo/FlatBlack</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference ="wheel_left_link">
|
|
<mu1>1000000</mu1>
|
|
<mu2>1000000</mu2>
|
|
<kp>500000</kp>
|
|
<kd>10</kd>
|
|
<minDepth>0.001</minDepth>
|
|
<maxVel>0.1</maxVel>
|
|
<fdir1>1 0 0</fdir1>
|
|
<material>Gazebo/FlatBlack</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference ="wheel_right_link">
|
|
<mu1>100000</mu1>
|
|
<mu2>100000</mu2>
|
|
<kp>500000</kp>
|
|
<kd>10</kd>
|
|
<minDepth>0.001</minDepth>
|
|
<maxVel>0.1</maxVel>
|
|
<fdir1>1 0 0</fdir1>
|
|
<material>Gazebo/FlatBlack</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="caster_back_right_link">
|
|
<mu1>0.1</mu1>
|
|
<mu2>0.1</mu2>
|
|
<kp>1000000</kp>
|
|
<kd>100</kd>
|
|
<minDepth>0.001</minDepth>
|
|
<maxVel>1</maxVel>
|
|
<fdir1>1 0 0</fdir1>
|
|
<material>Gazebo/FlatBlack</material>
|
|
</gazebo>
|
|
|
|
<gazebo reference="caster_back_left_link">
|
|
<mu1>0.1</mu1>
|
|
<mu2>0.1</mu2>
|
|
<kp>1000000</kp>
|
|
<kd>100</kd>
|
|
<minDepth>0.001</minDepth>
|
|
<maxVel>1</maxVel>
|
|
<fdir1>1 0 0</fdir1>
|
|
<material>Gazebo/FlatBlack</material>
|
|
</gazebo>
|
|
|
|
<gazebo>
|
|
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
|
|
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
|
<lagacyModeNS>true</lagacyModeNS>
|
|
</plugin>
|
|
</gazebo>
|
|
|
|
<transmission name="wheel_left_tranmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="wheel_left_joint">
|
|
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="wheel_left_actuator">
|
|
<mechanicalReduction>1.0</mechanicalReduction>
|
|
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
</actuator>
|
|
</transmission>
|
|
|
|
<transmission name="wheel_right_tranmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<joint name="wheel_right_joint">
|
|
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
</joint>
|
|
<actuator name="wheel_right_actuator">
|
|
<mechanicalReduction>1.0</mechanicalReduction>
|
|
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
</actuator>
|
|
</transmission>
|
|
</robot> |