Skip to content
Snippets Groups Projects
Commit 4dda24b1 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Placed the base_footprint frame before the base_link frame.

parent a7e19632
No related branches found
No related tags found
No related merge requests found
...@@ -7,6 +7,10 @@ ...@@ -7,6 +7,10 @@
<xacro:iri_skid_steering_gazebo name="${name}" config="${sim_config}"/> <xacro:iri_skid_steering_gazebo name="${name}" config="${sim_config}"/>
<gazebo reference="base_footprint">
<material>Gazebo/Red</material>
</gazebo>
<gazebo reference="base_link"> <gazebo reference="base_link">
<material>Gazebo/Red</material> <material>Gazebo/Red</material>
</gazebo> </gazebo>
......
...@@ -7,6 +7,14 @@ ...@@ -7,6 +7,14 @@
<xacro:macro name="pioneer3" params="name resolution sim_config"> <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"> <link name="base_link">
<collision> <collision>
<origin xyz="0 0 0.19" rpy="0 0 0"/> <origin xyz="0 0 0.19" rpy="0 0 0"/>
...@@ -30,14 +38,6 @@ ...@@ -30,14 +38,6 @@
</inertial> </inertial>
</link> </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"> <link name="top_plate">
<visual> <visual>
<origin xyz="0 0 0" rpy="0 0 0"/> <origin xyz="0 0 0" rpy="0 0 0"/>
......
...@@ -11,19 +11,7 @@ ...@@ -11,19 +11,7 @@
</gazebo> </gazebo>
<gazebo reference="${name}_wheel"> <gazebo reference="${name}_wheel">
<material>Gazebo/Black</material>
<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>
-->
</gazebo> </gazebo>
</xacro:macro> </xacro:macro>
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment