Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Consistent frames for QT64 and XT32 lidars #3

Merged
merged 1 commit into from
May 3, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
12 changes: 2 additions & 10 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,17 +1,9 @@
cmake_minimum_required(VERSION 3.0.2)
project(hesai_description)

find_package(catkin REQUIRED COMPONENTS
xacro
)

catkin_package(CATKIN_DEPENDS xacro)

set(xacro_files
${CMAKE_CURRENT_SOURCE_DIR}/urdf/hesai_standalone.urdf.xacro
)
find_package(catkin REQUIRED COMPONENTS)

xacro_add_files(${xacro_files} INSTALL DESTINATION urdf)
catkin_package()

install(DIRECTORY config launch urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
Expand Down
6 changes: 2 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
# hesai_description
URDF Model of hesai lidar products
This package contains a **URDF Xacro description of the Hesai XT32 and QT64 lidars**. In simulation the Gazebo Velodyne plug-in is used. The meshes were obtained from the original CAD provided by Hesai.

The mesh was obtained from the original CAD provided by HESAI.

This repository is not associated to or maintained by HESAI.
This repository is not associated to or maintained by Hesai.
5 changes: 3 additions & 2 deletions launch/load.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@

<launch>
<arg name="simulation" default="false" />
<arg name="model" default="$(find hesai_description)/urdf/hesai_standalone.urdf.xacro" />
<arg name="use_gpu" default="true" />
<arg name="model" default="$(find hesai_description)/urdf/hesai_qt64_standalone.urdf.xacro" />

<param name="robot_description" command="xacro $(arg model) simulation:=$(arg simulation)" />
<param name="robot_description" command="xacro $(arg model) simulation:=$(arg simulation) use_gpu:=$(arg use_gpu)" />
</launch>
2 changes: 2 additions & 0 deletions launch/view_urdf.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,11 @@
<launch>
<arg name="rviz" default="true" />
<arg name="simulation" default="true" />
<arg name="use_gpu" default="true" />

<include file="$(find hesai_description)/launch/load.launch">
<arg name="simulation" value="$(arg simulation)"/>
<arg name="use_gpu" value="$(arg use_gpu)"/>
</include>

<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,5 +10,5 @@
<license>Apache 2.0</license>

<buildtool_depend>catkin</buildtool_depend>
<depend>xacro</depend>
<exec_depend>xacro</exec_depend>
</package>
76 changes: 76 additions & 0 deletions urdf/gazebo.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<!-- Copyright 2024 University of Oxford

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->

<xacro:macro name="hesai_gazebo" params="lidar_frame:=pandar topic_name=/hesai/pandar
min_range:=0.4 max_range:=80.0 min_horizontal_angle:=-180.0 max_horizontal_angle:=180.0
min_vertical_angle:=-16.0 max_vertical_angle:=15.0 hz:=10 samples:=2000 lasers:=32
collision_range:=0.3 noise:=0.008 visualize:=false use_gpu:=true">

<gazebo reference="${lidar_frame}">
<xacro:if value="${use_gpu}">
<xacro:property name="ray_type" value="gpu_ray" />
<xacro:property name="laser_plugin" value="libgazebo_ros_velodyne_gpu_laser.so" />
</xacro:if>
<xacro:unless value="${use_gpu}">
<xacro:property name="ray_type" value="ray" />
<xacro:property name="laser_plugin" value="libgazebo_ros_velodyne_laser.so" />
</xacro:unless>

<sensor type="${ray_type}" name="hesai_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>${visualize}</visualize>
<update_rate>${hz}</update_rate>
<ray>
<scan>
<horizontal>
<samples>${samples}</samples>
<resolution>1</resolution>
<min_angle>${min_horizontal_angle*pi/180.0}</min_angle>
<max_angle>${max_horizontal_angle*pi/180.0}</max_angle>
</horizontal>
<vertical>
<samples>${lasers}</samples>
<resolution>1</resolution>
<min_angle>${min_vertical_angle*pi/180.0}</min_angle>
<max_angle>${max_vertical_angle*pi/180.0}</max_angle>
</vertical>
</scan>
<range>
<min>${collision_range}</min>
<max>${max_range+1}</max>
<resolution>0.001</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.0</stddev>
</noise>
</ray>

<plugin name="gazebo_ros_laser_controller" filename="${laser_plugin}">
<topicName>${topic_name}</topicName>
<frameName>${lidar_frame}</frameName>
<min_range>${min_range}</min_range>
<max_range>${max_range}</max_range>
<gaussianNoise>${noise}</gaussianNoise>
</plugin>
</sensor>
</gazebo>
</xacro:macro>

</robot>
74 changes: 74 additions & 0 deletions urdf/hesai_qt64.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
<?xml version="1.0"?>

<!-- Copyright 2022 University of Oxford

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
-->


<!-- Hesai PandarQT-64 Lidar Sensor -->
<robot name="hesai_qt64" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:arg name="simulation" default="false"/>
<xacro:arg name="use_gpu" default="true"/>

<xacro:macro name="hesai_qt64_device" params="parent *origin name:=pandar_xt32_lidar simulation:=false lidar_frame:=pandar use_gpu:=true">
<joint name="${parent}_to_hesai" type="fixed">
<xacro:insert_block name="origin"/>
<parent link="${parent}" />
<child link="hesai_base" />
</joint>
<link name="hesai_base">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<!-- If mesh is not available: -->
<!--origin xyz="0 0 38.0e-3" rpy="0 0 0" /-->
<geometry>
<!-- If mesh is not available: -->
<!--cylinder radius="51.500e-3" length="76.0e-3" /-->
<mesh filename="package://hesai_description/urdf/meshes/PandarQT64_model.dae" />
</geometry>
</visual>
<inertial>
<!-- CoM taken from CAD assuming constant density and mass 0.807 (best approximation available to real mass) -->
<origin xyz="-0.015e-3 0.0 37.494e-3" rpy="0 0 0" />
<!-- mass taken from Hesai datasheet -->
<mass value="0.807" />
<!-- Inertia tensor from CAD assuming constant density and mass 0.807 (best approximation vailable to real mass) -->
<inertia ixx="886.81e-6" ixy="5.802e-11" ixz="-0.34e-6" iyy="898.12e-6" iyz="-0.014e-6" izz="1004.287e-6" />
</inertial>
<collision>
<origin xyz="0 0 38.0e-3"/>
<geometry>
<cylinder radius="51.500e-3" length="76.0e-3" />
</geometry>
</collision>
</link>
<link name="${lidar_frame}"/>
<joint name="hesai_base_to_pandar" type="fixed">
<!-- See page 12 of QT64 User Manual -->
<!-- note that the X axis points left. See manual page 11 -->
<origin xyz="0.0 0.0 50.4e-3" rpy="0.0 0.0 ${pi/2}"/>
<parent link="hesai_base"/>
<child link="${lidar_frame}" />
</joint>

<xacro:if value="${simulation}">
<xacro:include filename="$(find hesai_description)/urdf/gazebo.urdf.xacro"/>
<xacro:hesai_gazebo lidar_frame="${lidar_frame}" topic_name="/hesai/pandar" min_range="0.1" max_range="20.0"
min_horizontal_angle="-180.0" max_horizontal_angle="180.0" min_vertical_angle="-52.1" max_vertical_angle="52.1"
hz="10" samples="600" lasers="64" collision_range="0.3" noise="0.008" use_gpu="${use_gpu}"
/>
</xacro:if>
</xacro:macro>

</robot>
Original file line number Diff line number Diff line change
Expand Up @@ -15,13 +15,14 @@
limitations under the License. -->

<robot name="hesai" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find hesai_description)/urdf/hesai.urdf.xacro" />
<xacro:include filename="$(find hesai_description)/urdf/hesai_qt64.urdf.xacro" />
<xacro:arg name="simulation" default="false" />
<xacro:arg name="use_gpu" default="true" />

