Skip to content

Commit

Permalink
add option to set horizontal_samples for lidars as a spawner param
Browse files Browse the repository at this point in the history
  • Loading branch information
stibipet committed Nov 3, 2023
1 parent be4d51e commit 8d6b558
Show file tree
Hide file tree
Showing 7 changed files with 51 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ enable_velodyne: [False, 'Add Velodyne PUCK Lite laser scanner to the vehicle',
enable_ouster: [False, 'Add Ouster laser scanner to the vehicle', [f450, f550, t650, x500, eaglemk2, naki, big_dofec]]
ouster_model: ['OS1-16', 'Choose the Ouster model. Options: OS0-32, OS0-64, OS0-128, OS1-16, OS1-32G1, OS1-32, OS1-64, OS1-128, OS2-32, OS2-64, OS2-128', [f450, f550, t650, x500, eaglemk2, naki, big_dofec]]
use_gpu_ray: [False, 'Laser ray casting will be handled by GPU shaders', [f330, f450, f550, t650, x500, eaglemk2, naki, big_dofec]]
horizontal_samples: [None, 'Override default base number of horizontal samples for LiDARs', [f450, f550, t650, x500, naki]]
enable_light: [False, 'Add light to the vehicle', [f450, f550, t650, x500, naki]]
enable_servo_camera: [False, 'Add camera on virtual servo to the vehicle', [f450, f550, t650, naki]]
enable_water_gun: [False, 'Add water gun for fire fighting', [t650]]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1501,7 +1501,12 @@ limitations under the License.
<!--}-->

<!-- Macro to add a RPlidar A3{-->
{%- macro rplidar_macro(namespace, parent_link, x, y, z, roll, pitch, yaw) -%}
{%- macro rplidar_macro(namespace, parent_link, horizontal_samples, x, y, z, roll, pitch, yaw) -%}
{% if horizontal_samples == 'None' %}
{%- set samples = 14400 -%}
{% else %}
{%- set samples = horizontal_samples | int -%}
{% endif %}
<link name="rplidar_link">
<pose>{{ x }} {{ y }} {{ z }} {{ roll }} {{ pitch }} {{ yaw }}</pose>
{{ zero_inertial_macro() }}
Expand Down Expand Up @@ -1541,7 +1546,7 @@ limitations under the License.
<ray>
<scan>
<horizontal>
<samples>{{ 14400/20 }}</samples>
<samples>{{ samples/20 }}</samples>
<resolution>1</resolution>
<min_angle>-3.1241390751</min_angle>
<max_angle>3.1241390751</max_angle>
Expand Down Expand Up @@ -1580,7 +1585,7 @@ limitations under the License.
<!--}-->

