mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
fixed state publish rate error (from 20hz to 50hz), gazebo scout v2 sim ready
This commit is contained in:
@@ -24,22 +24,6 @@
|
||||
<xacro:property name="wheel_length" value="1.1653e-01" />
|
||||
<xacro:property name="wheel_radius" value="1.6459e-01" />
|
||||
|
||||
<!-- Virtual link as root -->
|
||||
<link name="vehicle_reference" />
|
||||
<joint name="veh_ref_joint" type="fixed">
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<parent link="vehicle_reference" />
|
||||
<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>
|
||||
@@ -48,14 +32,6 @@
|
||||
<mesh filename="package://scout_description/meshes/base_link.dae" />
|
||||
</geometry>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="40" />
|
||||
<!-- <mass value="50" /> -->
|
||||
<!-- <origin xyz="-0.00065 -0.085 0.062" />
|
||||
<inertia ixx="0.6022" ixy="-0.02364" ixz="-0.1197" iyy="1.7386" iyz="-0.001544" izz="2.0296" /> -->
|
||||
<origin xyz="0.0 0.0 0.0" />
|
||||
<inertia ixx="2.288641" ixy="0" ixz="0" iyy="5.103976" iyz="0" izz="3.431465" />
|
||||
</inertial>
|
||||
<collision>
|
||||
<origin xyz="0 0 0.008" rpy="0 0 0" />
|
||||
<geometry>
|
||||
@@ -70,15 +46,37 @@
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<!-- Base footprint: base_link projected to the gound plane -->
|
||||
<link name="base_footprint"/>
|
||||
|
||||
<joint name="base_footprint_joint" type="fixed">
|
||||
<origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" />
|
||||
<!-- <joint name="chassis_link_joint" type="fixed">
|
||||
<origin xyz="0 0 ${wheel_radius - wheel_vertical_offset}" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="base_footprint" />
|
||||
<child link="chassis_link" />
|
||||
</joint> -->
|
||||
|
||||
<link name="inertial_link">
|
||||
<inertial>
|
||||
<mass value="40" />
|
||||
<!-- <mass value="50" /> -->
|
||||
<!-- <origin xyz="-0.00065 -0.085 0.062" />
|
||||
<inertia ixx="0.6022" ixy="-0.02364" ixz="-0.1197" iyy="1.7386" iyz="-0.001544" izz="2.0296" /> -->
|
||||
<origin xyz="0.0 0.0 0.0" />
|
||||
<inertia ixx="2.288641" ixy="0" ixz="0" iyy="5.103976" iyz="0" izz="3.431465" />
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<joint name="inertial_joint" type="fixed">
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<parent link="base_link" />
|
||||
<child link="inertial_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> -->
|
||||
|
||||
<!-- Scout wheel macros -->
|
||||
<!-- wheel labeled from 0 to 3, conter-clockwise, starting from front right wheel -->
|
||||
<!-- motor 1 and 2 (left side) are mechanically installed in a reversed direction -->
|
||||
|
||||
Reference in New Issue
Block a user