This commit is contained in:
Quella777
2025-08-25 16:30:02 +08:00
commit 32cc2a8e96
1633 changed files with 289456 additions and 0 deletions

253
hokuyo/meshes/hokuyo.dae Normal file

File diff suppressed because one or more lines are too long

Binary file not shown.

41
hokuyo/model-1_2.sdf Normal file
View File

@@ -0,0 +1,41 @@
<?xml version="1.0" ?>
<gazebo version="1.2">
<model name="hokuyo">
<link name="link">
<gravity>false</gravity>
<inertial>
<mass>0.1</mass>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name="laser" type="ray">
<pose>0.01 0 0.03 0 -0 0</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.26889</min_angle>
<max_angle>2.268899</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>10</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="laser" filename="libRayPlugin.so" />
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</gazebo>

62
hokuyo/model-1_3.sdf Normal file
View File

@@ -0,0 +1,62 @@
<?xml version="1.0" ?>
<sdf version="1.3">
<model name="hokuyo">
<pose>0 0 0.035 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.1</mass>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision-base">
<pose>0 0 -0.0145 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.041</size>
</box>
</geometry>
</collision>
<collision name="collision-top">
<pose>0 0 0.0205 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.021</radius>
<length>0.029</length>
</cylinder>
</geometry>
</collision>
<sensor name="laser" type="ray">
<pose>0.01 0 0.0175 0 -0 0</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.26889</min_angle>
<max_angle>2.268899</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>10</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="laser" filename="libRayPlugin.so" />
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</sdf>

62
hokuyo/model-1_4.sdf Normal file
View File

@@ -0,0 +1,62 @@
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="hokuyo">
<pose>0 0 0.035 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.1</mass>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision-base">
<pose>0 0 -0.0145 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.041</size>
</box>
</geometry>
</collision>
<collision name="collision-top">
<pose>0 0 0.0205 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.021</radius>
<length>0.029</length>
</cylinder>
</geometry>
</collision>
<sensor name="laser" type="ray">
<pose>0.01 0 0.0175 0 -0 0</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.26889</min_angle>
<max_angle>2.268899</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>10</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="laser" filename="libRayPlugin.so" />
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</sdf>

19
hokuyo/model.config Normal file
View File

@@ -0,0 +1,19 @@
<?xml version="1.0"?>
<model>
<name>Hokuyo</name>
<version>1.0</version>
<sdf version="1.2">model-1_2.sdf</sdf>
<sdf version="1.3">model-1_3.sdf</sdf>
<sdf version="1.4">model-1_4.sdf</sdf>
<sdf version="1.5">model.sdf</sdf>
<author>
<name>John Hsu</name>
<email>hsu@osrfoundation.org</email>
</author>
<description>
Hokuyo model
</description>
</model>

57
hokuyo/model.sdf Normal file
View File

@@ -0,0 +1,57 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="hokuyo">
<pose>0 0 0.035 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.1</mass>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision-base">
<pose>0 0 -0.0145 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.041</size>
</box>
</geometry>
</collision>
<collision name="collision-top">
<pose>0 0 0.0205 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.021</radius>
<length>0.029</length>
</cylinder>
</geometry>
</collision>
<sensor name="laser" type="ray">
<pose>0.01 0 0.0175 0 -0 0</pose>
<ray>
<scan>
<horizontal>
<samples>640</samples>
<resolution>1</resolution>
<min_angle>-2.26889</min_angle>
<max_angle>2.268899</max_angle>
</horizontal>
</scan>
<range>
<min>0.08</min>
<max>10</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="laser" filename="libRayPlugin.so" />
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</sdf>