fixed state publish rate error (from 20hz to 50hz), gazebo scout v2 sim ready

This commit is contained in:
Ruixiang Du
2020-04-02 11:43:29 +08:00
parent a1efd5b609
commit f73a2e2f59
15 changed files with 392 additions and 368 deletions

View File

@@ -1,10 +1,12 @@
<?xml version="1.0"?>
<!--
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
[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" />

View File

@@ -1,277 +0,0 @@
<?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>

View File

@@ -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 -->