Ros-gazebo xacro文件命名空间

24 篇文章 4 订阅
11 篇文章 1 订阅

xacro是urdf模型文件的升级版。如果想要在gazebo中用ros的spawn-model以<group ns="$arg(namespace)">同时打开多个这个xacro模型,要注意xacro文件中不要设置绝对的命名空间!

  <gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
    <legacyModeNS>true</legacyModeNS>
    <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
    <!--robotNamespace>/racecar</robotNamespace--> <!-- by spx, do not use absolute namespace-->
    </plugin>
  </gazebo>

这是xacro中的一段,用了gazebo_ros_control的plugin,不要设置namespace为/racecar这种绝对路径,否则launch文件里给这个模型的group ns就只能是racecar,无法打开多个模型了。

下面给一个打开两个racecar的xacro文件的示例,注意robot_description不能加后缀,不同的robot因为在不同的命名空间里,不存在robot_description冲突。其实spawn_urdf后面也不用区分ID。

<launch>

  <arg name="world_path" default="$(find uavros_gazebo)/worlds/lawn.world" />
  <arg name="vehicle" default="iris" />

	<include file="$(find gazebo_ros)/launch/empty_world.launch">
		<!--arg name="world_name" value="$(arg world_path)"/-->
	</include>


<group ns="ugv3">
	<arg name="ID" value="3"/>
	<arg name="x_pos" default="0"/>
	<arg name="y_pos" default="0"/>
	<arg name="z_pos" default="0"/>
	<arg name="yaw" default="0"/>
	<!-- 在gazebo中加载机器人模型-->
	<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find uavros_gazebo)/models/racecar_description/urdf/racecar.urdf.xacro'"/> <!--do not name as 'robot_description_3".etc-->
    <node name="spawn_urdf_$(arg ID)" pkg="gazebo_ros" type="spawn_model" args="-urdf -model racecar$(arg ID) -x $(arg x_pos) -y $(arg y_pos) -z $(arg z_pos) -Y $(arg yaw) -param robot_description"/> 

	<param name ="racecarID" value="$(arg ID)"/>
	<node pkg="uavros_gazebo" type="racecar_gazebo_odometry.py" name="racecar_gazebo_odometry" output="screen">
	</node>

	 <!-- 从yaml文件加载联合控制器的参数 -->
	<rosparam file="$(find uavros_gazebo)/config/racecar_config/ctrl.yaml" command="load"/>
	
	<!-- 加载控制器 spawner -->
	<node name="controller_manager" pkg="controller_manager" type="spawner" 
	      respawn="false" output="screen" 
	      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="uavros_gazebo" type="servo_commands.py" name="servo_commands" output="screen">
	</node>
</group>

<group ns="ugv4">
	<arg name="ID" value="4"/>
	<arg name="x_pos" default="1"/>
	<arg name="y_pos" default="0"/>
	<arg name="z_pos" default="0"/>
	<arg name="yaw" default="0"/>
	<!-- 在gazebo中加载机器人模型-->
	<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find uavros_gazebo)/models/racecar_description/urdf/racecar.urdf.xacro'"/> <!--do not name as 'robot_description_1".etc-->
    <node name="spawn_urdf_$(arg ID)" pkg="gazebo_ros" type="spawn_model" args="-urdf -model racecar$(arg ID) -x $(arg x_pos) -y $(arg y_pos) -z $(arg z_pos) -Y $(arg yaw) -param robot_description"/> 

	<param name ="racecarID" value="$(arg ID)"/>
	<node pkg="uavros_gazebo" type="racecar_gazebo_odometry.py" name="racecar_gazebo_odometry" output="screen">
	</node>

	 <!-- 从yaml文件加载联合控制器的参数 -->
	<rosparam file="$(find uavros_gazebo)/config/racecar_config/ctrl.yaml" command="load"/>
	
	<!-- 加载控制器 spawner -->
	<node name="controller_manager" pkg="controller_manager" type="spawner" 
	      respawn="false" output="screen" 
	      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="uavros_gazebo" type="servo_commands.py" name="servo_commands" output="screen">
	</node>
</group>

</launch>

 

  • 4
    点赞
  • 12
    收藏
    觉得还不错? 一键收藏
  • 3
    评论
评论 3
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值