在gazebo当中不用再设置颜色了,因为完全可以使用urdf的设置
<robot name="base" xmlns:xacro="http://wiki.ros.org/wiki/xacro">
<xacro:property name="PI" value="3.1415926"/><!--定义一个变量PI,后边用来调用的-->
<xacro:property name="base_footprint_radius" value="0.001"/>
<xacro:property name="base_radius" value="0.1"/>
<xacro:property name="base_length" value="0.08"/>
<xacro:property name="ground_clearance" value="0.015"/>
<xacro:property name="base_mass" value="0.5"/>
<link name="base_footprint">
<visual>
<geometry>
<sphere radius="${base_footprint_radius}"/>
</geometry>
</visual>
</link>
<link name="base">
<visual>
<geometry>
<cylinder radius="${base_radius}" length="${base_length}"/>
</geometry>
<origin xyz="0 0 0" rpy="0 0 0"/>
<material name="red">
<color rgba="1 0 0.0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder radius="${base_radius}" length="${base_length}"/>
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</collision>
<xacro:cylinder_inertial m="${base_mass}" r="${base_radius}" h="${base_length}"/>
</link>
<joint name="base2base_footprint" type="fixed">
<parent link="base_footprint"/>
<child link="base"/>
<origin xyz="0 0 ${ground_clearance+base_length/2}"/>
</joint>
<!--
<gazebo reference="base">
<material>
Gazebo/Blue
</material>
</gazebo>
-->
<xacro:property name="wheel_radius" value="0.0325"/>
<xacro:property name="wheel_length" value="0.015"/>
<xacro:property name="wheel_m" value="0.05"/>
<xacro:macro name="add_wheel" 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"/>
<material name="green">
<color rgba="0 1 0.0 1"/>
</material>
</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 m="${wheel_m}" r="${wheel_radius}" h="${wheel_length}"/>
</link>
<joint name="${name}_wheel2base" type="continuous">
<parent link="base"/>
<child link="${name}_wheel"/>
<origin xyz="0 ${flag*base_radius} ${-(ground_clearance+base_length/2-wheel_radius)}"/>
<axis xyz="0 1 0"/>
</joint>
<!--
<gazebo reference="${name}_wheel">
<material>
Gazebo/Blue
</material>
</gazebo>
-->
</xacro:macro>
<xacro:add_wheel name="left" flag="1"/>
<xacro:add_wheel name="right" flag="-1"/>
<xacro:property name="holder_wheel_radius" value="0.0075"/>
<xacro:property name="holder_wheel_m" value="0.03"/>
<xacro:macro name="add_holder_wheel" params="name flag">
<link name="${name}_wheel">
<visual>
<geometry>
<sphere radius="${holder_wheel_radius}"/>
</geometry>
<origin xyz="0 0 0" rpy="0.0 0.0 0.0"/>
<material name="blue">
<color rgba="0 0 1.0 1"/>
</material>
</visual>
<collision>
<geometry>
<sphere radius="${holder_wheel_radius}"/>
</geometry>
<origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0"/>
</collision>
<xacro:sphere_inertial m="${holder_wheel_m}" r="${holder_wheel_radius}"/>
</link>
<joint name="${name}_wheel2base" type="continuous">
<parent link="base"/>
<child link="${name}_wheel"/>
<origin xyz="${flag*(base_radius-holder_wheel_radius)} 0 ${-(base_length/2+ground_clearance/2)}"/>
<axis xyz="1 1 1"/>
</joint>
<!-- <gazebo reference="${name}_wheel">
<material>
Gazebo/Blue
</material>
</gazebo>
-->
</xacro:macro>
<xacro:add_holder_wheel name="front" flag="1"/>
<xacro:add_holder_wheel name="back" flag="-1"/>
</robot>
这个代码完全使用了urdf自己的颜色rgba,没有使用<gazebo>内的<material>标签,事实证明即使添加一个<material>标签,也不会有用,所以这样设计更加方便。算是进化了
请诸位放心,一切都在掌控之中哈哈