<!-- Macro to add a Velodyne Lidar {-->
{%- macro velodyne_macro(namespace, parent_link, sensor_name, rot_freq, lasers, max_range, noise, vfov_angle, enable_gpu_ray, x, y, z, roll, pitch, yaw) -%}
{%- macro velodyne_macro(namespace, parent_link, sensor_name, rot_freq, lasers, max_range, noise, vfov_angle, enable_gpu_ray, horizontal_samples, x, y, z, roll, pitch, yaw) -%}

{# The real ouster is transforming lidar data from lidar_frame to sensor_frame directly for user. #}
{# For simplicity, we are placing sensor_frame to the same place as the lidar_frame is. #}
Expand Down Expand Up @@ -1612,6 +1617,12 @@ limitations under the License.
{%- set sensor_type = "ray" -%}
{% endif %}

{% if horizontal_samples == 'None' %}
{%- set samples = 291200 -%}
{% else %}
{%- set samples = horizontal_samples | int -%}
{% endif %}

<link name="velodyne_link">
<pose>{{ x }} {{ y }} {{ z }} {{ roll }} {{ pitch }} {{ yaw }}</pose>
{{ zero_inertial_macro() }}
Expand Down Expand Up @@ -1668,7 +1679,7 @@ limitations under the License.
<ray>
<scan>
<horizontal>
<samples>{{ 291200/(rot_freq*lasers) }}</samples>
<samples>{{ samples/(rot_freq*lasers) }}</samples>
<resolution>1</resolution>
<min_angle>{{ -rad180 }}</min_angle>
<max_angle>{{ rad180 }}</max_angle>
Expand Down Expand Up @@ -1722,7 +1733,7 @@ limitations under the License.
<!-- Macro to add an Ouster Lidar {-->

<!-- Macro to add an Generic Ouster Lidar {-->
{%- macro generic_ouster_macro(namespace, parent_link, sensor_name, rot_freq, lasers, max_range, noise, vfov_angle, enable_gpu_ray, x, y, z, roll, pitch, yaw) -%}
{%- macro generic_ouster_macro(namespace, parent_link, sensor_name, rot_freq, lasers, max_range, noise, vfov_angle, enable_gpu_ray, horizontal_samples, x, y, z, roll, pitch, yaw) -%}

{# The real ouster is transforming lidar data from lidar_frame to sensor_frame directly for user. #}
{# For simplicity, we are placing sensor_frame to the same place as the lidar_frame is. #}
Expand Down Expand Up @@ -1765,6 +1776,12 @@ limitations under the License.
{%- set sensor_type = "ray" -%}
{% endif %}

{% if horizontal_samples == 'None' %}
{%- set samples = 20480 -%}
{% else %}
{%- set samples = horizontal_samples | int -%}
{% endif %}

<link name="{{ sensor_link }}">
<pose>{{ x }} {{ y }} {{ z }} {{ roll }} {{ pitch }} {{ yaw }}</pose>
{{ zero_inertial_macro() }}
Expand Down Expand Up @@ -1798,7 +1815,7 @@ limitations under the License.
</script>
</material>
</visual>

{# IMU #}
<sensor name="{{ sensor_name }}_imu_sensor" type="imu">
<pose>{{ imu_x }} {{ imu_y }} {{ imu_z }} {{ imu_roll }} {{ imu_pitch }} {{ imu_yaw }}</pose>
Expand Down Expand Up @@ -1829,7 +1846,7 @@ limitations under the License.
<!-- <headingGaussianNoise>0.005</headingGaussianNoise> -->
<!-- </plugin> -->
</sensor>

{# LIDAR #}
<sensor name="{{ sensor_name }}_lidar_sensor" type="{{ sensor_type }}">
<pose>{{ lidar_x }} {{ lidar_y }} {{ lidar_z }} {{ lidar_roll }} {{ lidar_pitch }} {{ lidar_yaw }}</pose>
Expand All @@ -1839,7 +1856,7 @@ limitations under the License.
<ray>
<scan>
<horizontal>
<samples>{{ 20480/rot_freq }}</samples>
<samples>{{ samples/rot_freq }}</samples>
<resolution>1</resolution>
<min_angle>0</min_angle>
<max_angle>{{ 2*pi }}</max_angle>
Expand Down Expand Up @@ -1902,7 +1919,7 @@ limitations under the License.
{%- endmacro -%}
<!--}-->

{%- macro ouster_macro(namespace, parent_link, sensor_name, ouster_model, rot_freq, noise, enable_gpu_ray, x, y, z, roll, pitch, yaw) -%}
{%- macro ouster_macro(namespace, parent_link, sensor_name, ouster_model, rot_freq, noise, enable_gpu_ray, horizontal_samples, x, y, z, roll, pitch, yaw) -%}

<!-- Outster type selection {-->
{# default: OS1-16 Generation 1 - is specified in the config file #}
Expand Down Expand Up @@ -1999,6 +2016,7 @@ limitations under the License.
max_range = range,
noise = noise,
enable_gpu_ray = enable_gpu_ray,
horizontal_samples = horizontal_samples,
x = x,
y = y,
z = z,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -857,6 +857,7 @@
{{ components.rplidar_macro(
namespace = namespace,
parent_link = root,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.1,
Expand All @@ -882,6 +883,7 @@
max_range = 100,
noise = 0.01,
enable_gpu_ray = use_gpu_ray,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.066,
Expand All @@ -904,6 +906,7 @@
rot_freq = 10,
noise = 0.03,
enable_gpu_ray = use_gpu_ray,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.066,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1006,6 +1006,7 @@
{{ components.rplidar_macro(
namespace = namespace,
parent_link = root,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.1,
Expand All @@ -1031,6 +1032,7 @@
max_range = 100,
noise = 0.01,
enable_gpu_ray = use_gpu_ray,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.066,
Expand All @@ -1053,6 +1055,7 @@
rot_freq = 10,
noise = 0.03,
enable_gpu_ray = use_gpu_ray,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.066,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -782,6 +782,7 @@
{{ components.rplidar_macro(
namespace = namespace,
parent_link = root,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.09,
Expand All @@ -804,6 +805,7 @@
rot_freq = 10,
noise = 0.03,
enable_gpu_ray = use_gpu_ray,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.0611,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -213,7 +213,7 @@
yaw = 0)
}}
<!--}-->

<!-- pixhawk {-->
{{ components.visual_mesh_macro(
name = "pixhawk",
Expand Down Expand Up @@ -392,7 +392,7 @@
}}
<!--}-->
{% endif %}

{% if enable_rplidar or fire_challenge_blanket %}
<!-- RPLidar mount {-->
{{ components.visual_mesh_macro(
Expand All @@ -409,7 +409,7 @@
}}
<!--}-->
{% endif %}

{% if enable_realsense_front %}
<!-- Realsense mount {-->
{{ components.visual_mesh_macro(
Expand All @@ -426,7 +426,7 @@
}}
<!--}-->
{% endif %}

{% if enable_ouster or enable_velodyne %}
<!-- Ouster mount {-->
{{ components.visual_mesh_macro(
Expand All @@ -443,7 +443,7 @@
}}
<!--}-->
{% endif %}

<!--}-->
</link>

Expand Down Expand Up @@ -760,6 +760,7 @@
{{ components.rplidar_macro(
namespace = namespace,
parent_link = root,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.107,
Expand All @@ -785,6 +786,7 @@
max_range = 100,
noise = 0.01,
enable_gpu_ray = use_gpu_ray,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.073,
Expand All @@ -807,6 +809,7 @@
rot_freq = 10,
noise = 0.03,
enable_gpu_ray = use_gpu_ray,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.073,
Expand All @@ -817,7 +820,7 @@
<!--}-->
{% endif %}
{# <!--}--> #}

<!-- ========================= camera sensors ========================= -->

<!-- Bluefox camera placements{-->
Expand Down Expand Up @@ -1269,10 +1272,10 @@
yaw=-2.5665787)
}}
<!--}-->

<!--}-->
{% endif %}

{% if fire_challenge_blanket %}
<!-- fire_challenge_blanket {-->

Expand All @@ -1289,7 +1292,7 @@
yaw = 0)
}}
<!--}-->

<!-- rplidar {-->
{{ components.rplidar_macro(
namespace = namespace,
Expand Down Expand Up @@ -1344,7 +1347,7 @@
yaw = 0)
}}
<!--}-->

<!--}-->
{% endif %}
{# <!--}--> #}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -832,6 +832,7 @@
{{ components.rplidar_macro(
namespace = namespace,
parent_link = root,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.136,
Expand All @@ -854,6 +855,7 @@
rot_freq = 10,
noise = 0.03,
enable_gpu_ray = use_gpu_ray,
horizontal_samples = horizontal_samples,
x = 0.0,
y = 0.0,
z = 0.107,
Expand Down

0 comments on commit 8d6b558

Please sign in to comment.