【环境配置】gazebo搭建仿真机器人研究动态障碍物算法

本文详细记录了作者在ROS中搭建仿真环境的过程,包括Gazebo的使用,四轮机器人模型从麦克纳姆轮转换为阿克曼模型的配置,以及障碍物小车的设定。作者遇到困难后决定基于现有模型进行修改,并成功添加了Velodyne激光雷达。此外,还介绍了如何为动态障碍物添加碰撞属性。

摘要生成于 C知道 ,由 DeepSeek-R1 满血版支持, 前往体验 >

0前言

最近由于实验过程中遇到一些问题,打算直接仿真了,利用一个月时间把整体的仿真环境搭建出来,这里对最近的学习成果,进行梳理.

1Gazebo

学习准备:

  • urdf基本语法
  • xacro基本语法
  • 一个机器人包含:link and joint,link代表每一节刚体,joint代表刚体之间的运动关系
  • ros_control插件,用于代替实体驱动板或者下位控制器

搭建步骤:

  1. solidworks导出stl dae文件(可选)
  2. 宏定义
  3. 刚体,关节定义
  4. 由于gazebo是物理引擎,每个部分必须包含惯性矩阵和碰撞属性,颜色跟RVIZ系统不一样,需要另外设置
  5. 为关节添加传动属性
  6. ros_control配置,每个传动关节订阅的话题和发布的话题,用于控制和检测
  7. 移动机器人可设置差速模型(可选)
  8. ros话题与发布配置一些底层驱动文件,如差速模型,阿克曼模型

2准备搭建

2.1工程移植

因为我的研究方向是算法,一些工作自己去做,偏离了搭建仿真环境的本意,我就直接download别人的SolidWorks文件和Gazebo仿真环境,在这些模型的基础上,修改成自己心仪的仿真环境,由于源文件工程是麦克纳姆轮的转向灵活,但是仿真模型里卡顿,我打算将其改成阿卡曼模型,正好熟悉一些整个机器人配置过程,待续…
在这里插入图片描述

四轮阿克曼模型

	<!-- skid steering plugin -->
	<xacro:macro name="skid_steering" params="broadcastOdomTF">
    <gazebo>
      <plugin name="skid_steer_drive_controller" filename="libgazebo_ros_skid_steer_drive.so">
			<robotNamespace>/summit_xl</robotNamespace>
		    <updateRate>100.0</updateRate>
		    <leftFrontJoint>joint_front_left_wheel</leftFrontJoint>  
		    <rightFrontJoint>joint_front_right_wheel</rightFrontJoint>
		    <leftRearJoint>joint_back_left_wheel</leftRearJoint>
		    <rightRearJoint>joint_back_right_wheel</rightRearJoint>
			<covariance_x>0.0001</covariance_x>
			<covariance_y>0.0001</covariance_y>
			<covariance_yaw>0.01</covariance_yaw>
		    <!-- wheelSeparation>0.566</wheelSeparation --> <!-- real parameter value -->
		    <wheelSeparation>1.5</wheelSeparation> <!-- works a bit better in Gazebo -->
		    <wheelDiameter>0.234</wheelDiameter>
		    <robotBaseFrame>base_footprint</robotBaseFrame>
		    <torque>50</torque>
		    <commandTopic>/summit_xl_control/cmd_vel</commandTopic>
		    <odometryTopic>odom</odometryTopic>
		    <odometryFrame>/odom</odometryFrame>
		    <broadcastTF>${broadcastOdomTF}</broadcastTF>
      </plugin>
    </gazebo>
  </xacro:macro>

