aquanaute_description.urdf.xacro 4.68 KB
Newer Older
1
<?xml version="1.0"?>
2
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="aquanaute">
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
3
4
5
6
7
8
9
10

    <material name="blue">
        <color rgba="0 0 0.8 1"/>
    </material>
    <material name="red">
        <color rgba="0.8 0 0 1"/>
    </material>
    <material name="green">
11
        <color rgba="0 0.8 0 0.5"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
    </material>
    <material name="cyan">
        <color rgba="0 0.6 0.6 1"/>
    </material>
    <material name="yellow">
        <color rgba="0.8 0.8 0 1"/>
    </material>
    <material name="purple">
        <color rgba="0.5 0 0.5 1"/>
    </material>
    <material name="white">
        <color rgba="1 1 1 1"/>
    </material>
    <material name="gray">
        <color rgba="0.35 0.35 0.35 1"/>
    </material>
    <material name="black">
        <color rgba="0 0 0 1"/>
    </material>

32
    <!-- * * * Link Definitions * * * -->
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
33
    <link name="base_link">
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
34
        <visual>
35
            <origin rpy="0 0 0" xyz="0 0 0"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
36
37
38
39
40
41
42
            <geometry>
                <sphere radius="0.001"/>
            </geometry>
            <material name="blue"/>
        </visual>
    </link>

43
    <link name="boat_link">
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
44
45
        <inertial>
            <origin xyz="0 0 0" rpy="0 0 0"/>
46
47
            <mass value="38.718"/>
            <inertia ixx="16.283" ixy="0.008" ixz="0.458" iyy="19.728" iyz="0.0" izz="33.013"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
48
49
50
51
52
        </inertial>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
53
                <mesh filename="package://aquanaute_description/models/meshes/Assambly_aquanaute.stl"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
54
55
56
57
            </geometry>
        </collision>

        <visual>
58
            <origin rpy="0 0 0" xyz="0 0 0"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
59
            <geometry>
60
                <mesh filename="package://aquanaute_description/models/meshes/Assambly_aquanaute.stl"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
61
            </geometry>
62
            <material name="gray"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
63
64
65
66
67
        </visual>
    </link>

    <link name="motor_link">
        <inertial>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
68
69
70
            <origin xyz="-0.133 0 -0.391" rpy="0 0 0"/>
            <mass value="6.6"/>
            <inertia ixx="0.072" ixy="3.604" ixz="-0.011" iyy="0.111" iyz="5.484" izz="0.042"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
71
72
73
74
75
76
77
78
79
80
        </inertial>

        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Motor.stl"/>
            </geometry>
        </collision>

        <visual>
81
            <origin rpy="0 0 0" xyz="0 0 0"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
82
83
84
            <geometry>
                <mesh filename="package://aquanaute_description/models/meshes/Motor.stl"/>
            </geometry>
85
            <material name="purple"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
86
87
88
        </visual>
    </link>

89
    <link name="propeller_link">
90
91
92
        <inertial>
            <origin xyz="-0.034 0 0" rpy="0 0 0"/>
            <mass value="0.233"/>
93
94
            <!--<inertia ixx="1.441e-04" ixy="4.406e-09" ixz="0.00" iyy="1.760e-04"	iyz="2.373e-06" izz="1.961e-04"/>-->
            <inertia ixx="0.00" ixy="0.00" ixz="0.00" iyy="0.00" iyz="0.00" izz="0.00"/>
95
96
        </inertial>

97
98
99
        <collision>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
100
                <mesh filename="package://aquanaute_description/models/meshes/Propeller.stl"/>
101
102
103
104
            </geometry>
        </collision>

        <visual>
105
            <origin rpy="0 0 0" xyz="0 0 0"/>
106
            <geometry>
107
                <mesh filename="package://aquanaute_description/models/meshes/Propeller.stl"/>
108
            </geometry>
109
            <material name="blue"/>
110
111
112
        </visual>
    </link>

113
114
    <link name="imu_link">
        <visual>
115
            <origin rpy="0 0 0" xyz="0 0 0"/>
116
117
118
119
120
121
122
            <geometry>
                <cylinder radius="0.04" length="0.05"/>
            </geometry>
            <material name="cyan"/>
        </visual>
    </link>

Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
123
    <!-- * * * Joint Definitions * * * -->
124
    <joint name="boat_base_joint" type="fixed">
125
        <parent link="base_link"/>
126
127
        <child link="boat_link"/>
        <origin xyz="0 0 0.25" rpy="0 0 0"/>
128
    </joint>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
129

130
131
    <joint name="motor_boat_joint" type="revolute">
        <parent link="boat_link"/>
132
        <child link="motor_link"/>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
133
        <origin xyz="-0.905 0.0 0.115" rpy="0 0 0"/>
134
        <axis xyz="0 0 1"/>
135
136
        <limit effort="-1" velocity="-1" lower="-0.9" upper="0.9"/>
        <dynamics damping="0.0000001"/>
137
138
    </joint>

139
    <joint name="propeller_motor_joint" type="revolute">
140
141
        <parent link="motor_link"/>
        <child link="propeller_link"/>
142
143
        <origin xyz="-0.265 0 -0.42" rpy="0 0 0"/>
        <axis xyz="1 0 0"/>
144
145
        <limit effort="-1" velocity="-1" lower="-1e+16" upper="1e+16"/>
        <dynamics damping="0.0000001"/>
146
    </joint>
Ricardo Rico Uribe's avatar
Ricardo Rico Uribe committed
147

148
149
    <joint name="imu_boat_joint" type="fixed">
        <parent link="boat_link"/>
150
        <child link="imu_link"/>
151
        <origin xyz="0 0 0.04" rpy="0 0 0"/>
152
    </joint>
153
</robot>