Skip to content

Commit 7db7430

Browse files
committed
add hokuyo and adjust quimera_robot folder name.
1 parent f4423af commit 7db7430

File tree

10 files changed

+333
-2
lines changed

10 files changed

+333
-2
lines changed
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.
File renamed without changes.

meshes/sensors/hokuyo.dae

Lines changed: 253 additions & 0 deletions
Large diffs are not rendered by default.

urdf/include/common_sensors.xacro

Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
4+
<xacro:macro name="hokuyo_sensor" params=" *joint_origin parent_link ">
5+
6+
<link name="hokuyo_link">
7+
<collision>
8+
<origin xyz="0 0 0" rpy="0 0 0"/>
9+
<geometry>
10+
<box size="0.06 0.06 0.087"/>
11+
</geometry>
12+
</collision>
13+
<visual>
14+
<origin xyz="0 0 0" rpy="0 0 0"/>
15+
<geometry>
16+
<mesh filename="package://${package_name}/meshes/sensors/hokuyo.dae" />
17+
</geometry>
18+
</visual>
19+
<inertial>
20+
<mass value="1e-5" />
21+
<origin xyz="0 0 0" rpy="0 0 0"/>
22+
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
23+
</inertial>
24+
</link>
25+
26+
<joint name="hokuyo_joint" type="fixed">
27+
<axis xyz="0 1 0" />
28+
<xacro:insert_block name="joint_origin" />
29+
<parent link="${parent_link}"/>
30+
<child link="hokuyo_link"/>
31+
</joint>
32+
33+
<!-- hokuyo gazebo references -->
34+
<gazebo reference="hokuyo_link">
35+
<sensor type="gpu_ray" name="head_hokuyo_sensor">
36+
<pose>0 0 0 0 0 0</pose>
37+
<visualize>false</visualize>
38+
<update_rate>40</update_rate>
39+
<ray>
40+
<scan>
41+
<horizontal>
42+
<samples>720</samples>
43+
<resolution>1</resolution>
44+
<min_angle>-1.570796</min_angle>
45+
<max_angle>1.570796</max_angle>
46+
</horizontal>
47+
</scan>
48+
<range>
49+
<min>0.10</min>
50+
<max>30.0</max>
51+
<resolution>0.01</resolution>
52+
</range>
53+
<noise>
54+
<type>gaussian</type>
55+
<!--Noise parameters based on published spec for Hokuyo laser
56+
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
57+
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
58+
reading. -->
59+
<mean>0.0</mean>
60+
<stddev>0.01</stddev>
61+
</noise>
62+
</ray>
63+
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_gpu_laser.so">
64+
<topicName>/${robot_name}/scan</topicName>
65+
<frameName>hokuyo_link</frameName>
66+
</plugin>
67+
</sensor>
68+
</gazebo>
69+
70+
</xacro:macro>
71+
72+
</robot>

urdf/quimera_robot.urdf.xacro

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,9 +2,10 @@
22
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="quimera_robot">
33

44
<xacro:property name="package_name" value="mobile_robot_description"/>
5-
<xacro:property name="robot_name" value="quimera"/>
5+
<xacro:property name="robot_name" value="quimera_robot"/>
66

77
<xacro:include filename="$(find ${package_name})/urdf/include/common_macros.urdf.xacro" />
8+
<xacro:include filename="$(find ${package_name})/urdf/include/common_sensors.xacro" />
89
<xacro:include filename="$(find ${package_name})/urdf/quimera_robot.gazebo.xacro" />
910

1011
<xacro:property name="back_wheel_yaml" value="$(find ${package_name})/config/${robot_name}/back_wheel.yaml" />
@@ -44,6 +45,11 @@
4445
wheel_props="${front_wheel_props}"
4546
base_props="${base_props}">
4647
</xacro:wheel>
47-
48+
49+
<!-- Sensors -->
50+
51+
<xacro:hokuyo_sensor parent_link="base_link" >
52+
<origin xyz="-0.02 0 ${base_props['base']['z_size'] + 0.05}" rpy="0 0 0" />
53+
</xacro:hokuyo_sensor>
4854

4955
</robot>

0 commit comments

Comments
 (0)