两轮差速

        <!-- controller -->
 	<xacro:macro name="diff">
          <gazebo>
              <plugin name="differential_drive_controller"
                      filename="libgazebo_ros_diff_drive.so">
                  <rosDebugLevel>Debug</rosDebugLevel>
                  <publishWheelTF>true</publishWheelTF>
                  <robotNamespace>/summit_xl</robotNamespace>
                  <publishTf>1</publishTf>
                  <publishWheelJointState>true</publishWheelJointState>
                  <alwaysOn>true</alwaysOn>
                  <updateRate>100.0</updateRate>
                  <legacyMode>true</legacyMode>
                  <leftJoint>joint_back_left_wheel</leftJoint>
                  <rightJoint>joint_back_right_wheel</rightJoint>
                  <wheelSeparation>1.5</wheelSeparation>
                  <wheelDiameter>0.234</wheelDiameter>
                  <broadcastTF>1</broadcastTF>
                  <wheelTorque>30</wheelTorque>
                  <wheelAcceleration>1.8</wheelAcceleration>
                  <commandTopic>/summit_xl_control/cmd_vel</commandTopic>
                  <odometryFrame>odom</odometryFrame>
                  <odometryTopic>odom</odometryTopic>
                  <robotBaseFrame>base_footprint</robotBaseFrame>
              </plugin>
          </gazebo>
  </xacro:macro>

障碍物小车,用于轨迹控制作为动态障碍物的一部分

<?xml version="1.0"?>

<!-- racecar.urdf.xacro

This file defines a model of a Traxxas(R) E-Maxx(R) #3905 RC (Radio Controlled)
truck.

Lengths are measured in meters, angles are measured in radians, and masses are
measured in kilograms. All of these values are approximations.

To work with Gazebo, each link must have an inertial element, even if
the link only serves to connect two joints. To be visible in Gazebo, a link
must have a collision element. Furthermore, the link must have a Gazebo
material.

Traxxas(R), E-Maxx(R), and Titan(R) are registered trademarks of Traxxas
Management, LLC. em_3905.urdf.xacro was independently created by Wunderkammer
Laboratory, and neither em_3905.urdf.xacro nor Wunderkammer Laboratory is
affiliated with, sponsored by, approved by, or endorsed by Traxxas Management,
LLC. Mabuchi Motor(R) is a registered trademark of Mabuchi Motor Co., Ltd.
Corporation Japan. All other trademarks and service marks are the property of
their respective owners.

Copyright (c) 2011-2014 Wunderkammer Laboratory

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

  http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->

