--- /dev/null
+rotate([0,90,0]) scale([0.0000254,0.0000254,0.0000254])
+{
+ difference()
+ {
+ color("DarkOrange") cylinder(h=328-159,d=1513,center=true);
+ for(x=[-1500/2:100:1500/2], y=[-1500/2:100:1500/2])
+ translate([x,y,0]) cylinder(h=328-159,d=30,center=true);
+ }
+ color("Black") translate([0,0,-(328-159)/2-159/2]) cylinder(h=159,d=1690,center=true);
+ color("Silver") translate([0,0,-(328-159)/2-159-128/2]) cylinder(h=128,d=1580,center=true);
+
+}
\ No newline at end of file
--- /dev/null
+rotate([0,90,0]) scale([0.001,0.001,0.001]) translate([0,0,40/2]) color("black") difference()
+{
+ cube([85,70,40],center=true);
+ translate([0,0,12/2]) cube([79,70,40-12],center=true);
+ translate([0,0,39/2]) cube([82,70,40-39],center=true);
+ translate([0,0,2/2]) cube([79,65,40-2],center=true);
+
+ translate([0,70/2,0]) cube([17,2.5,40],center=true);
+ translate([0,-70/2,0]) cube([17,2.5,40],center=true);
+
+}
--- /dev/null
+rotate([0,90,0]) scale([0.001,0.001,0.001])
+translate([0,0,28/2+12])
+color("lightgray")
+{
+ difference()
+ {
+ cube([82,70,28],center=true);
+ translate([0,0,-0.7]) cube([82,66.6,28-0.7],center=true);
+ cylinder(h=28,d=1513*25.4/1000,center=true);
+ }
+ translate([0,70/2-1,-28/2-8/2]) cube([16,(70-66.6)/2,8],center=true);
+ translate([0,-70/2+1,-28/2-8/2]) cube([16,(70-66.6)/2,8],center=true);
+}
--- /dev/null
+scale([0.001,0.001,0.001])
+{
+ color("black") cylinder(d=57.12,h=50.16,center=false);
+ color("silver")
+ {
+ translate([0,0,50.16])
+ {
+ difference()
+ {
+ cube([57.12,57.12,5],center=true);
+ translate([23.52,23.52,0]) cylinder(d=5,h=5,center=true);
+ translate([23.52,-23.52,0]) cylinder(d=5,h=5,center=true);
+ translate([-23.52,23.52,0]) cylinder(d=5,h=5,center=true);
+ translate([-23.52,-23.52,0]) cylinder(d=5,h=5,center=true);
+ }
+ cylinder(d=2.54*2,h=15,center=false);
+ }
+ }
+}
\ No newline at end of file
--- /dev/null
+rotate([0,0,90]) scale([0.001,0.001,0.001]) color("silver")
+{
+ cylinder(h=130,d=9.35,center=false);
+ translate([0,0,130]) cylinder(h=876-130,d=10,center=false);
+ translate([0,0,876-25/2]) difference()
+ {
+ cube([400,50,25],center=true);
+
+ cube([400,50-4,25-4],center=true);
+
+ cylinder(h=25,d=25.4/2,center=true);
+
+ translate([25+150/2,0,0]) cube([150,5,25],center=true);
+ translate([25,0,0]) cylinder(h=25,d=5,center=true);
+ translate([25+150,0,0]) cylinder(h=25,d=5,center=true);
+
+ translate([-(25+150/2),0,0]) cube([150,5,25],center=true);
+ translate([-25,0,0]) cylinder(h=25,d=5,center=true);
+ translate([-(25+150),0,0]) cylinder(h=25,d=5,center=true);
+
+ }
+}
</joint>
<gazebo reference="${name}">
- <material>Gazebo/Gold</material>
+ <material>Gazebo/White</material>
</gazebo>
</xacro:macro>
--- /dev/null
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+ <xacro:property name="M_PI" value="3.1415926535897931" />
+ <xacro:property name="ABS_DENSITY" value="1200" />
+
+ <xacro:macro name="sonar" params="name parent *origin">
+
+ <link name="${name}_box">
+ <inertial>
+ <origin xyz="0.011687 0 0" rpy="0 0 0" />
+ <mass value="${3.109e-5*ABS_DENSITY}" />
+ <inertia ixx="${5.08964e-8*ABS_DENSITY}" ixy="0" ixz="0" iyy="${4.03098e-8*ABS_DENSITY}" iyz="0" izz="${1.97915e-8*ABS_DENSITY}" />
+ </inertial>
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/sonar_box.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="0 0 0 1" />
+ </material>
+ </visual>
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/sonar_box.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="${name}_box_joint" type="fixed">
+ <xacro:insert_block name="origin" />
+ <parent link="${parent}" />
+ <child link="${name}_box" />
+ </joint>
+
+ <gazebo reference="${name}_box">
+ <material>Gazebo/Black</material>
+ </gazebo>
+
+ <link name="${name}_cover">
+ <inertial>
+ <origin xyz="0.030163 0 0" rpy="0 0 0" />
+ <mass value="${1.27668e-5*ABS_DENSITY}" />
+ <inertia ixx="${1.91036e-8*ABS_DENSITY}" ixy="0" ixz="0" iyy="${8.73999e-9*ABS_DENSITY}" iyz="0" izz="${1.28721e-8*ABS_DENSITY}" />
+ </inertial>
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/sonar_cover.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="0.5 0.5 0.5 1" />
+ </material>
+ </visual>
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/sonar_cover.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="${name}_cover_joint" type="fixed">
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <parent link="${name}_box" />
+ <child link="${name}_cover" />
+ </joint>
+
+ <gazebo reference="${name}_cover">
+ <material>Gazebo/Gray</material>
+ </gazebo>
+
+ <link name="${name}_sensor">
+ <inertial>
+ <origin xyz="0.003870 0 0" rpy="0 0 0" />
+ <mass value="${1.44829e-5*ABS_DENSITY}" />
+ <inertia ixx="${2.98565e-9*ABS_DENSITY}" ixy="0" ixz="0" iyy="${1.64409e-9*ABS_DENSITY}" iyz="0" izz="${1.64419e-9*ABS_DENSITY}" />
+ </inertial>
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/polaroid600.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="1 0.75686 0.14510 1" />
+ </material>
+ </visual>
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/polaroid600.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="${name}_sensor_joint" type="fixed">
+ <origin xyz="${0.028+0.012} 0 0" rpy="0 0 0" />
+ <parent link="${name}_cover" />
+ <child link="${name}_sensor" />
+ </joint>
+
+ <gazebo reference="${name}_sensor">
+ <material>Gazebo/Orange</material>
+ </gazebo>
+
+ </xacro:macro>
+
+</robot>
--- /dev/null
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+ <xacro:property name="M_PI" value="3.1415926535897931" />
+
+ <xacro:macro name="step_motor" params="name parent *origin">
+
+ <link name="${name}">
+ <inertial>
+ <origin xyz="0 0 0.026946" rpy="0 0 0" />
+ <mass value="0.5" />
+ <inertia ixx="224.8E-6" ixy="0" ixz="0" iyy="224.8E-6" iyz="0" izz="209.4E-6" />
+ </inertial>
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/step_motor.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="0 0 0 1" />
+ </material>
+ </visual>
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/step_motor.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="${name}_motor_joint" type="fixed">
+ <xacro:insert_block name="origin" />
+ <parent link="${parent}" />
+ <child link="${name}" />
+ </joint>
+
+ <gazebo reference="${name}">
+ <material>Gazebo/Black</material>
+ </gazebo>
+
+ </xacro:macro>
+
+</robot>
--- /dev/null
+<?xml version="1.0" ?>
+
+<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
+
+ <xacro:property name="M_PI" value="3.1415926535897931" />
+
+ <xacro:macro name="tower" params="name parent *origin">
+
+ <link name="${name}">
+ <inertial>
+ <origin xyz="0 0 0.704262" rpy="0 0 0" />
+ <!-- Supposing aluminium with a density of 2700 kg/m^3 -->
+ <mass value="0.4664" />
+ <inertia ixx="0.0342" ixy="0" ixz="0" iyy="0.0304" iyz="0" izz="0.0040" />
+ </inertial>
+ <visual>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/tower.stl" />
+ </geometry>
+ <material name="">
+ <color rgba="0.75294 0.75294 0.75294 1" />
+ </material>
+ </visual>
+ <collision>
+ <origin xyz="0 0 0" rpy="0 0 0" />
+ <geometry>
+ <mesh filename="package://twil_description/meshes/tower.stl" />
+ </geometry>
+ </collision>
+ </link>
+
+ <joint name="${name}_joint" type="continuous">
+ <xacro:insert_block name="origin" />
+ <parent link="${parent}" />
+ <child link="${name}" />
+ <axis xyz="0 0 1" />
+ <limit effort="100.0" velocity="${1.8*M_PI/180*1000}" />
+ </joint>
+
+ <transmission name="${name}_transmission">
+ <type>transmission_interface/SimpleTransmission"</type>
+ <joint name="${name}_joint">
+ <hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
+ </joint>
+ <actuator name="${name}_motor">
+ <mechanicalReduction>1</mechanicalReduction>
+ </actuator>
+ </transmission>
+
+ <gazebo reference="${name}">
+ <material>Gazebo/White</material>
+ </gazebo>
+
+ </xacro:macro>
+
+</robot>
<xacro:include filename="$(find twil_description)/xacro/battery_bosch_12v.urdf.xacro" />
<xacro:include filename="$(find twil_description)/xacro/cpu.urdf.xacro" />
<xacro:include filename="$(find twil_description)/xacro/eurocard.urdf.xacro" />
+ <xacro:include filename="$(find twil_description)/xacro/tower.urdf.xacro" />
+ <xacro:include filename="$(find twil_description)/xacro/step_motor.urdf.xacro" />
+ <xacro:include filename="$(find twil_description)/xacro/sonar.urdf.xacro" />
<link name="twil_origin" />
<xacro:caster_wheel name="front_caster_wheel" parent="front_caster_base">
<origin xyz="-0.04 0 0" rpy="0 0 0" />
</xacro:caster_wheel>
+
+ <xacro:tower name="tower" parent="chassis">
+ <origin xyz="0.1875 0 0.306" rpy="0 0 0" />
+ </xacro:tower>
+
+ <xacro:step_motor name="tower_motor" parent="chassis">
+ <origin xyz="0.1875 0 0.24684" rpy="0 0 0" />
+ </xacro:step_motor>
+
+ <xacro:sonar name="top_sonar" parent="tower">
+ <origin xyz="0.005 0 ${0.876-0.04-0.04}" rpy="0 0 0" />
+ </xacro:sonar>
+
+ <xacro:sonar name="bottom_sonar" parent="tower">
+ <origin xyz="0.005 0 ${0.130+0.04+0.02}" rpy="0 0 0" />
+ </xacro:sonar>
<!--xacro:battery_bosch_12v name="battery" parent="chassis">
<origin xyz="-0.15 0.0 ${0.0015+0.0875}" rpy="0.0 0.0 ${M_PI/2}" />
</xacro:eurocard>
<xacro:cpu name="cpu" parent="chassis">
- <origin xyz="0 0.0 ${0.0015+0.3+0.003+0.127+0.003+0.17}" rpy="0.0 0.0 0.0" />
+ <origin xyz="0 0.0 ${0.0015+0.3+0.003+0.127+0.003+0.17}" rpy="0.0 0.0 ${M_PI/2}" />
</xacro:cpu>
<link name="chassis_top" />