gazebo小车——加上了激光雷达

用solidworks到处urdf还是比较方便的,xacro好,但是对我好像并没有什么用?

<?xml version="1.0" encoding="utf-8"?>


<robot
  name="mycar-080501">
  <gazebo reference="base_link"> 

     <material>Gazebo/Red </material>
  </gazebo>
  <gazebo reference="leftwheel_link"> 

     <material>Gazebo/Yellow </material>
  </gazebo>
  <gazebo reference="rightwheel_link"> 
     <material>Gazebo/Yellow </material>
  </gazebo>
  <gazebo reference="leftcastorwheel_link"> 
     <material>Gazebo/Black </material>
  </gazebo>
  <gazebo reference="rightcastorwheel_link"> 
     <material>Gazebo/Black </material>
  </gazebo>
  <gazebo reference="rightcastor_link"> 
     <material>Gazebo/Grey </material>
  </gazebo>
  <gazebo reference="leftcastor_link"> 
     <material>Gazebo/Grey </material>
  </gazebo>

  <gazebo reference="vlp_link"> 
     <material>Gazebo/Green </material>
  </gazebo>
 
  <link name="base_footprint">
        <visual>
            <origin xyz="0.041793 -0.00060626 0.19988" rpy="0 0 0" />
            <geometry>
                    <box size="0.001 0.001 0.001" />
            </geometry>
        </visual>
  </link>

  <joint name="base_footprint_joint" type="fixed">
            <origin xyz="0.041793 -0.00060626 0.19988" rpy="0 0 0" />
            <parent link="base_footprint"/>
            <child link="base_link" />
  </joint>
  <link
    name="base_link">
    <inertial>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <mass
        value="7.7302" />
      <inertia
        ixx="0.11154"
        ixy="-0.00075198"
        ixz="0.010376"
        iyy="0.21008"
        iyz="-0.00013307"
        izz="0.24146" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/base_link.STL" />
      </geometry>

    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/base_link.STL" />
      </geometry>
    </collision>
    <gazebo reference="base_link">
        <material name="Black">
        <color rgba="0 0 0 1"/>
    </material>
    </gazebo>
  </link>
  <link
    name="leftwheel_link">
    <inertial>
      <origin
        xyz="1.1102E-16 -2.7756E-17 4.4409E-16"
        rpy="0 0 0" />
      <mass
        value="1.6659" />
      <inertia
        ixx="0.0046446"
        ixy="8.5867E-18"
        ixz="2.1412E-18"
        iyy="0.0084051"
        iyz="1.7579E-19"
        izz="0.0046446" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/leftwheel_link.STL" />
      </geometry>

    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/leftwheel_link.STL" />
      </geometry>
    </collision>
    <gazebo reference="leftwheel_link">
      <material name="Blue">
        <color rgba="0 0 1 1"/>
      </material>
    </gazebo>
  </link>
  <joint
    name="leftwheel_joint"
    type="continuous">
    <origin
      xyz="0.15638 0.185 0.1"
      rpy="0 0 0" />
    <parent
      link="base_link" />
    <child
      link="leftwheel_link" />
    <axis
      xyz="0 1 0" />
  </joint>
  <link
    name="rightwheel_link">
    <inertial>
      <origin
        xyz="-4.7184E-16 2.7756E-17 -2.7756E-17"
        rpy="0 0 0" />
      <mass
        value="1.6659" />
      <inertia
        ixx="0.0046446"
        ixy="-7.0223E-19"
        ixz="1.1792E-17"
        iyy="0.0084051"
        iyz="3.1071E-17"
        izz="0.0046446" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/rightwheel_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.33333 0.33333 0.33333 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/rightwheel_link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="rightwheel_joint"
    type="continuous">
    <origin
      xyz="0.156380588704616 -0.184999999999995 0.0999999999999956"
      rpy="0 0 0" />
    <parent
      link="base_link" />
    <child
      link="rightwheel_link" />
    <axis
      xyz="0 1 0" />
  </joint>
  <link
    name="leftcastor_link">
    <inertial>
      <origin
        xyz="-0.014919 2.0333E-08 -0.034431"
        rpy="0 0 0" />
      <mass
        value="0.066308" />
      <inertia
        ixx="6.7914E-05"
        ixy="1.0208E-11"
        ixz="-9.9589E-06"
        iyy="6.8636E-05"
        iyz="-2.9374E-11"
        izz="6.2053E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/leftcastor_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.37255 0.37255 0.37255 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/leftcastor_link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="leftcastor_joint"
    type="continuous">
    <origin
      xyz="-0.15612 0.1585 0.115"
      rpy="0 0 0" />
    <parent
      link="base_link" />
    <child
      link="leftcastor_link" />
    <axis
      xyz="0 0 -1" />
  </joint>
  <link
    name="leftcastorwheel_link">
    <inertial>
      <origin
        xyz="2.498E-16 0 2.7756E-17"
        rpy="0 0 0" />
      <mass
        value="0.22508" />
      <inertia
        ixx="0.00015664"
        ixy="1.0696E-18"
        ixz="1.6255E-19"
        iyy="0.00027762"
        iyz="1.998E-19"
        izz="0.00015664" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/leftcastorwheel_link.STL" />
      </geometry>
      <material
        name="">
        <color
          rgba="0.50196 0.50196 0.50196 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/leftcastorwheel_link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="leftcastorwheel_joint"
    type="continuous">
    <origin
      xyz="-0.03725 0 -0.069"
      rpy="0 0 0" />
    <parent
      link="leftcastor_link" />
    <child
      link="leftcastorwheel_link" />
    <axis
      xyz="0 -1 0" />
  </joint>
  <link
    name="rightcastor_link">
    <inertial>
      <origin
        xyz="-0.014919 2.0333E-08 -0.034431"
        rpy="0 0 0" />
      <mass
        value="0.066308" />
      <inertia
        ixx="6.7914E-05"
        ixy="1.0208E-11"
        ixz="-9.9589E-06"
        iyy="6.8636E-05"
        iyz="-2.9374E-11"
        izz="6.2053E-05" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/rightcastor_link.STL" />
      </geometry>
      <material
        name="gray">
        <color
          rgba="0.37255 0.37255 0.37255 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/rightcastor_link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="rightcastor_joint"
    type="continuous">
    <origin
      xyz="-0.15612 -0.1585 0.115"
      rpy="0 0 0" />
    <parent
      link="base_link" />
    <child
      link="rightcastor_link" />
    <axis
      xyz="0 0 -1" />
  </joint>
  <link
    name="rightcastorwheel_link">
    <inertial>
      <origin
        xyz="6.7168E-15 -2.0539E-15 4.7184E-16"
        rpy="0 0 0" />
      <mass
        value="0.22508" />
      <inertia
        ixx="0.00015664"
        ixy="1.8282E-21"
        ixz="-5.501E-19"
        iyy="0.00027762"
        iyz="-6.8108E-21"
        izz="0.00015664" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/rightcastorwheel_link.STL" />
      </geometry>
      <material
        name="green">
        <color
          rgba="0.50196 0.50196 0.50196 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/rightcastorwheel_link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="rightcastorwheel_joint"
    type="continuous">
    <origin
      xyz="-0.03725 0 -0.069"
      rpy="0 0 0" />
    <parent
      link="rightcastor_link" />
    <child
      link="rightcastorwheel_link" />
    <axis
      xyz="0 -1 0" />
  </joint>


  <link
    name="vlp_link">
    <inertial>
      <origin
        xyz="-7.5151E-05 -2.5877E-06 0.035859"
        rpy="0 0 0" />
      <mass
        value="0.45" />
      <inertia
        ixx="0.0049102"
        ixy="1.8101E-09"
        ixz="-9.8635E-06"
        iyy="0.0049341"
        iyz="-3.8995E-07"
        izz="0.005856" />
    </inertial>
    <visual>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/VLP_link.STL" />
      </geometry>
      <material
        name="balck">
        <color
          rgba="0 0.75294 0 1" />
      </material>
    </visual>
    <collision>
      <origin
        xyz="0 0 0"
        rpy="0 0 0" />
      <geometry>
        <mesh
          filename="package://mycar-080501/meshes/VLP_link.STL" />
      </geometry>
    </collision>
  </link>
  <joint
    name="vlp_Joint"
    type="fixed">
    <origin
      xyz="0.15 0 0.304"
      rpy="0 0 0" />
    <parent
      link="base_link" />
    <child
      link="vlp_link" />
    <axis
      xyz="0 0 0" />
  </joint>
  <!-- controller -->
        <gazebo>
            <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
                <rosDebugLevel>Debug</rosDebugLevel>
                <publishWheelTF>true</publishWheelTF>
                <robotNamespace>/</robotNamespace>
                <publishTf>1</publishTf>
                <publishWheelJointState>true</publishWheelJointState>
                <alwaysOn>true</alwaysOn>
                <updateRate>100.0</updateRate>
                <legacyMode>true</legacyMode>
                <leftJoint>rightwheel_joint</leftJoint>
                <rightJoint>leftwheel_joint</rightJoint>
                <wheelSeparation>0.4</wheelSeparation>
                <wheelDiameter>0.2</wheelDiameter>
                <broadcastTF>1</broadcastTF>
                <wheelTorque>30</wheelTorque>
                <wheelAcceleration>1.8</wheelAcceleration>
                <commandTopic>cmd_vel</commandTopic>
                <odometryFrame>odom</odometryFrame> 
                <odometryTopic>odom</odometryTopic> 
                <!-- odometrySource>world </odometrySource><publishOdomTF> False</publishOdomTF> -->
                
                <robotBaseFrame>base_footprint</robotBaseFrame>
            </plugin>
       </gazebo> 
        <gazebo reference="vlp_link">
            <sensor type="ray" name="rplidar">
                <pose>0 0 0 0 0 0</pose>
                <visualize>false</visualize>
                <update_rate>5.5</update_rate>
                <ray>
                    <scan>
                      <horizontal>
                        <samples>360</samples>
                        <resolution>1</resolution>
                        <min_angle>-3</min_angle>
                        <max_angle>3</max_angle>
                      </horizontal>
                    </scan>
                    <range>
                      <min>0.10</min>
                      <max>6.0</max>
                      <resolution>0.01</resolution>
                    </range>
                    <noise>
                      <type>gaussian</type>
                      <mean>0.0</mean>
                      <stddev>0.01</stddev>
                    </noise>
                </ray>
                <plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
                    <topicName>/scan</topicName>
                    <frameName>vlp_link</frameName>
                </plugin>
            </sensor>
        </gazebo>