<!-- Dummy link -->
<link name="base"/>

<xacro:hesai_device parent="base" simulation="$(arg simulation)">
<xacro:hesai_qt64_device parent="base" simulation="$(arg simulation)" use_gpu="$(arg use_gpu)" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:hesai_device>
</xacro:hesai_qt64_device>
</robot>
61 changes: 0 additions & 61 deletions urdf/hesai_standalone.urdf

This file was deleted.

17 changes: 12 additions & 5 deletions urdf/hesai.urdf.xacro → urdf/hesai_xt32.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,11 @@


<!-- Hesai PandarXT-32 Lidar Sensor -->
<robot name="hesai" xmlns:xacro="http://www.ros.org/wiki/xacro">
<robot name="hesai_xt32" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:arg name="simulation" default="false" />
<xacro:arg name="use_gpu" default="true"/>

<xacro:macro name="hesai_device" params="parent *origin name:=pandar_xt32_lidar simulation:=false lidar_frame:=pandar">
<xacro:macro name="hesai_xt32_device" params="parent *origin name:=pandar_xt32_lidar simulation:=false lidar_frame:=pandar use_gpu:=true">
<joint name="${parent}_to_hesai" type="fixed">
<xacro:insert_block name="origin"/>
<parent link="${parent}" />
Expand Down Expand Up @@ -54,14 +55,20 @@
</link>
<link name="${lidar_frame}"/>
<joint name="hesai_base_to_pandar" type="fixed">
<!-- See page 12 of User Manual -->
<!-- See page 12 of XT64 User Manual -->
<!-- note that the X axis points left. See manual page 11 -->
<origin xyz="0.0 0.0 50.4e-3" rpy="0.0 0.0 0.0"/>
<origin xyz="0.0 0.0 46.4e-3" rpy="0.0 0.0 ${pi/2}"/>
<parent link="hesai_base"/>
<child link="${lidar_frame}" />
</joint>

<!-- TODO implement gazebo plugin loading if simulation is true -->
<xacro:if value="${simulation}">
<xacro:include filename="$(find hesai_description)/urdf/gazebo.urdf.xacro"/>
<xacro:hesai_gazebo lidar_frame="${lidar_frame}" topic_name="/hesai/pandar" min_range="0.4" max_range="80.0"
min_horizontal_angle="-180.0" max_horizontal_angle="180.0" min_vertical_angle="-16.0" max_vertical_angle="15.0"
hz="10" samples="2000" lasers="32" collision_range="0.3" noise="0.008" use_gpu="${use_gpu}"
/>
</xacro:if>
</xacro:macro>

</robot>
28 changes: 28 additions & 0 deletions urdf/hesai_xt32_standalone.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
<?xml version="1.0"?>

<!-- Copyright 2022 University of Oxford

Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License. -->

<robot name="hesai" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:include filename="$(find hesai_description)/urdf/hesai_xt32.urdf.xacro" />
<xacro:arg name="simulation" default="false" />
<xacro:arg name="use_gpu" default="true" />

<!-- Dummy link -->
<link name="base"/>

<xacro:hesai_xt32_device parent="base" simulation="$(arg simulation)" use_gpu="$(arg use_gpu)" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:hesai_xt32_device>
</robot>
56 changes: 56 additions & 0 deletions urdf/meshes/PandarQT64_model.dae

Large diffs are not rendered by default.

88 changes: 88 additions & 0 deletions urdf/meshes/PandarQT64_model_original_from_step.dae

Large diffs are not rendered by default.