mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
fixed friction issue
This commit is contained in:
@@ -1,5 +1,12 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro" >
|
||||
|
||||
Reference:
|
||||
[1] https://answers.ros.org/question/246914/four-wheeled-skid-steering-in-gazebo-and-ros-using-gazebo-ros-control/
|
||||
[2] https://answers.ros.org/question/10119/gazebo-controller-for-skid-steering/
|
||||
[3] https://answers.ros.org/question/9640/rotation-error-in-gazebo-simulation/
|
||||
[4] https://www.youtube.com/watch?v=fuRAv6PDwdw
|
||||
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<xacro:include filename="$(find scout_description)/urdf/scout_wheel.gazebo" />
|
||||
|
||||
<!-- Additional definitions for simulation -->
|
||||
@@ -20,6 +27,17 @@
|
||||
</plugin>
|
||||
</gazebo>
|
||||
|
||||
<!-- kp spring constant, kd damping constant -->
|
||||
<gazebo>
|
||||
<mu1 value="1.0"/>
|
||||
<mu2 value="0.9"/>
|
||||
<kp value="10000000.0" />
|
||||
<kd value="1.0" />
|
||||
<fdir1 value="1 0 0"/>
|
||||
<minDepth value="0.001" />
|
||||
<maxContacts value="64"/>
|
||||
</gazebo>
|
||||
|
||||
<!-- <gazebo>
|
||||
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
|
||||
<updateRate>100.0</updateRate>
|
||||
|
||||
@@ -32,6 +32,14 @@
|
||||
<child link="base_link" />
|
||||
</joint>
|
||||
|
||||
<!-- For testing, hang the robot up in the air -->
|
||||
<!-- <link name="world" />
|
||||
<joint name="world_to_base_link=" type="fixed">
|
||||
<origin xyz="0 0 0.5" rpy="0 0 0" />
|
||||
<parent link="world"/>
|
||||
<child link="base_link"/>
|
||||
</joint> -->
|
||||
|
||||
<!-- Base link -->
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
@@ -87,14 +95,6 @@
|
||||
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
|
||||
</xacro:scout_wheel_type2>
|
||||
|
||||
<!-- For testing, hang the robot up in the air -->
|
||||
<!-- <link name="world" />
|
||||
<joint name="world_to_base_link=" type="fixed">
|
||||
<origin xyz="0 0 0.5" rpy="0 0 0" />
|
||||
<parent link="world"/>
|
||||
<child link="base_link"/>
|
||||
</joint> -->
|
||||
|
||||
<!-- Additional definitions -->
|
||||
<xacro:include filename="$(arg urdf_extras)" />
|
||||
|
||||
|
||||
@@ -28,17 +28,6 @@ ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSI
|
||||
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="scout_wheel">
|
||||
|
||||
<xacro:macro name="scout_wheel_transmission" params="wheel_prefix">
|
||||
<!-- kp spring constant, kd damping constant -->
|
||||
<gazebo reference="${wheel_prefix}_wheel_link">
|
||||
<mu1 value="1.0"/>
|
||||
<mu2 value="0.9"/>
|
||||
<kp value="10000000.0" />
|
||||
<kd value="1.0" />
|
||||
<fdir1 value="1 0 0"/>
|
||||
<minDepth value="0.001" />
|
||||
<maxContacts value="64"/>
|
||||
</gazebo>
|
||||
|
||||
<transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<actuator name="${wheel_prefix}_wheel_motor">
|
||||
|
||||
Reference in New Issue
Block a user