-
Notifications
You must be signed in to change notification settings - Fork 276
/
quadrotor_base.urdf.xacro
38 lines (31 loc) · 1.27 KB
/
quadrotor_base.urdf.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find hector_sensors_description)/urdf/sonar_sensor.urdf.xacro" />
<xacro:property name="pi" value="3.1415926535897931" />
<!-- Main quadrotor link -->
<xacro:macro name="quadrotor_base_macro">
<link name="base_link">
<inertial>
<mass value="1.477" />
<origin xyz="0 0 0" />
<inertia ixx="0.01152" ixy="0.0" ixz="0.0" iyy="0.01152" iyz="0.0" izz="0.0218" />
</inertial>
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://hector_quadrotor_description/meshes/quadrotor/quadrotor_base.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://hector_quadrotor_description/meshes/quadrotor/quadrotor_base.stl"/>
</geometry>
</collision>
</link>
<!-- Sonar height sensor -->
<xacro:sonar_sensor name="sonar" parent="base_link" ros_topic="sonar_height" update_rate="10" min_range="0.03" max_range="3.0" field_of_view="${40*pi/180}" ray_count="3">
<origin xyz="-0.16 0.0 -0.012" rpy="0 ${90*pi/180} 0"/>
</xacro:sonar_sensor>
</xacro:macro>
</robot>