Skip to content

Commit

Permalink
updated scale
Browse files Browse the repository at this point in the history
  • Loading branch information
MathisAbalain committed Dec 18, 2023
1 parent 64e7026 commit f3d7e78
Showing 1 changed file with 52 additions and 55 deletions.
107 changes: 52 additions & 55 deletions src/ezbot_descr_simul/description/robot_core.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -39,20 +39,20 @@

<link name="chassis">
<visual>
<origin xyz="0.55 0 0.3"/>
<origin xyz="0.055 0 0.03"/>
<geometry>
<box size="1.1 1.1 0.6"/>
<box size="0.11 0.11 0.06"/>
</geometry>
<material name="orange"/>
</visual>
<collision>
<origin xyz="0.55 0 0.3"/>
<origin xyz="0.055 0 0.03"/>
<geometry>
<box size="1.1 1.1 0.6"/>
<box size="0.11 0.11 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="1.1" y="1.1" z="0.6">
<origin xyz="0.55 0 0.3" rpy="0 0 0"/>
<xacro:inertial_box mass="0.5" x="0.11" y="0.11" z="0.06">
<origin xyz="0.055 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>

Expand All @@ -65,25 +65,25 @@
<joint name= "bloc_avant_joint" type="fixed">
<parent link="chassis"/>
<child link="bloc_avant"/>
<origin xyz="1.1 0 0"/>
<origin xyz="0.11 0 0"/>
</joint>

<link name="bloc_avant">
<visual>
<origin xyz="0.4 0 0.3"/>
<origin xyz="0.04 0 0.03"/>
<geometry>
<box size="0.8 0.8 0.6"/>
<box size="0.08 0.08 0.06"/>
</geometry>
<material name="white"/>
</visual>
<collision>
<origin xyz="0.4 0 0.3"/>
<origin xyz="0.04 0 0.03"/>
<geometry>
<box size="0.8 0.8 0.6"/>
<box size="0.08 0.08 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.8" y="0.8" z="0.6">
<origin xyz="0.4 0 0.3" rpy="0 0 0"/>
<xacro:inertial_box mass="0.5" x="0.08" y="0.08" z="0.06">
<origin xyz="0.04 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>

Expand All @@ -96,25 +96,25 @@
<joint name= "bloc_arriere_joint" type="fixed">
<parent link="chassis"/>
<child link="bloc_arriere"/>
<origin xyz="-0.8 0 0"/>
<origin xyz="-0.08 0 0"/>
</joint>

<link name="bloc_arriere">
<visual>
<origin xyz="0.4 0 0.3"/>
<origin xyz="0.04 0 0.03"/>
<geometry>
<box size="0.8 0.8 0.6"/>
<box size="0.08 0.08 0.06"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0.4 0 0.3"/>
<origin xyz="0.04 0 0.03"/>
<geometry>
<box size="0.8 0.8 0.6"/>
<box size="0.08 0.08 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.8" y="0.8" z="0.6">
<origin xyz="0.4 0 0.3" rpy="0 0 0"/>
<xacro:inertial_box mass="0.05" x="0.08" y="0.08" z="0.06">
<origin xyz="0.04 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>

Expand All @@ -127,25 +127,25 @@
<joint name= "bloc_gauche_joint" type="fixed">
<parent link="chassis"/>
<child link="bloc_gauche"/>
<origin xyz="0.15 0.95 0"/>
<origin xyz="0.015 0.095 0"/>
</joint>

<link name="bloc_gauche">
<visual>
<origin xyz="0.4 0 0.3"/>
<origin xyz="0.04 0 0.03"/>
<geometry>
<box size="0.8 0.8 0.6"/>
<box size="0.08 0.08 0.06"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0.4 0 0.3"/>
<origin xyz="0.04 0 0.03"/>
<geometry>
<box size="0.8 0.8 0.6"/>
<box size="0.08 0.08 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.8" y="0.8" z="0.6">
<origin xyz="0.4 0 0.3" rpy="0 0 0"/>
<xacro:inertial_box mass="0.5" x="0.08" y="0.08" z="0.06">
<origin xyz="0.04 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>

Expand All @@ -158,25 +158,25 @@
<joint name= "bloc_droit_joint" type="fixed">
<parent link="chassis"/>
<child link="bloc_droit"/>
<origin xyz="0.15 -0.95 0"/>
<origin xyz="0.015 -0.095 0"/>
</joint>