<robot name="obstacle" xmlns:xacro="http://www.ros.org/wiki/xacro">
  <!-- include sensors -->

  <!-- Degree-to-radian conversions -->
  <xacro:property name="degrees_45" value="0.785398163"/>
  <xacro:property name="degrees_90" value="1.57079633"/>

  <!-- chassis_length is measured along the x axis, chassis_width
       along the y axis, and chassis_height along the z axis. -->
  <xacro:property name="chassis_length" value="0.258"/>
  <xacro:property name="chassis_width" value="0.168"/>
  <xacro:property name="chassis_height" value="0.01"/>
  <xacro:property name="chassis_mass" value="2.788"/>

  <!-- battery_dist is the distance between the inner edges of the
       batteries. battery_comp_depth is the battery compartment depth.
       battery_length is measured along the x axis, battery_width
       along the y axis, and battery_height along the z axis. -->
  <xacro:property name="battery_x_offset" value="0.055"/>
  <xacro:property name="battery_dist" value="0.065"/>
  <xacro:property name="battery_comp_depth" value="0.02"/>
  <xacro:property name="battery_comp_angle" value="0.34906585"/>
  <xacro:property name="battery_length" value="0.16"/>
  <xacro:property name="battery_width" value="0.047"/>
  <xacro:property name="battery_height" value="0.024"/>
  <xacro:property name="battery_mass" value="0.5025"/>

  <!-- hub_dia and tire_dia are the diameters of the hub and tire,
       respectively. hex_hub_depth is the distance that the hex hub is
       inset from the outer edge of the tire. It is set so that each wheel
       is a "zero offset" wheel. hex_hub_depth = tire_width / 2 -
       axle_length. -->
  <xacro:property name="hub_dia" value="0.09652"/>
  <xacro:property name="tire_dia" value="0.14605"/>
  <xacro:property name="tire_width" value="0.0889"/>
  <xacro:property name="hex_hub_depth" value="0.01445"/>
  <xacro:property name="wheel_mass" value="0.29"/>

  <!-- hex_hub_dist is the distance between left and right hex hubs when
       the shock absorbers are fully extended. axle_length is the distance
       from a U joint to the corresponding hex hub. wheel_travel is the
       vertical wheel travel. -->
  <xacro:property name="wheelbase" value="0.335"/>
  <xacro:property name="hex_hub_dist" value="0.365"/>
  <xacro:property name="axle_length" value="0.03"/>
  <xacro:property name="wheel_travel" value="0.084"/>
  <xacro:property name="shock_z_offset" value="0.0655"/>

  <!-- shock_eff_limit is 2 * ((shock_stroke / 2) * shock_spring_constant) N.
       shock_stroke is 0.028575 meters. shock_spring_constant, an approximation
       of a Traxxas Ultra Shock shock absorber spring's constant, is
       437.817 N/m. -->
  <xacro:property name="shock_eff_limit" value="12.5106"/>
  <xacro:property name="shock_vel_limit" value="1000"/>

  <!-- The specifications for a Titan(R) 550 motor could not be found, so the
       stall torque of a Mabuchi Motor(R) RS-550VC-7525 motor was used instead.

       num_spur_gear_teeth = 68
       num_pinion_gear_teeth = 19
       final_gear_ratio = (num_spur_gear_teeth / num_pinion_gear_teeth) *
         5.22 = 18.68
       stall_torque = 0.549 N m
       axle_eff_limit = ((2 * stall_torque) * final_gear_ratio) / 4 =
         5.12766 N m

       max_speed = 40 mph (30+ mph) = 17.8816 m/s
       axle_vel_limit = (2 * pi) * (max_speed / (pi * tire_dia)) =
         244.8696 rad/s -->
  <xacro:property name="axle_eff_limit" value="5.12766"/>
  <xacro:property name="axle_vel_limit" value="244.8696"/>

  <!-- These constants are used to simulate a Traxxas 2056 servo operated at
       6 V. servo_stall_torque is measured in N m. servo_no_load_speed is
       measured in rad/s. -->
  <xacro:property name="servo_stall_torque" value="0.5649"/>
  <xacro:property name="servo_no_load_speed" value="4.553"/>

  <xacro:property name="layer_mass"   value="0.0" />
  <xacro:property name="layer_x" value="0.40"/>
  <xacro:property name="layer_y" value="0.18"/>
  <xacro:property name="layer_z" value="0.01"/>
  <xacro:property name="layer_height" value="0.08"/>

  <material name="battery_mat">
    <color rgba="0 0 1 1"/>
  </material>
  <material name="chassis_mat">
    <color rgba="0.5 0.5 0.5 1"/>
  </material>
  <material name="tire_mat">
    <color rgba="0 0 0 1"/>
  </material>
  <material name="yellow">
    <color rgba="1 0.4 0 1"/>
  </material>

  <!-- Null inertial element. This is needed to make the model work with
       Gazebo. -->
  <xacro:macro name="null_inertial">
    <inertial>
      <mass value="0.001"/>
      <inertia ixx="0.001" ixy="0" ixz="0" iyy="0.001" iyz="0" izz="0.001"/>
    </inertial>
  </xacro:macro>

  <!-- Inertia of a solid cuboid. Width is measured along the x axis, depth
       along the y axis, and height along the z axis. -->
  <xacro:macro name="solid_cuboid_inertial"
               params="width depth height mass *origin">
    <inertial>
      <xacro:insert_block name="origin"/>
      <mass value="${mass}"/>
      <inertia ixx="${mass * (depth * depth + height * height) / 12}"
               ixy="0" ixz="0"
               iyy="${mass * (width * width + height * height) / 12}"
               iyz="0"
               izz="${mass * (width * width + depth * depth) / 12}"/>
    </inertial>
  </xacro:macro>

  <!-- Inertia of a thick-walled cylindrical tube with open ends. Height is
       measured along the z axis, which is the tube's axis. inner_rad and
       outer_rad are the tube's inner and outer radii, respectively. -->
  <xacro:macro name="thick_walled_tube_inertial"
               params="inner_rad outer_rad height mass">
    <inertial>
      <mass value="${mass}"/>
      <inertia ixx="${(1 / 12) * mass * (3 * (inner_rad * inner_rad +
                    outer_rad * outer_rad) + height * height)}"
               ixy="0" ixz="0"
               iyy="${(1 / 12) * mass * (3 * (inner_rad * inner_rad +
                    outer_rad * outer_rad) + height * height)}"
               iyz="0"
               izz="${mass * (inner_rad * inner_rad +
                    outer_rad * outer_rad) / 2}"/>
    </inertial>
  </xacro:macro>

  <!-- Battery -->
  <xacro:macro name="battery" params="prefix reflect">
    <joint name="chassis_to_${prefix}_battery" type="fixed">
      <parent link="chassis"/>
      <child link="${prefix}_battery_offset"/>
      <origin xyz="${battery_x_offset - battery_length / 2}
                   ${reflect * battery_dist / 2}
                   0"
              rpy="${reflect * battery_comp_angle} 0 0"/>
    </joint>

    <link name="${prefix}_battery_offset">
      <xacro:null_inertial/>
    </link>

    <joint name="offset_to_${prefix}_battery" type="fixed">
      <parent link="${prefix}_battery_offset"/>
      <child link="${prefix}_battery"/>
      <origin xyz="0
                   ${reflect * battery_width / 2}
                   ${(battery_height / 2) - battery_comp_depth}"/>
    </joint>

    <link name="${prefix}_battery">
      <visual>
        <geometry>
          <box size="${battery_length} ${battery_width} ${battery_height}"/>
        </geometry>
        <material name="battery_mat"/>
      </visual>

      <collision>
        <geometry>
          <box size="${battery_length} ${battery_width} ${battery_height}"/>
        </geometry>
      </collision>

      <xacro:solid_cuboid_inertial
         width="${battery_length}" depth="${battery_width}"
         height="${battery_height}" mass="${battery_mass}">
        <origin/>
      </xacro:solid_cuboid_inertial>
    </link>

    <gazebo reference="${prefix}_battery">
      <material>Gazebo/Blue</material>
    </gazebo>
  </xacro:macro>

  <!-- Shock absorber -->
  <xacro:macro name="shock"
               params="lr_prefix fr_prefix lr_reflect fr_reflect child">
    <joint name="${lr_prefix}_${fr_prefix}_shock" type="prismatic">
      <parent link="chassis"/>
      <child link="${child}"/>

      <origin xyz="${fr_reflect * wheelbase / 2}
                   ${lr_reflect * ((hex_hub_dist / 2) - axle_length)}
                   ${(wheel_travel / 2) - shock_z_offset}"/>
      <axis xyz="0 0 -1"/>
      <limit lower="${-wheel_travel / 2}" upper="${wheel_travel / 2}"
             effort="${shock_eff_limit}" velocity="${shock_vel_limit}"/>
    </joint>
    <transmission name="${lr_prefix}_${fr_prefix}_shock_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${lr_prefix}_${fr_prefix}_shock">
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      </joint>
      <actuator name="${lr_prefix}_${fr_prefix}_shock_act">
        <!-- This hardwareInterface element exists for compatibility
             with ROS Hydro. -->
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>
  </xacro:macro>

  <!-- The "wheel" macro defines an axle carrier, axle, and wheel. -->
  <xacro:macro name="wheel" params="lr_prefix fr_prefix lr_reflect">
    <link name="${lr_prefix}_${fr_prefix}_axle_carrier">
      <xacro:null_inertial/>
    </link>

    <!-- The left and right axles have the same axis so that identical
         rotation values cause the wheels to rotate in the same direction. -->
    <joint name="${lr_prefix}_${fr_prefix}_axle" type="continuous">
      <parent link="${lr_prefix}_${fr_prefix}_axle_carrier"/>
      <child link="${lr_prefix}_${fr_prefix}_wheel"/>
      <origin rpy="${degrees_90} 0 0"/>
      <axis xyz="0 0 -1"/>
      <limit effort="${axle_eff_limit}" velocity="${axle_vel_limit}"/>
    </joint>
    <transmission name="${lr_prefix}_${fr_prefix}_axle_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${lr_prefix}_${fr_prefix}_axle">
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      </joint>
      <actuator name="${lr_prefix}_${fr_prefix}_axle_act">
        <!-- This hardwareInterface element exists for compatibility
             with ROS Hydro. -->
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>

    <link name="${lr_prefix}_${fr_prefix}_wheel">
      <visual>
        <origin xyz="0
                     ${lr_reflect * (axle_length - (tire_width /
                     2 - hex_hub_depth))}
                     0"/>
        <geometry>
          <cylinder radius="${tire_dia / 2}" length="${tire_width}"/>
        </geometry>
        <material name="tire_mat"/>
      </visual>

      <collision>
        <origin xyz="0
                     ${lr_reflect * (axle_length - (tire_width /
                     2 - hex_hub_depth))}
                     0"/>
        <geometry>
          <cylinder radius="${tire_dia / 2}" length="${tire_width}"/>
        </geometry>
      </collision>

      <xacro:thick_walled_tube_inertial
          inner_rad="${hub_dia / 2}" outer_rad="${tire_dia / 2}"
          height="${tire_width}" mass="${wheel_mass}"/>
    </link>

    <gazebo reference="${lr_prefix}_${fr_prefix}_wheel">
      <material>Gazebo/Black</material>
    </gazebo>
  </xacro:macro>

  <!-- Front wheel -->
  <xacro:macro name="front_wheel"
               params="lr_prefix fr_prefix lr_reflect fr_reflect">
    <xacro:shock lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
                 lr_reflect="${lr_reflect}" fr_reflect="${fr_reflect}"
                 child="${lr_prefix}_steering_link"/>

    <link name="${lr_prefix}_steering_link">
      <xacro:null_inertial/>
    </link>

    <joint name="${lr_prefix}_steering_joint" type="revolute">
      <parent link="${lr_prefix}_steering_link"/>
      <child link="${lr_prefix}_${fr_prefix}_axle_carrier"/>
      <axis xyz="0 0 1"/>
      <limit lower="${-degrees_45}" upper="${degrees_45}"
             effort="${servo_stall_torque}" velocity="${servo_no_load_speed}"/>
    </joint>
    <transmission name="${lr_prefix}_steering_trans">
      <type>transmission_interface/SimpleTransmission</type>
      <joint name="${lr_prefix}_steering_joint">
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
      </joint>
      <actuator name="${lr_prefix}_steering_act">
        <!-- This hardwareInterface element exists for compatibility
             with ROS Hydro. -->
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
      </actuator>
    </transmission>

    <xacro:wheel lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
                 lr_reflect="${lr_reflect}"/>
  </xacro:macro>

  <!-- Rear wheel -->
  <xacro:macro name="rear_wheel"
               params="lr_prefix fr_prefix lr_reflect fr_reflect">
    <xacro:shock lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
                 lr_reflect="${lr_reflect}" fr_reflect="${fr_reflect}"
                 child="${lr_prefix}_${fr_prefix}_axle_carrier"/>
    <xacro:wheel lr_prefix="${lr_prefix}" fr_prefix="${fr_prefix}"
                 lr_reflect="${lr_reflect}"/>
  </xacro:macro>

  <!-- chassis for sensors -->
  <xacro:macro name="layer" params="layer parent m x y z *joint_pose">
    <joint name="${layer}_joint" type="fixed">
      <xacro:insert_block name="joint_pose"/>
      <parent link="${parent}"/>
      <child link="${layer}_link" />
    </joint>

    <link name="${layer}_link">
      <visual>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <box size="${x} ${y} ${z}" />
        </geometry>
        <material name="yellow" />
      </visual>
      <collision>
        <origin xyz="0 0 0" rpy="0 0 0" />
        <geometry>
          <box size="${x} ${y} ${z}" />
        </geometry>
      </collision>
      <xacro:solid_cuboid_inertial
              width="${x}" depth="${y}"
              height="${z}" mass="${m}">
        <origin xyz="0 0 ${-z / 2}"/>
      </xacro:solid_cuboid_inertial>
    </link>

    <gazebo reference="${layer}_link">
      <material>Gazebo/Orange</material>
    </gazebo>
  </xacro:macro>

  <link name="base_footprint"/>
  <!-- base_link must have geometry so that its axes can be displayed in
       rviz. -->
  <link name="base_link">
    <visual>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
      <material name="chassis_mat"/>
    </visual>
  </link>
  <gazebo reference="base_link">
    <material>Gazebo/Grey</material>
  </gazebo>

  <joint name="base_footprint_to_base_link" type="fixed">
    <parent link="base_footprint"/>
    <child link="base_link"/>
    <origin xyz="0 0 ${(wheel_travel/2)+shock_z_offset}" />
  </joint>

  <!-- Chassis -->
  <link name="chassis">
    <visual>W
      <origin xyz="0 0 ${-chassis_height / 2}"/>
      <geometry>
        <box size="${chassis_length} ${chassis_width} ${chassis_height}"/>
      </geometry>
      <material name="chassis_mat"/>
    </visual>

    <collision>
      <origin xyz="0 0 ${-chassis_height / 2}"/>
      <geometry>
        <box size="${chassis_length} ${chassis_width} ${chassis_height}"/>
      </geometry>
    </collision>

    <xacro:solid_cuboid_inertial
        width="${chassis_length}" depth="${chassis_width}"
        height="${chassis_height}" mass="${chassis_mass}">
      <origin xyz="0 0 ${-chassis_height / 2}"/>
    </xacro:solid_cuboid_inertial>
  </link>
  <gazebo reference="chassis">
    <material>Gazebo/Grey</material>
  </gazebo>

  <joint name="base_link_to_chassis" type="fixed">
    <parent link="base_link"/>
    <child link="chassis"/>
  </joint>

  <!-- Batteries -->
  <xacro:battery prefix="left" reflect="1"/>
  <xacro:battery prefix="right" reflect="-1"/>

  <!-- Wheels -->
  <xacro:front_wheel lr_prefix="left" fr_prefix="front"
                     lr_reflect="1" fr_reflect="1"/>
  <xacro:front_wheel lr_prefix="right" fr_prefix="front"
                     lr_reflect="-1" fr_reflect="1"/>
  <xacro:rear_wheel lr_prefix="left" fr_prefix="rear"
                    lr_reflect="1" fr_reflect="-1"/>
  <xacro:rear_wheel lr_prefix="right" fr_prefix="rear"
                    lr_reflect="-1" fr_reflect="-1"/>

  <gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
    <legacyModeNS>true</legacyModeNS>
    <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
    <robotNamespace>/obstacle</robotNamespace>
    </plugin>
  </gazebo>

