updated scout v2 urdf

This commit is contained in:
Ruixiang Du
2020-03-24 22:48:57 +08:00
parent f249b5147b
commit 5279161dbf
9 changed files with 1167 additions and 546 deletions

View File

@@ -0,0 +1,45 @@
<?xml version="1.0"?>
<robot>
<!-- <gazebo reference="base_link">
<material>Gazebo/Grey</material>
</gazebo> -->
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<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>
<!-- <topicName>cmd_vel</topicName> -->
<commandTopic>cmd_vel</commandTopic>
<broadcastTF>1</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>

View File

@@ -28,7 +28,7 @@
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://scout_description/meshes/body_assembly.dae" />
<mesh filename="package://scout_description/meshes/base_link.dae" />
</geometry>
</visual>
<collision>
@@ -69,13 +69,15 @@
<child link="inertial_link" />
</joint>
<!-- scout wheel macros -->
<xacro:scout_wheel_type2 wheel_prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:scout_wheel_type2>
<!-- 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 -->
<xacro:scout_wheel_type1 wheel_prefix="front_right">
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
</xacro:scout_wheel_type1>
<xacro:scout_wheel_type2 wheel_prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:scout_wheel_type2>
<xacro:scout_wheel_type1 wheel_prefix="rear_left">
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:scout_wheel_type1>
@@ -83,54 +85,18 @@
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
</xacro:scout_wheel_type2>
<!-- IMU Link is the standard mounting position for the UM6 IMU.-->
<!-- Can be modified with environment variables in /etc/ros/setup.bash -->
<!-- <link name="imu_link"/>
<joint name="imu_joint" type="fixed">
<origin xyz="$(optenv scout_IMU_XYZ 0.19 0 0.149)" rpy="$(optenv scout_IMU_RPY 0 -1.5708 3.1416)" />
<parent link="base_link" />
<child link="imu_link" />
</joint>
<gazebo reference="imu_link">
</gazebo> -->
<!-- <xacro:scout_decorate /> -->
<!-- For testing, hang the robot up in the air -->
<!-- <link name="world" />
<joint name="world_to_base_link=" type="fixed">
<origin xyz="0 0 1.0" rpy="0 0 0" />
<parent link="world"/>
<child link="base_link"/>
</joint> -->
<!-- <gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
</plugin>
</gazebo>
<gazebo>
<plugin name="imu_controller" filename="libhector_gazebo_ros_imu.so">
<updateRate>50.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>imu/data</topicName>
<accelDrift>0.005 0.005 0.005</accelDrift>
<accelGaussianNoise>0.005 0.005 0.005</accelGaussianNoise>
<rateDrift>0.005 0.005 0.005 </rateDrift>
<rateGaussianNoise>0.005 0.005 0.005 </rateGaussianNoise>
<headingDrift>0.005</headingDrift>
<headingGaussianNoise>0.005</headingGaussianNoise>
</plugin>
</gazebo>
<gazebo>
<plugin name="gps_controller" filename="libhector_gazebo_ros_gps.so">
<updateRate>40</updateRate>
<bodyName>base_link</bodyName>
<frameId>base_link</frameId>
<topicName>navsat/fix</topicName>
<velocityTopicName>navsat/vel</velocityTopicName>
<referenceLatitude>49.9</referenceLatitude>
<referenceLongitude>8.9</referenceLongitude>
<referenceHeading>0</referenceHeading>
<referenceAltitude>0</referenceAltitude>
<drift>0.0001 0.0001 0.0001</drift>
</plugin>
</gazebo> -->
<!-- Optional custom includes. -->
<!-- <xacro:include filename="$(arg urdf_extras)" /> -->
<!-- Additional definitions -->
<xacro:include filename="$(arg urdf_extras)" />
<!-- Gazebo definitions -->
<xacro:include filename="$(find scout_description)/urdf/scout_v2.gazebo" />
</robot>

View File

@@ -0,0 +1,78 @@
<?xml version="1.0"?>
<!--
Software License Agreement (BSD)
\file scout_wheel.xacro (adapted from wheel.urdf.xacro in husky_description)
\authors Paul Bovbel <pbovbel@clearpathrobotics.com>
Ruixiang Du <ruixiang.du@westonrobot.com>
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
\copyright Copyright (c) 2020, Weston Robot Pte. Ltd., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="scout_wheel">
<xacro:macro name="scout_wheel_type1" params="wheel_prefix *joint_pose">
<link name="${wheel_prefix}_wheel_link">
<inertial>
<mass value="2.637" />
<origin xyz="0 0 0" />
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.04411" iyz="0" izz="0.02467" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://scout_description/meshes/wheel_type1.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder length="${wheel_length}" radius="${wheel_radius}" />
</geometry>
</collision>
</link>
<joint name="${wheel_prefix}_wheel" type="continuous">
<parent link="base_link"/>
<child link="${wheel_prefix}_wheel_link"/>
<xacro:insert_block name="joint_pose"/>
<axis xyz="0 -1 0" rpy="0 0 0" />
</joint>
<!-- <transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${wheel_prefix}_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="${wheel_prefix}_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission> -->
<!-- Gazebo definitions -->
<gazebo reference="${wheel_prefix}_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="1 0 0"/>
</gazebo>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,78 @@
<?xml version="1.0"?>
<!--
Software License Agreement (BSD)
\file scout_wheel.xacro (adapted from wheel.urdf.xacro in husky_description)
\authors Paul Bovbel <pbovbel@clearpathrobotics.com>
Ruixiang Du <ruixiang.du@westonrobot.com>
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
\copyright Copyright (c) 2020, Weston Robot Pte. Ltd., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="scout_wheel">
<xacro:macro name="scout_wheel_type2" params="wheel_prefix *joint_pose">
<link name="${wheel_prefix}_wheel_link">
<inertial>
<mass value="2.637" />
<origin xyz="0 0 0" />
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.04411" iyz="0" izz="0.02467" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://scout_description/meshes/wheel_type2.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder length="${wheel_length}" radius="${wheel_radius}" />
</geometry>
</collision>
</link>
<joint name="${wheel_prefix}_wheel" type="continuous">
<parent link="base_link"/>
<child link="${wheel_prefix}_wheel_link"/>
<xacro:insert_block name="joint_pose"/>
<axis xyz="0 -1 0" rpy="0 0 0" />
</joint>
<!-- <transmission name="${wheel_prefix}_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="${wheel_prefix}_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="${wheel_prefix}_wheel">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
</transmission> -->
<!-- Gazebo definitions -->
<gazebo reference="${wheel_prefix}_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0" />
<kd value="1.0" />
<fdir1 value="1 0 0"/>
</gazebo>
</xacro:macro>
</robot>