diff --git a/urdf/pioneer3.gazebo b/urdf/pioneer3.gazebo index f8ac3ba4f2b3f97cb85d00cd9d65f5b2fa6f94d4..8fc2637e4c354d6c8e27df01bafd782437f873da 100644 --- a/urdf/pioneer3.gazebo +++ b/urdf/pioneer3.gazebo @@ -7,6 +7,10 @@ <xacro:iri_skid_steering_gazebo name="${name}" config="${sim_config}"/> + <gazebo reference="base_footprint"> + <material>Gazebo/Red</material> + </gazebo> + <gazebo reference="base_link"> <material>Gazebo/Red</material> </gazebo> diff --git a/urdf/pioneer3.xacro b/urdf/pioneer3.xacro index d952793f9476aa5e3817add5a581b7b6d6778640..fb3f7c4cd43816ebc4259416a28d56b85c29f1dc 100644 --- a/urdf/pioneer3.xacro +++ b/urdf/pioneer3.xacro @@ -7,6 +7,14 @@ <xacro:macro name="pioneer3" params="name resolution sim_config"> + <link name="base_footprint"/> + + <joint name="base_footprint_to_base_link_joint" type="fixed"> + <origin xyz="0 0 0" rpy="0 0 0"/> + <parent link="base_footprint"/> + <child link="base_link"/> + </joint> + <link name="base_link"> <collision> <origin xyz="0 0 0.19" rpy="0 0 0"/> @@ -30,14 +38,6 @@ </inertial> </link> - <link name="base_footprint"/> - - <joint name="base_link_to_base_footprint_joint" type="fixed"> - <origin xyz="0 0 0" rpy="0 0 0"/> - <parent link="base_link"/> - <child link="base_footprint"/> - </joint> - <link name="top_plate"> <visual> <origin xyz="0 0 0" rpy="0 0 0"/> diff --git a/urdf/pioneer3_wheel.gazebo b/urdf/pioneer3_wheel.gazebo index de525a7e554da88f629adaa44aeabf1c78d9caa6..12fd3b15d82000eec377315b9141d91047dda2cd 100644 --- a/urdf/pioneer3_wheel.gazebo +++ b/urdf/pioneer3_wheel.gazebo @@ -11,19 +11,7 @@ </gazebo> <gazebo reference="${name}_wheel"> - - <material value="Gazebo/Black"/> - - <!-- - <kp>1000000.0</kp> - <kd>100.0</kd> - <mu1>1.0</mu1> - <mu2>1.0</mu2> - <fdir1>1 0 0</fdir1> - <maxVel>1.0</maxVel> - <minDepth>0.00</minDepth> - --> - + <material>Gazebo/Black</material> </gazebo> </xacro:macro>