</robot>
<?xml version="1.0"?>
<launch>
	    <!-- 设置launch文件的参数 -->
    <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="x_pos" default="-0.5"/>
    <arg name="y_pos" default="0"/>
    <arg name="z_pos" default="0.0"/>

	<!--运行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)"/>
		<arg name="world_name" value="$(find racecar_description)/worlds/actor_collisions.world"/>

               <!-- .world文件的地址-->
    	</include>

	<!-- 加载机器人模型描述参数 -->
	<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find racecar_description)/urdf/racecar.urdf.xacro'"/>

    <param name="robot_description1" command="$(find xacro)/xacro --inorder '$(find racecar_description)/urdf/moving_obs.xacro'"/>

	<!--运行joint_state_publisher节点,发布机器人关节状态-->
	<!--<node name = "robot_state_publisher" pkg = "robot_state_publisher" type = "state_publisher">-->
	<node name= "robot_state_publisher" pkg= "robot_state_publisher" type= "robot_state_publisher">
		<param name="publish_frequency" type="double" value="20.0" />
		<remap from="/joint_states" to="/racecar/joint_states"/>
	</node>
	<node name= "robot_state_publisher1" pkg= "robot_state_publisher" type= "robot_state_publisher">
		<param name="publish_frequency" type="double" value="20.0" />
		<remap from="/joint_states" to="/obstacle/joint_states"/>
	</node>
	    <!-- 在gazebo中加载机器人模型-->
    <node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
          args="-urdf -model racecar -param robot_description -x $(arg x_pos) -y $(arg y_pos) -z $(arg z_pos)"/>


    <node name="urdf_spawner1" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
          args="-urdf -model obstacle -param robot_description1 -x 10 -y 10 -z 0"/>
	 <!-- 从yaml文件加载联合控制器的参数 -->
	<rosparam file="$(find bringup)/config/ctrl.yaml" command="load"/>
	<!-- 加载控制器 spawner -->
	<node name="controller_manager" pkg="controller_manager" type="spawner"
	      respawn="false" output="screen" ns="/racecar"
	      args="left_rear_wheel_velocity_controller       right_rear_wheel_velocity_controller
	            left_front_wheel_velocity_controller      right_front_wheel_velocity_controller
	            left_steering_hinge_position_controller   right_steering_hinge_position_controller
	            joint_state_controller"/>
	<!-- 加载控制器 spawner -->
	<node name="controller_manager1" pkg="controller_manager" type="spawner"
	      respawn="false" output="screen" ns="/obstacle"
	      args="left_rear_wheel_velocity_controller       right_rear_wheel_velocity_controller
	            left_front_wheel_velocity_controller      right_front_wheel_velocity_controller
	            left_steering_hinge_position_controller   right_steering_hinge_position_controller
	            joint_state_controller"/>


