gazebo小车模型(附带仿真环境)

博客地址:https://www.cnblogs.com/zylyehuo/

参考链接

1、(https://blog.csdn.net/qq_43406338/article/details/109600827?ops_request_misc={"request_id"%3A"168087043216800182749128"%2C"scm"%3A"20140713.130102334.pc_all."}&request_id=168087043216800182749128&biz_id=0&utm_medium=distribute.pc_search_result.none-task-blog-2allfirst_rank_ecpm_v1~rank_v31_ecpm-1-109600827-null-null.142v82insert_down1,201v4add_ask,239v2insert_chatgpt&utm_term=Resource not found%3A gazebo_ros ROS path [0]%3D%2Fopt%2Fros%2Fmelodic%2Fshare%2Fros ROS path [1]%3D%2Fhome%2Fyehuo%2Fmycar_ws%2Fsrc ROS path [2]%3D%2Fopt%2Fros%2Fmelodic%2Fshare The traceback for the exception was written to the log &spm=1018.2226.3001.4187)
2、(https://blog.csdn.net/samsu0108/article/details/121686776?ops_request_misc=&request_id=&biz_id=102&utm_term=[Err] [REST.cc:205] Error in R&utm_medium=distribute.pc_search_result.none-task-blog-2allsobaiduweb~default-0-121686776.142v82insert_down1,201v4add_ask,239v2insert_chatgpt&spm=1018.2226.3001.4187)
3、(https://blog.csdn.net/qq_39400324/article/details/125051463?ops_request_misc=&request_id=&biz_id=102&utm_term=Error [Converter.cc:151] Unabl&utm_medium=distribute.pc_search_result.none-task-blog-2allsobaiduweb~default-0-125051463.142v82insert_down1,201v4add_ask,239v2insert_chatgpt&spm=1018.2226.3001.4187)
4、(http://www.autolabor.com.cn/book/ROSTutorials/di-6-zhang-ji-qi-ren-xi-tong-fang-zhen/66-urdfji-cheng-gazebo.html)
5、(https://www.bilibili.com/video/BV1Ci4y1L7ZZ?p=271&vd_source=4acdb875c05ce9dccfce3cd6cfaac651)

成果图

STEP1:创建工作空间

mkdir -p mycar_ws/src
cd mycar_ws
catkin_make

STEP2:在vscode中准备需要的文件夹

右键src,点击Create Catkin Package
先输入包名:mycar
再输入依赖工具:urdf xacro gazebo_ros gazebo_ros_control gazebo_plugins

STEP3:在vscode中准备需要的文件夹

在mycar目录下依次创建 launch、urdf、worlds文件夹
在 mycar/urdf 文件夹下再创建 xacro文件夹
结构如下图所示

STEP4:mycar/launch

创建 environment.launch 文件

mycar/launch/environment.launch

<launch>

    <param name="robot_description" command="$(find xacro)/xacro $(find mycar)/urdf/xacro/car.urdf.xacro" />

    <include file="$(find gazebo_ros)/launch/empty_world.launch">
        <arg name="world_name" value="$(find mycar)/worlds/box_house.world" />
    </include>

    <node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description"  />
</launch>

STEP5:下载worlds文件夹下需要的文件

终端输入命令
git clone https://github.com/zx595306686/sim_demo.git
得到以下文件

将第三个文件 box_house.world 复制到mycar_ws中创建的worlds文件夹下

STEP6:mycar/urdf/xacro

创建以下文件

mycar/urdf/xacro/car_base.urdf.xacro

<robot name="mycar" xmlns:xacro="http://www.ros.org/wiki/xacro">

    <xacro:property name="PI" value="3.141"/>

    <material name="black">
        <color rgba="0.0 0.0 0.0 1.0" />
    </material>

    <xacro:property name="footprint_radius" value="0.001" /> 
    <xacro:property name="base_radius" value="0.1" /> 
    <xacro:property name="base_length" value="0.08" /> 
    <xacro:property name="earth_space" value="0.015" /> 
     <xacro:property name="base_joint_z" value="${base_length / 2 + earth_space}" /> 

     <xacro:property name="base_mass" value="2" /> 

    <!-- base -->
    <link name="base_footprint">
      <visual>
        <geometry>
          <sphere radius="${footprint_radius}" />
        </geometry>
      </visual>
    </link>

    <link name="base_link">
      <visual>
        <geometry>
          <cylinder radius="${base_radius}" length="${base_length}" />
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <material name="baselink_color">
          <color rgba="1.0 0.5 0.2 0.7" />
        </material>
      </visual>

      <collision>
        <geometry>
          <cylinder radius="${base_radius}" length="${base_length}" />
        </geometry>
        <origin xyz="0 0 0" rpy="0 0 0" />
      </collision>
      <xacro:cylinder_inertial_matrix m="${base_mass}" r="${base_radius}" h="${base_length}" />

    </link>

    <gazebo reference="base_link">
        <material>Gazebo/Yellow</material>
    </gazebo>

    <joint name="link2footprint" type="fixed">
      <parent link="base_footprint" />
      <child link="base_link" />
      <origin xyz="0 0 ${earth_space + base_length / 2 }"  rpy="0 0 0"/>
    </joint>

    <!-- qudong wheel -->
    <xacro:property name="wheel_radius" value="0.0325" />
    <xacro:property name="wheel_length" value="0.015" />
    <xacro:property name="wheel_mass" value="0.05" />
    
    <xacro:macro name="add_wheels" params="name flag">
      <link name="${name}_wheel">
        <visual>
          <geometry>
            <cylinder radius="${wheel_radius}" length="${wheel_length}" />
          </geometry>
          <origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
          <material name="black" />
        </visual>

        <collision>
          <geometry>
            <cylinder radius="${wheel_radius}" length="${wheel_length}" />
          </geometry>
          <origin xyz="0.0 0.0 0.0" rpy="${PI / 2} 0.0 0.0" />
        </collision>
        <xacro:cylinder_inertial_matrix m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}" />

      </link>

      <gazebo reference="${name}_wheel">
        <material>Gazebo/Red</material>
      </gazebo>

      <joint name="${name}_wheel2base_link" type="continuous">
        <parent link="base_link" />
        <child link="${name}_wheel" />
        <origin xyz="0 ${flag * base_radius} ${-(earth_space + base_length / 2 - wheel_radius) }" />
        <axis xyz="0 1 0" />
      </joint>
    </xacro:macro>
    <xacro:add_wheels name="left" flag="1" />
    <xacro:add_wheels name="right" flag="-1" />
 
    <!-- zhicheng/wanxiang wheel -->
    <xacro:property name="support_wheel_radius" value="0.0075" /> 
    <xacro:property name="support_wheel_mass" value="0.01" /> 

    <xacro:macro name="add_support_wheel" params="name flag" >
      <link name="${name}_wheel">
        <visual>
            <geometry>
                <sphere radius="${support_wheel_radius}" />
            </geometry>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <material name="black" />
        </visual>

        <collision>
            <geometry>
                <sphere radius="${support_wheel_radius}" />
            </geometry>
            <origin xyz="0 0 0" rpy="0 0 0" />
        </collision>
        <xacro:sphere_inertial_matrix m="${support_wheel_mass}" r="${support_wheel_radius}" />

      </link>

      <gazebo reference="${name}_wheel">
        <material>Gazebo/Red</material>
      </gazebo>

      <joint name="${name}_wheel2base_link" type="continuous">
          <parent link="base_link" />
          <child link="${name}_wheel" />
          <origin xyz="${flag * (base_radius - support_wheel_radius)} 0 ${-(base_length / 2 + earth_space / 2)}" />
          <axis xyz="1 1 1" />
      </joint>
    </xacro:macro>

    <xacro:add_support_wheel name="front" flag="1" />
    <xacro:add_support_wheel name="back" flag="-1" />

</robot>

mycar/urdf/xacro/car_camera.urdf.xacro

<robot name="my_camera" xmlns:xacro="http://wiki.ros.org/xacro">

    <xacro:property name="camera_length" value="0.01" />
    <xacro:property name="camera_width" value="0.025" /> 
    <xacro:property name="camera_height" value="0.025" /> 
    <xacro:property name="camera_x" value="0.08" />
    <xacro:property name="camera_y" value="0.0" /> 
    <xacro:property name="camera_z" value="${base_length / 2 + camera_height / 2}" /> 
    <xacro:property name="camera_mass" value="0.01" />

   
    <link name="camera">
        <visual>
            <geometry>
                <box size="${camera_length} ${camera_width} ${camera_height}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
            <material name="black" />
        </visual>

        <collision>
            <geometry>
                <box size="${camera_length} ${camera_width} ${camera_height}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
        </collision>
        <xacro:Box_inertial_matrix m="${camera_mass}" l="${camera_length}" w="${camera_width}" h="${camera_height}" />

    </link>

    <gazebo reference="camera">
        <material>Gazebo/Blue</material>
    </gazebo>


    <joint name="camera2base_link" type="fixed">
        <parent link="base_link" />
        <child link="camera" />
        <origin xyz="${camera_x} ${camera_y} ${camera_z}" />
    </joint>
    
</robot>

mycar/urdf/xacro/car_laser.urdf.xacro

<robot name="my_laser" xmlns:xacro="http://wiki.ros.org/xacro">

    <xacro:property name="support_length" value="0.15" /> 
    <xacro:property name="support_radius" value="0.01" /> 
    <xacro:property name="support_x" value="0.0" /> 
    <xacro:property name="support_y" value="0.0" /> 
    <xacro:property name="support_z" value="${base_length / 2 + support_length / 2}" /> 
    <xacro:property name="support_mass" value="0.02" /> 


    <link name="support">
        <visual>
            <geometry>
                <cylinder radius="${support_radius}" length="${support_length}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
            <material name="red">
                <color rgba="0.8 0.2 0.0 0.8" />
            </material>
        </visual>

        <collision>
            <geometry>
                <cylinder radius="${support_radius}" length="${support_length}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
        </collision>

        <xacro:cylinder_inertial_matrix m="${support_mass}" r="${support_radius}" h="${support_length}" />

    </link>

    <gazebo reference="support">
        <material>Gazebo/Grey</material>
    </gazebo>

    <joint name="support2base_link" type="fixed">
        <parent link="base_link" />
        <child link="support" />
        <origin xyz="${support_x} ${support_y} ${support_z}" />
    </joint>


    <xacro:property name="laser_length" value="0.05" />
    <xacro:property name="laser_radius" value="0.03" />
    <xacro:property name="laser_x" value="0.0" />
    <xacro:property name="laser_y" value="0.0" /> 
    <xacro:property name="laser_z" value="${support_length / 2 + laser_length / 2}" /> 
     <xacro:property name="laser_mass" value="0.1" />

  
    <link name="laser">
        <visual>
            <geometry>
                <cylinder radius="${laser_radius}" length="${laser_length}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
            <material name="black" />
        </visual>

        <collision>
            <geometry>
                <cylinder radius="${laser_radius}" length="${laser_length}" />
            </geometry>
            <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
        </collision>
        <xacro:cylinder_inertial_matrix m="${laser_mass}" r="${laser_radius}" h="${laser_length}" />

    </link>

    <gazebo reference="laser">
        <material>Gazebo/Black</material>
    </gazebo>

    <joint name="laser2support" type="fixed">
        <parent link="support" />
        <child link="laser" />
        <origin xyz="${laser_x} ${laser_y} ${laser_z}" />
    </joint>

</robot>

mycar/urdf/xacro/car.urdf.xacro

<robot name="car" xmlns:xacro="http://wiki.ros.org/xacro">
    <xacro:include filename="inertial_matrix.xacro" />
    <xacro:include filename="car_base.urdf.xacro" />
    <xacro:include filename="car_camera.urdf.xacro" />
    <xacro:include filename="car_laser.urdf.xacro" />
</robot>

mycar/urdf/xacro/inertial_matrix.xacro

<robot name="base" xmlns:xacro="http://wiki.ros.org/xacro">
    <!-- Macro for inertia matrix -->
    <xacro:macro name="sphere_inertial_matrix" params="m r">
        <inertial>
            <mass value="${m}" />
            <inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"
                iyy="${2*m*r*r/5}" iyz="0" 
                izz="${2*m*r*r/5}" />
        </inertial>
    </xacro:macro>

    <xacro:macro name="cylinder_inertial_matrix" params="m r h">
        <inertial>
            <mass value="${m}" />
            <inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
                iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
                izz="${m*r*r/2}" /> 
        </inertial>
    </xacro:macro>

    <xacro:macro name="Box_inertial_matrix" params="m l w h">
       <inertial>
               <mass value="${m}" />
               <inertia ixx="${m*(h*h + l*l)/12}" ixy = "0" ixz = "0"
                   iyy="${m*(w*w + l*l)/12}" iyz= "0"
                   izz="${m*(w*w + h*h)/12}" />
       </inertial>
   </xacro:macro>
</robot>

STEP7:运行

启动 roscore

建议在vscode外终端启动(也可在vscode中启动)

设置环境变量,启动gazebo

在vscode中新建终端
注意要进入 mycar_ws 路径下
依次执行以下命令

出现如下画面即代表创建成功
第一次创建时可检查一下左栏选项是否一致

常见问题汇总

1、ResourceNotFound: gazebo_ros

ResourceNotFound: gazebo_ros
ROS path [0]=/opt/ros/kinetic/share/ros
ROS path [1]=/home/park/catkin_ws/src
ROS path [2]=/opt/ros/kinetic/share
问题:找不到资源
解决办法:直接安装缺失的gazebo:
$ sudo apt-get install ros-kinetic-gazebo-ros-pkgs ros-kinetic-gazebo-ros-control

2、[Err] [REST.cc:205] Error in REST request Gazebo 启动报错

1、在终端输入命令
   sudo vim ~/.ignition/fuel/config.yaml
2、将https://api.ignitionfuel.org替换为https://fuel.ignitionrobotics.org

3、Unable to convert from SDF version 1.7 to 1.6

将 environment.world文件 中第一行的<sdf version = '1.7'>该为<sdf version = '1.6'>即可。
posted @ 2023-04-08 15:17  zylyehuo  阅读(765)  评论(0编辑  收藏  举报