-
Notifications
You must be signed in to change notification settings - Fork 0
/
base.xacro
101 lines (86 loc) · 4.06 KB
/
base.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Loading some constants -->
<xacro:include filename="$(find uuv_descriptions)/urdf/common.urdf.xacro"/>
<!-- Loading file with sensor macros -->
<xacro:include filename="$(find uuv_sensor_ros_plugins)/urdf/sensor_snippets.xacro"/>
<!-- Loading the UUV simulator ROS plugin macros -->
<xacro:include filename="$(find uuv_gazebo_ros_plugins)/urdf/snippets.xacro"/>
<!-- Loading vehicle's specific macros -->
<xacro:include filename="$(find submarine_description)/urdf/snippets.xacro"/>
<!--
Vehicle's parameters (remember to enter the model parameters below)
-->
<!--xacro:property name="mass" value="31.233724"/-->
<xacro:property name="mass" value="69.903673598"/>
<!-- Center of gravity -->
<xacro:property name="cog" value="0 0 0"/>
<!-- Fluid density -->
<xacro:property name="rho" value="1028"/>
<!--
Visual mesh file for the vehicle, usually in DAE (Collada) format. Be sure to store the
mesh with the origin of the mesh on the same position of the center of mass, otherwise
the mesh pose will have to be corrected below in the <visual> block.
Open the meshes for the submarine vehicle in Blender to see an example on the mesh placement.
-->
<xacro:property name="visual_mesh_file" value="file://$(find submarine_description)/meshes/strange_body_RED.dae"/>
<!-- Collision geometry mesh, usually in STL format (it is recommended to keep
this geometry as simple as possible to improve the performance the physics engine
regarding the computation of collision forces) -->
<xacro:property name="collision_mesh_file" value="file://$(find submarine_description)/meshes/strange_body.stl"/>
<!-- Vehicle macro -->
<xacro:macro name="submarine_base" params="namespace *gazebo">
<!-- Rigid body description of the base link -->
<link name="${namespace}/base_link">
<!--
Be careful to setup the coefficients for the inertial tensor,
otherwise your model will become unstable on Gazebo
-->
<inertial>
<mass value="${mass}" />
<origin xyz="${cog}" rpy="0 0 0"/>
<!--inertia ixx="0.000212" ixy="-0.000003" ixz="-0.000015"
iyy="0.001941" iyz="0.000000"
izz="0.002028" /-->
<!--inertia ixx="${0.5 * mass * submarine_radius * submarine_radius}" ixy="0" ixz="0"
iyy="${0.083333333 * mass * 3 * submarine_radius * submarine_radius + 0.083333333 * mass * submarine_length * submarine_length}" iyz="0"
izz="${0.083333333 * mass * 3 * submarine_radius * submarine_radius + 0.083333333 * mass * submarine_length * submarine_length}" />
</inertial-->
<inertia ixx="0.6" ixy="0" ixz="0"
iyy="30.0" iyz="0"
izz="35.0" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="${visual_mesh_file}" scale="1 1 1" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<mesh filename="${collision_mesh_file}" scale="1 1 1" />
</geometry>
</collision>
</link>
<gazebo reference="${namespace}/base_link">
<light name='cylinder/light_source1' type='spot'>
</light>
<plugin name='light_control' filename='libFlashLightPlugin.so'>
<enable>true</enable>
<light>
<id>cylinder/light_source1</id>
<duration>0.5</duration>
<interval>0.5</interval>
</light>
</plugin>
<selfCollide>false</selfCollide>
</gazebo>
<!-- Set up hydrodynamic plugin given as input parameter -->
<xacro:insert_block name="gazebo"/>
<!-- Include the thruster modules -->
<xacro:include filename="$(find submarine_description)/urdf/actuators.xacro"/>
<!-- Include the sensor modules -->
<xacro:include filename="$(find submarine_description)/urdf/sensors.xacro"/>
</xacro:macro>
</robot>