<node pkg="racecar_description" type="servo_commands.py" name="servo_commands" output="screen">
</node>

</launch>

2.2工程确定

折腾来折腾去,我直接打算,在2019年全国智能车ROS仿真赛的环境基础进行修改了,因为自己太菜了,阿克曼模型的配置整不了.

安装velodyne16线激光雷达

  1. 下载velodyne源码
git clone https://bitbucket.org/DataspeedInc/velodyne_simulator.git

2.配置xacro
在机器人总xacro文件中添加下端代码(看了很多资料,各种乱七八糟的改,才发现就…fuck!),按实际修改:

  <xacro:include filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro"/>
    <xacro:VLP-16 parent="lidar_platform_link(根据自己的机器人修改就是把雷达安装在哪个link上)" name="VLD16" topic="/VLD16" organize_cloud="fasle" hz="10" samples="440" gpu="false">
    <origin xyz="-0.2 0 -0.07(坐标位置按照实际修改,显示一下慢慢修改)" rpy="0 0 0" />
  </xacro:VLP-16>

效果:
在这里插入图片描述在这里插入图片描述舒服了,二维激光和三维激光,深度相机,里程计都有了,再也…

3.人形模型

一般由于gazebo是基于物理引擎,没有碰撞属性,虽然深度相机可以观察到,但是激光雷达无法检测到,需要对移动障碍物添加碰撞属性,移动障碍物,在Gazebo中用到了< actor>标签.
参考:
gazebo之actor标签行人添加碰撞属性-little_miya

  1. 下载gazeo源码需要得到 libActorCollisionsPlugin.so, sudo 安装没有,需要下载带有源码版本
  2. 进入 /gazebo/examples/plugins/actor_collisions,新建build ,进行编译得到
    libActorCollisionsPlugin.so
    mkdir build
    cd build
    cmake ..
    make
  1. 将得到的.so文件复制到自带的gazebo 目录下