<link name="bloc_droit">
<visual>
<origin xyz="0.4 0 0.3"/>
<origin xyz="0.04 0 0.03"/>
<geometry>
<box size="0.8 0.8 0.6"/>
<box size="0.08 0.08 0.06"/>
</geometry>
<material name="black"/>
</visual>
<collision>
<origin xyz="0.4 0 0.3"/>
<origin xyz="0.04 0 0.03"/>
<geometry>
<box size="0.8 0.8 0.6"/>
<box size="0.08 0.08 0.06"/>
</geometry>
</collision>
<xacro:inertial_box mass="0.5" x="0.8" y="0.8" z="0.6">
<origin xyz="0.4 0 0.3" rpy="0 0 0"/>
<xacro:inertial_box mass="0.5" x="0.08" y="0.08" z="0.06">
<origin xyz="0.04 0 0.03" rpy="0 0 0"/>
</xacro:inertial_box>
</link>

Expand All @@ -189,7 +189,7 @@
<joint name= "roue_droite_joint" type="continuous">
<parent link="bloc_droit"/>
<child link="roue_droite"/>
<origin xyz="0.4 -0.5 0.2" rpy="-${pi/2} 0 0"/>
<origin xyz="0.04 -0.05 0.02" rpy="-${pi/2} 0 0"/>
<axis xyz="0 0 1"/>
</joint>

Expand All @@ -198,22 +198,21 @@
<visual>
<material name="blue"/>
<geometry>
<cylinder radius="0.3" length="0.2"/>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder radius="0.3" length="0.2"/>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" radius="0.3" length="0.2">
<xacro:inertial_cylinder mass="0.1" radius="0.03" length="0.02">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>

<gazebo reference="roue_droite">
<material>Gazebo/Blue</material>
<!--Have friction only along the way it rotates-->
<fdir1>1 0 0</fdir1>
<mu1>1.0</mu1>
<mu2>0.1</mu2>
Expand All @@ -224,7 +223,7 @@
<joint name= "roue_gauche_joint" type="continuous">
<parent link="bloc_gauche"/>
<child link="roue_gauche"/>
<origin xyz="0.4 0.5 0.2" rpy="-${pi/2} 0 0"/>
<origin xyz="0.04 0.05 0.02" rpy="-${pi/2} 0 0"/>
<axis xyz="0 0 1"/>
</joint>

Expand All @@ -233,22 +232,21 @@
<visual>
<material name="blue"/>
<geometry>
<cylinder radius="0.3" length="0.2"/>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder radius="0.3" length="0.2"/>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" radius="0.3" length="0.2">
<xacro:inertial_cylinder mass="0.1" radius="0.03" length="0.02">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>

<gazebo reference="roue_gauche">
<material>Gazebo/White</material>
<!--Have friction only along the way it rotates-->
<material>Gazebo/Blue</material>
<fdir1>1 0 0</fdir1>
<mu1>1.0</mu1>
<mu2>0.1</mu2>
Expand All @@ -258,8 +256,8 @@

<joint name= "roue_avant_joint" type="continuous">
<parent link="bloc_avant"/>
<child link="roue_avant"/>
<origin xyz="0.9 0 0.2" rpy="0 ${pi/2} 0"/>
<child link="roue_avant"/>
<origin xyz="0.09 0 0.02" rpy="0 ${pi/2} 0"/>
<axis xyz="0 0 1"/>
</joint>

Expand All @@ -268,15 +266,15 @@
<visual>
<material name="blue"/>
<geometry>
<cylinder radius="0.3" length="0.2"/>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder radius="0.3" length="0.2"/>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" radius="0.3" length="0.2">
<xacro:inertial_cylinder mass="0.1" radius="0.03" length="0.02">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
Expand All @@ -293,7 +291,7 @@
<joint name= "roue_arriere_joint" type="continuous">
<parent link="bloc_arriere"/>
<child link="roue_arriere"/>
<origin xyz="-0.1 0 0.2" rpy="0 ${pi/2} 0"/>
<origin xyz="-0.01 0 0.02" rpy="0 ${pi/2} 0"/>
<axis xyz="0 0 1"/>
</joint>

Expand All @@ -302,15 +300,15 @@
<visual>
<material name="blue"/>
<geometry>
<cylinder radius="0.3" length="0.2"/>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</visual>
<collision>
<geometry>
<cylinder radius="0.3" length="0.2"/>
<cylinder radius="0.03" length="0.02"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" radius="0.3" length="0.2">
<xacro:inertial_cylinder mass="0.1" radius="0.03" length="0.02">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
Expand All @@ -322,5 +320,4 @@
<mu2>0.1</mu2>
</gazebo>


</robot>

0 comments on commit f3d7e78

Please sign in to comment.