diff --git a/aip_x1_launch/launch/velodyne_node_container.launch.py b/aip_x1_launch/launch/velodyne_node_container.launch.py index 5e6fea0e..eaca0fbb 100644 --- a/aip_x1_launch/launch/velodyne_node_container.launch.py +++ b/aip_x1_launch/launch/velodyne_node_container.launch.py @@ -25,7 +25,11 @@ def get_vehicle_info(context): + # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support + # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py gp = context.launch_configurations.get("ros_params", {}) + if not gp: + gp = context.launch_configurations.get("global_params", {}) p = {} p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] diff --git a/aip_x2_launch/launch/pandar_node_container.launch.py b/aip_x2_launch/launch/pandar_node_container.launch.py index 7f2139bd..8e5a137a 100644 --- a/aip_x2_launch/launch/pandar_node_container.launch.py +++ b/aip_x2_launch/launch/pandar_node_container.launch.py @@ -35,7 +35,11 @@ def get_dual_return_filter_info(context): def get_vehicle_info(context): + # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support + # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py gp = context.launch_configurations.get("ros_params", {}) + if not gp: + gp = context.launch_configurations.get("global_params", {}) p = {} p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] diff --git a/common_sensor_launch/launch/livox_horizon.launch.py b/common_sensor_launch/launch/livox_horizon.launch.py index 62a64635..d550282b 100644 --- a/common_sensor_launch/launch/livox_horizon.launch.py +++ b/common_sensor_launch/launch/livox_horizon.launch.py @@ -27,7 +27,11 @@ def get_vehicle_info(context): + # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support + # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py gp = context.launch_configurations.get("ros_params", {}) + if not gp: + gp = context.launch_configurations.get("global_params", {}) p = {} p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"] diff --git a/common_sensor_launch/launch/velodyne_node_container.launch.py b/common_sensor_launch/launch/velodyne_node_container.launch.py index 06331da6..1c993bda 100644 --- a/common_sensor_launch/launch/velodyne_node_container.launch.py +++ b/common_sensor_launch/launch/velodyne_node_container.launch.py @@ -26,7 +26,11 @@ def get_vehicle_info(context): + # TODO(TIER IV): Use Parameter Substitution after we drop Galactic support + # https://github.com/ros2/launch_ros/blob/master/launch_ros/launch_ros/substitutions/parameter.py gp = context.launch_configurations.get("ros_params", {}) + if not gp: + gp = context.launch_configurations.get("global_params", {}) p = {} p["vehicle_length"] = gp["front_overhang"] + gp["wheel_base"] + gp["rear_overhang"] p["vehicle_width"] = gp["wheel_tread"] + gp["left_overhang"] + gp["right_overhang"]