</robot>

有时间我一定要研究下博客园里面的markdown缩进,代码太长了,真的难受看着。
launch 文件内容为

<launch>

  <arg name="world_name" value="$(find ros_robotic)/worlds/playground.world"/>
    <arg name="paused" default="false"/>
    <arg name="use_sim_time" default="true"/>
    <arg name="gui" default="true"/>
    <arg name="headless" default="false"/>
    <arg name="debug" default="false"/>
    <arg name="model" default="$(find mycar-080501)/urdf/mycar-080501.urdf"/>
    <!-- 运行gazebo仿真环境 -->
    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <arg name="debug" value="$(arg debug)" />
        <arg name="gui" value="$(arg gui)" />
        <arg name="paused" value="$(arg paused)"/>
        <arg name="use_sim_time" value="$(arg use_sim_time)"/>
        <arg name="headless" value="$(arg headless)"/>
    </include>
  <param name="robot_description" command="$(find xacro)/xacro --inorder $(arg model)" />

    <node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node> 

    <!-- 运行robot_state_publisher节点,发布tf  -->
    <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"  output="screen" >
        <param name="publish_frequency" type="double" value="50.0" />
    </node>

    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" args=" -urdf -model mycar-080501 -param robot_description" respawn="false" output="screen" /> 

</launch>
原文地址:https://www.cnblogs.com/robohou/p/13449572.html