forked from start-jsk/jsk_mbzirc
-
Notifications
You must be signed in to change notification settings - Fork 0
/
quadrotor_with_hokyo30lx_and_downward_cam.urdf.xacro
36 lines (27 loc) · 1.66 KB
/
quadrotor_with_hokyo30lx_and_downward_cam.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
<?xml version="1.0"?>
<robot name="quadrotor" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Included URDF Files -->
<xacro:include filename="$(find hector_quadrotor_description)/urdf/quadrotor_base.urdf.xacro" />
<xacro:include filename="$(find hector_quadrotor_gazebo)/urdf/quadrotor_plugins.gazebo.xacro" />
<!-- Instantiate quadrotor_base_macro once (has no parameters atm) -->
<xacro:quadrotor_base_macro />
<xacro:property name="M_PI" value="3.1415926535897931" />
<!-- Custom sensors settings -->
<!-- Hokuyo UTM-30LX mounted upside down below the quadrotor body -->
<xacro:include filename="$(find hector_sensors_description)/urdf/hokuyo_utm30lx.urdf.xacro" />
<xacro:hokuyo_utm30lx name="laser0" parent="base_link" ros_topic="scan" update_rate="40"
ray_count="1081" min_angle="-135" max_angle="135">
<origin xyz="0.0 0.0 -0.097" rpy="${M_PI} 0 0"/>
</xacro:hokuyo_utm30lx>
<!-- Downward facing camera -->
<xacro:include filename="$(find hector_sensors_description)/urdf/generic_camera.urdf.xacro" />
<xacro:generic_camera name="downward_cam" parent="base_link" ros_topic="camera/image" cam_info_topic="camera/camera_info"
update_rate="20" res_x="640" res_y="480" image_format="L8" hfov="100">
<origin xyz="0.4 0.0 -0.0" rpy="0 ${M_PI/2} 0"/>
</xacro:generic_camera>
<!-- side facing camera -->
<xacro:generic_camera name="side_cam" parent="base_link" ros_topic="camera/image" cam_info_topic="camera/camera_info"
update_rate="20" res_x="640" res_y="480" image_format="L8" hfov="100">
<origin xyz="-0.4 0.0 -0.0" rpy="${M_PI} ${M_PI} 0"/>
</xacro:generic_camera>
</robot>