mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 03:15:01 +08:00
278 lines
9.8 KiB
XML
278 lines
9.8 KiB
XML
<?xml version="1.0" encoding="utf-8"?>
|
|
<!-- =================================================================================== -->
|
|
<!-- | This document was autogenerated by xacro from scout_v2.xacro | -->
|
|
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
|
<!-- =================================================================================== -->
|
|
<robot name="scout_v2">
|
|
<!-- Virtual link as root -->
|
|
<link name="vehicle_reference"/>
|
|
<joint name="veh_ref_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<parent link="vehicle_reference"/>
|
|
<child link="base_link"/>
|
|
</joint>
|
|
<!-- Base link -->
|
|
<link name="base_link">
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<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 rpy="0 0 0" xyz="0 0 0.008"/>
|
|
<geometry>
|
|
<box size="0.925 0.38 0.21"/>
|
|
</geometry>
|
|
</collision>
|
|
<collision>
|
|
<origin rpy="0 0 0" xyz="0 0 0.035"/>
|
|
<geometry>
|
|
<box size="0.154166666667 0.627 0.07"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<!-- Base footprint: base_link projected to the gound plane -->
|
|
<link name="base_footprint"/>
|
|
<joint name="base_footprint_joint" type="fixed">
|
|
<origin rpy="0 0 0" xyz="0 0 -0.23479"/>
|
|
<parent link="base_link"/>
|
|
<child link="base_footprint"/>
|
|
</joint>
|
|
<link name="front_right_wheel_link">
|
|
<inertial>
|
|
<mass value="3"/>
|
|
<origin xyz="0 0 0"/>
|
|
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://scout_description/meshes/wheel_type1.dae"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<cylinder length="0.11653" radius="0.16459"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="front_right_wheel" type="continuous">
|
|
<parent link="base_link"/>
|
|
<child link="front_right_wheel_link"/>
|
|
<origin rpy="3.14 0 0" xyz="0.249 -0.29153 -0.0702"/>
|
|
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
|
</joint>
|
|
<link name="front_left_wheel_link">
|
|
<inertial>
|
|
<mass value="3"/>
|
|
<origin xyz="0 0 0"/>
|
|
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://scout_description/meshes/wheel_type2.dae"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<cylinder length="0.11653" radius="0.16459"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="front_left_wheel" type="continuous">
|
|
<parent link="base_link"/>
|
|
<child link="front_left_wheel_link"/>
|
|
<origin rpy="0 0 0" xyz="0.249 0.29153 -0.0702"/>
|
|
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
|
</joint>
|
|
<link name="rear_left_wheel_link">
|
|
<inertial>
|
|
<mass value="3"/>
|
|
<origin xyz="0 0 0"/>
|
|
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://scout_description/meshes/wheel_type1.dae"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<cylinder length="0.11653" radius="0.16459"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="rear_left_wheel" type="continuous">
|
|
<parent link="base_link"/>
|
|
<child link="rear_left_wheel_link"/>
|
|
<origin rpy="0 0 0" xyz="-0.249 0.29153 -0.0702"/>
|
|
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
|
</joint>
|
|
<link name="rear_right_wheel_link">
|
|
<inertial>
|
|
<mass value="3"/>
|
|
<origin xyz="0 0 0"/>
|
|
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
|
</inertial>
|
|
<visual>
|
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="package://scout_description/meshes/wheel_type2.dae"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<cylinder length="0.11653" radius="0.16459"/>
|
|
</geometry>
|
|
</collision>
|
|
</link>
|
|
<joint name="rear_right_wheel" type="continuous">
|
|
<parent link="base_link"/>
|
|
<child link="rear_right_wheel_link"/>
|
|
<origin rpy="3.14 0 0" xyz="-0.249 -0.29153 -0.0702"/>
|
|
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
|
</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> -->
|
|
<!-- This file is a placeholder which is included by default from
|
|
husky.urdf.xacro. If a robot is being customized and requires
|
|
additional URDF, set the HUSKY_URDF_EXTRAS environment variable
|
|
to the full path of the file you would like included. -->
|
|
<!-- Additional definitions for simulation -->
|
|
<!-- <gazebo reference="base_link">
|
|
<material>Gazebo/Grey</material>
|
|
</gazebo> -->
|
|
<!-- kp spring constant, kd damping constant -->
|
|
<gazebo reference="front_right_wheel_link">
|
|
<mu1 value="1.0"/>
|
|
<mu2 value="1.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<fdir1 value="1 0 0"/>
|
|
<minDepth value="0.001"/>
|
|
<maxContacts value="64"/>
|
|
</gazebo>
|
|
<transmission name="front_right_wheel_trans" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<actuator name="front_right_wheel_motor">
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
<joint name="front_right_wheel">
|
|
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
</joint>
|
|
</transmission>
|
|
<!-- kp spring constant, kd damping constant -->
|
|
<gazebo reference="front_left_wheel_link">
|
|
<mu1 value="1.0"/>
|
|
<mu2 value="1.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<fdir1 value="1 0 0"/>
|
|
<minDepth value="0.001"/>
|
|
<maxContacts value="64"/>
|
|
</gazebo>
|
|
<transmission name="front_left_wheel_trans" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<actuator name="front_left_wheel_motor">
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
<joint name="front_left_wheel">
|
|
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
</joint>
|
|
</transmission>
|
|
<!-- kp spring constant, kd damping constant -->
|
|
<gazebo reference="rear_left_wheel_link">
|
|
<mu1 value="1.0"/>
|
|
<mu2 value="1.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<fdir1 value="1 0 0"/>
|
|
<minDepth value="0.001"/>
|
|
<maxContacts value="64"/>
|
|
</gazebo>
|
|
<transmission name="rear_left_wheel_trans" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<actuator name="rear_left_wheel_motor">
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
<joint name="rear_left_wheel">
|
|
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
</joint>
|
|
</transmission>
|
|
<!-- kp spring constant, kd damping constant -->
|
|
<gazebo reference="rear_right_wheel_link">
|
|
<mu1 value="1.0"/>
|
|
<mu2 value="1.0"/>
|
|
<kp value="10000000.0"/>
|
|
<kd value="1.0"/>
|
|
<fdir1 value="1 0 0"/>
|
|
<minDepth value="0.001"/>
|
|
<maxContacts value="64"/>
|
|
</gazebo>
|
|
<transmission name="rear_right_wheel_trans" type="SimpleTransmission">
|
|
<type>transmission_interface/SimpleTransmission</type>
|
|
<actuator name="rear_right_wheel_motor">
|
|
<mechanicalReduction>1</mechanicalReduction>
|
|
</actuator>
|
|
<joint name="rear_right_wheel">
|
|
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
|
|
</joint>
|
|
</transmission>
|
|
<!-- Controller configurations -->
|
|
<gazebo>
|
|
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
|
|
<robotNamespace>/</robotNamespace>
|
|
</plugin>
|
|
</gazebo>
|
|
<!-- <gazebo>
|
|
<plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
|
|
<updateRate>100.0</updateRate>
|
|
<robotNamespace></robotNamespace>
|
|
<leftFrontJoint>front_left_wheel</leftFrontJoint>
|
|
<rightFrontJoint>front_right_wheel</rightFrontJoint>
|
|
<leftRearJoint>rear_left_wheel</leftRearJoint>
|
|
<rightRearJoint>rear_right_wheel</rightRearJoint>
|
|
<wheelSeparation>4</wheelSeparation>
|
|
<wheelDiameter>0.32918</wheelDiameter>
|
|
<robotBaseFrame>base_link</robotBaseFrame>
|
|
<torque>1000</torque>
|
|
<commandTopic>cmd_vel</commandTopic>
|
|
<broadcastTF>true</broadcastTF>
|
|
<odometryTopic>odom</odometryTopic>
|
|
<odometryFrame>odom</odometryFrame>
|
|
<covariance_x>0.000100</covariance_x>
|
|
<covariance_y>0.000100</covariance_y>
|
|
<covariance_yaw>0.010000</covariance_yaw>
|
|
</plugin>
|
|
</gazebo> -->
|
|
<!-- <gazebo>
|
|
<plugin name="object_controller" filename="libgazebo_ros_planar_move.so">
|
|
<commandTopic>cmd_vel</commandTopic>
|
|
<odometryTopic>odom</odometryTopic>
|
|
<odometryFrame>odom</odometryFrame>
|
|
<odometryRate>20.0</odometryRate>
|
|
<robotBaseFrame>base_footprint</robotBaseFrame>
|
|
</plugin>
|
|
</gazebo> -->
|
|
</robot>
|