sudo cp libActorCollisionsPlugin.so /usr/lib/x86_64-linux-gnu/gazebo-9/plugins
  1. 测试t
gazebo actor_collisions.world(在/gazebo/examples/plugins/actor_collisions目录下)
  1. 借鉴world文件添加到自己的gazebo环境,我直接在launch文件中加载了它的原始world文件,没做修改

Gazebo动态障碍物三维激光雷达检测

B站链接

### Gazebo 四轮车仿真教程 #### 启动四轮车仿真环境 为了启动基于Gazebo的四轮车仿真,可以使用如下命令来加载预配置好的发射文件[^1]: ```bash roslaunch diff_wheeled_robot_gazebo diff_wheeled_gazebo.launch ``` 此命令会初始化并运行一个差分驱动的小车型机器人模型,在Gazebo环境中展示出来。 #### URDF与Gazebo基本集成流程 对于希望深入了解如何将自定义的四轮车辆模型集成到Gazebo中的开发者来说,了解URDF (Universal Robot Description Format) 文件的作用至关重要。URDF用于描述机器人的物理属性和结构,而这些信息会被用来构建虚拟世界内的实体对象[^2]。 当涉及到具体的集成过程时,通常遵循以下几个方面的工作: - **创建或修改URDF文件**:根据实际需求设计四轮车的具体参数; - **调整链接(link) 和关节(joint)** :确保各个部件能够按照预期的方式相互作用; - **应用材质、颜色和其他视觉效果**:使模拟更加逼真; - **添加传感器或其他功能模块**:比如激光雷达(LiDAR),摄像头等设备的支持; #### 创建仿真环境的方法 在准备好了四轮车的基础模型之后,还需要为其设定合适的场景以便更好地测试其性能。这可以通过两种主要途径实现: - 使用已有的内置组件快速建立简单的室内/室外场地布局[^3]; 或者 - 自己动手利用建模工具如Blender制作特定形状的对象,并导入至Gazebo中作为新的障碍物或是装饰品[^4]. 这两种方法各有优劣,前者适合初学者迅速上手实践,后者则提供了更大的自由度去定制个性化的实验条件。 #### 示例代码片段 下面给出一段Python脚本的例子,展示了怎样通过ROS接口控制一辆已经存在于Gazebo里的四轮移动平台向前行驶一小段距离: ```python import rospy from geometry_msgs.msg import Twist def move(): # 初始化节点 rospy.init_node('robot_mover', anonymous=True) velocity_publisher = rospy.Publisher('/cmd_vel', Twist, queue_size=10) vel_msg = Twist() speed = input("Input your speed:") distance = input("Type your distance:") isForward = input("Foward?: ")==1 if(isForward): vel_msg.linear.x = abs(speed) else: vel_msg.linear.x = -abs(speed) t0 = rospy.Time.now().to_sec() current_distance = 0 while(current_distance < distance): velocity_publisher.publish(vel_msg) t1=rospy.Time.now().to_sec() current_distance= speed*(t1-t0) vel_msg.linear.x = 0 velocity_publisher.publish(vel_msg) if __name__ == '__main__': try: move() except rospy.ROSInterruptException: pass ```
评论 7
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

RockWang.

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值