Skip to content

Commit

Permalink
temp
Browse files Browse the repository at this point in the history
  • Loading branch information
TomohitoAndo committed Sep 12, 2024
1 parent 11e0567 commit 604a372
Show file tree
Hide file tree
Showing 3 changed files with 44 additions and 17 deletions.
2 changes: 1 addition & 1 deletion aip_x2_gen2_launch/launch/imu.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<node pkg="tamagawa_imu_driver" name="tag_can_driver" exec="tag_can_driver" if="$(var launch_driver)">
<remap from="/can/imu" to="from_can_bus"/>
<remap from="imu/data_raw" to="imu_raw"/>
<param name="imu_frame_id" value="tamagawa/imu_link"/>
<param name="imu_frame_id" value="top_front_left/imu_link"/>
</node>
</group>

Expand Down
42 changes: 29 additions & 13 deletions aip_x2_gen2_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
<arg name="use_intra_process" value="true" />
<arg name="use_multithread" value="true" />
<arg name="use_pointcloud_container" value="true"/>
<arg name="pointcloud_container_name" value="pointcloud_container"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

<!-- LiDARs connected to Main ECU -->
Expand All @@ -44,7 +44,7 @@
<arg name="ptp_domain" value="0"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
Expand All @@ -55,7 +55,9 @@
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />

<!-- TODO: remove -->
<arg name="scan_phase" value="90.0"/>
</include>
</group>

Expand All @@ -78,7 +80,7 @@
<arg name="ptp_domain" value="0"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
Expand All @@ -89,7 +91,9 @@
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />

<!-- TODO: remove -->
<arg name="scan_phase" value="0.0"/>
</include>
</group>

Expand All @@ -112,7 +116,7 @@
<arg name="ptp_domain" value="0"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
Expand All @@ -123,7 +127,9 @@
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />

<!-- TODO: remove -->
<arg name="scan_phase" value="90.0"/>
</include>
</group>

Expand All @@ -146,7 +152,7 @@
<arg name="ptp_domain" value="0"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="container_name" value="pointcloud_container"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>

<arg name="distance_range" value="[0.5, 200.0]"/>
<arg name="blockage_range" value="[90.0, 270.0]"/>
Expand All @@ -157,7 +163,9 @@
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />

<!-- TODO: remove -->
<arg name="scan_phase" value="0.0"/>
</include>
</group>

Expand Down Expand Up @@ -192,7 +200,9 @@
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />

<!-- TODO: remove -->
<arg name="scan_phase" value="270.0"/>
</include>
</group>

Expand Down Expand Up @@ -226,7 +236,9 @@
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />

<!-- TODO: remove -->
<arg name="scan_phase" value="180.0"/>
</include>
</group>

Expand Down Expand Up @@ -260,7 +272,9 @@
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />

<!-- TODO: remove -->
<arg name="scan_phase" value="270.0"/>
</include>
</group>

Expand Down Expand Up @@ -294,7 +308,9 @@
<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="dual_return_filter_param_file" value="$(var dual_return_filter_param_file)" />
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)" />

<!-- TODO: remove -->
<arg name="scan_phase" value="180.0"/>
</include>
</group>

Expand Down
17 changes: 14 additions & 3 deletions aip_x2_gen2_launch/launch/nebula_node_container.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch_ros.substitutions import FindPackageShare
import yaml


Expand Down Expand Up @@ -131,6 +132,7 @@ def str2vector(string):
"ptp_switch_type",
"ptp_domain",
"diag_span",
"scan_phase" # TODO: remove
),
"launch_hw": True,
"retry_hw": True,
Expand Down Expand Up @@ -218,10 +220,10 @@ def str2vector(string):
remappings=[
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
("~/input/imu", "/sensing/imu/imu_data"),
("~/input/velocity_report", "/vehicle/status/velocity_status"),
("~/input/pointcloud", "mirror_cropped/pointcloud_ex"),
("~/output/pointcloud", "pointcloud"),
],
parameters=[load_composable_node_param("distortion_corrector_node_param_file")],
extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}],
)

Expand Down Expand Up @@ -364,8 +366,14 @@ def add_launch_arg(name: str, default_value=None, description=None):
add_launch_arg("container_name", "nebula_node_container")

add_launch_arg("dual_return_filter_param_file")
add_launch_arg("blockage_diagnostics_param_file")

add_launch_arg(
"blockage_diagnostics_param_file",
[FindPackageShare("common_sensor_launch"), "/config/blockage_diagnostics.param.yaml"],
)
add_launch_arg(
"distortion_corrector_node_param_file",
[FindPackageShare("common_sensor_launch"), "/config/distortion_corrector_node.param.yaml"],
)
add_launch_arg("vertical_bins", "128")
add_launch_arg("horizontal_ring_id", "12")
add_launch_arg("blockage_range", "[270.0, 90.0]")
Expand All @@ -374,6 +382,9 @@ 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")

# TODO: remove
add_launch_arg("scan_phase", "0.0")

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

0 comments on commit 604a372

Please sign in to comment.