Skip to content

Commit

Permalink
Merge branch 'beta/x2_gen2/v0.29.0' into fix/sync-angle-cut-angle
Browse files Browse the repository at this point in the history
  • Loading branch information
TomohitoAndo authored Oct 5, 2024
2 parents 7885ec7 + efb3773 commit 2fadc5a
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 32 deletions.
6 changes: 3 additions & 3 deletions aip_x2_gen2_launch/launch/hesai_OT128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,13 +26,13 @@
<arg name="is_channel_order_top2down" default="true"/>
<arg name="horizontal_resolution" default="0.4"/>
<arg name="enable_blockage_diag" default="$(var enable_blockage_diag)"/>
<arg name="calibration" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="dual_return_filter_param_file" default="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" default="$(var vehicle_mirror_param_file)" />
<arg name="blockage_diagnostics_param_file" default="$(find-pkg-share aip_x2_gen2_launch)/config/blockage_diagnostics_param_file.yaml" />

<include file="$(find-pkg-share aip_x2_gen2_launch)/launch/nebula_node_container.launch.py">
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="launch_hw" value="$(var launch_driver)"/>
<arg name="sensor_model" value="$(var model)"/>
<arg name="return_mode" value="$(var return_mode)"/>
<arg name="frame_id" value="$(var sensor_frame)"/>
Expand Down Expand Up @@ -61,7 +61,7 @@
<arg name="is_channel_order_top2down" value="$(var is_channel_order_top2down)"/>
<arg name="horizontal_resolution" value="$(var horizontal_resolution)"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(var calibration)"/>
<arg name="calibration_file" value="$(var calibration_file)"/>
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)"/>
<arg name="blockage_diagnostics_param_file" value="$(var blockage_diagnostics_param_file)"/>

Expand Down
6 changes: 3 additions & 3 deletions aip_x2_gen2_launch/launch/hesai_QT128.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,13 @@
<arg name="is_channel_order_top2down" default="true"/>
<arg name="horizontal_resolution" default="0.4"/>
<arg name="enable_blockage_diag" default="$(var enable_blockage_diag)"/>
<arg name="calibration" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" default="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="dual_return_filter_param_file" default="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" default="$(var vehicle_mirror_param_file)" />
<arg name="blockage_diagnostics_param_file" default="$(find-pkg-share aip_x2_gen2_launch)/config/blockage_diagnostics_param_file.yaml" />

<include file="$(find-pkg-share aip_x2_gen2_launch)/launch/nebula_node_container.launch.py">
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="launch_hw" value="$(var launch_driver)"/>
<arg name="sensor_model" value="$(var model)"/>
<arg name="return_mode" value="$(var return_mode)"/>
<arg name="frame_id" value="$(var sensor_frame)"/>
Expand Down Expand Up @@ -61,7 +61,7 @@
<arg name="is_channel_order_top2down" value="$(var is_channel_order_top2down)"/>
<arg name="horizontal_resolution" value="$(var horizontal_resolution)"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(var calibration)"/>
<arg name="calibration_file" value="$(var calibration_file)"/>
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)"/>
<arg name="blockage_diagnostics_param_file" value="$(var blockage_diagnostics_param_file)"/>
</include>
Expand Down
16 changes: 8 additions & 8 deletions aip_x2_gen2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/rear_upper.csv" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
</include>
</group>
Expand Down Expand Up @@ -86,7 +86,7 @@
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/left_upper.csv" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
</include>
</group>
Expand Down Expand Up @@ -119,7 +119,7 @@
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/rear_lower.csv" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
</include>
</group>
Expand Down Expand Up @@ -152,7 +152,7 @@
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/left_lower.csv" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
</include>
</group>
Expand Down Expand Up @@ -186,7 +186,7 @@
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_upper.csv" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
</include>
</group>
Expand Down Expand Up @@ -219,7 +219,7 @@
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/right_upper.csv" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
</include>
</group>
Expand Down Expand Up @@ -252,7 +252,7 @@
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
</include>
</group>
Expand Down Expand Up @@ -285,7 +285,7 @@
<arg name="is_channel_order_top2down" value="true"/>
<arg name="horizontal_resolution" value="0.4"/>
<arg name="enable_blockage_diag" value="$(var enable_blockage_diag)"/>
<arg name="calibration" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/front_lower.csv" />
<arg name="calibration_file" value="$(find-pkg-share individual_params)/config/$(var vehicle_id)/aip_x2_gen2/pandar/right_lower.csv" />
<arg name="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
</include>
</group>
Expand Down
23 changes: 5 additions & 18 deletions aip_x2_gen2_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,6 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os

from ament_index_python.packages import get_package_share_directory
import launch
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
Expand Down Expand Up @@ -83,18 +80,6 @@ def str2vector(string):
# Model and make
sensor_model = LaunchConfiguration("sensor_model").perform(context)
sensor_make, sensor_extension = get_lidar_make(sensor_model)
nebula_decoders_share_dir = get_package_share_directory("nebula_decoders")

# Calibration file
sensor_calib_fp = os.path.join(
nebula_decoders_share_dir,
"calibration",
sensor_make.lower(),
sensor_model + sensor_extension,
)
assert os.path.exists(
sensor_calib_fp
), "Sensor calib file under calibration/ was not found: {}".format(sensor_calib_fp)

glog_component = ComposableNode(
package="glog_component",
Expand All @@ -108,7 +93,6 @@ def str2vector(string):
name=sensor_make.lower() + "_ros_wrapper_node",
parameters=[
{
"calibration_file": sensor_calib_fp,
"sensor_model": sensor_model,
"point_filters": "{}",
**create_parameter_dict(
Expand All @@ -134,8 +118,9 @@ def str2vector(string):
"ptp_switch_type",
"ptp_domain",
"diag_span",
"calibration_file",
"launch_hw",
),
"launch_hw": True,
"retry_hw": True,
},
],
Expand Down Expand Up @@ -333,7 +318,7 @@ def add_launch_arg(name: str, default_value=None, description=None):

add_launch_arg("sensor_model", description="sensor model name")
add_launch_arg("config_file", "", description="sensor configuration file")
add_launch_arg("launch_driver", "True", "do launch driver")
add_launch_arg("launch_hw", "True", "do launch driver")
add_launch_arg("setup_sensor", "True", "configure sensor")
add_launch_arg("sensor_ip", "192.168.1.201", "device ip address")
add_launch_arg(
Expand Down Expand Up @@ -383,6 +368,8 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("max_azimuth_deg", "225.0")
add_launch_arg("enable_blockage_diag", "true")

add_launch_arg("calibration_file", "")

set_container_executable = SetLaunchConfiguration(
"container_executable",
"component_container",
Expand Down

0 comments on commit 2fadc5a

Please sign in to comment.