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

feat(tier4_control_launch): declare param path argument #1432

Merged
merged 1 commit into from
Jul 26, 2022
Merged
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
75 changes: 35 additions & 40 deletions launch/tier4_control_launch/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os

import launch
from launch.actions import DeclareLaunchArgument
from launch.actions import GroupAction
Expand All @@ -33,26 +35,42 @@ def launch_setup(context, *args, **kwargs):
vehicle_info_param_path = LaunchConfiguration("vehicle_info_param_file").perform(context)
with open(vehicle_info_param_path, "r") as f:
vehicle_info_param = yaml.safe_load(f)["/**"]["ros__parameters"]
lat_controller_param_path = LaunchConfiguration("lat_controller_param_path").perform(context)

lat_controller_param_path = os.path.join(
LaunchConfiguration("tier4_control_launch_param_path").perform(context),
"trajectory_follower",
"lateral_controller.param.yaml",
)
with open(lat_controller_param_path, "r") as f:
lat_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"]
lon_controller_param_path = LaunchConfiguration("lon_controller_param_path").perform(context)

lon_controller_param_path = os.path.join(
LaunchConfiguration("tier4_control_launch_param_path").perform(context),
"trajectory_follower",
"longitudinal_controller.param.yaml",
)
with open(lon_controller_param_path, "r") as f:
lon_controller_param = yaml.safe_load(f)["/**"]["ros__parameters"]
vehicle_cmd_gate_param_path = LaunchConfiguration("vehicle_cmd_gate_param_path").perform(
context

vehicle_cmd_gate_param_path = os.path.join(
LaunchConfiguration("tier4_control_launch_param_path").perform(context),
"vehicle_cmd_gate",
"vehicle_cmd_gate.param.yaml",
)
with open(vehicle_cmd_gate_param_path, "r") as f:
vehicle_cmd_gate_param = yaml.safe_load(f)["/**"]["ros__parameters"]

lane_departure_checker_param_path = LaunchConfiguration(
"lane_departure_checker_param_path"
).perform(context)
with open(lane_departure_checker_param_path, "r") as f:
lane_departure_checker_param = yaml.safe_load(f)["/**"]["ros__parameters"]

operation_mode_transition_manager_param_path = LaunchConfiguration(
"operation_mode_transition_manager_param_path"
).perform(context)
operation_mode_transition_manager_param_path = os.path.join(
LaunchConfiguration("tier4_control_launch_param_path").perform(context),
"operation_mode_transition_manager",
"operation_mode_transition_manager.param.yaml",
)
with open(operation_mode_transition_manager_param_path, "r") as f:
operation_mode_transition_manager_param = yaml.safe_load(f)["/**"]["ros__parameters"]

Expand Down Expand Up @@ -247,8 +265,17 @@ def add_launch_arg(name: str, default_value=None, description=None):
DeclareLaunchArgument(name, default_value=default_value, description=description)
)

# lateral controller
# parameter
add_launch_arg(
"tier4_control_launch_param_path",
[
FindPackageShare("tier4_control_launch"),
"/config",
],
"tier4_control_launch parameter path",
)

# lateral controller
add_launch_arg(
"lateral_controller_mode",
"mpc_follower",
Expand All @@ -264,42 +291,10 @@ def add_launch_arg(name: str, default_value=None, description=None):
"path to the parameter file of vehicle information",
)

add_launch_arg(
"lat_controller_param_path",
[
FindPackageShare("tier4_control_launch"),
"/config/trajectory_follower/lateral_controller.param.yaml",
],
"path to the parameter file of lateral controller",
)
add_launch_arg(
"lon_controller_param_path",
[
FindPackageShare("tier4_control_launch"),
"/config/trajectory_follower/longitudinal_controller.param.yaml",
],
"path to the parameter file of longitudinal controller",
)
add_launch_arg(
"vehicle_cmd_gate_param_path",
[
FindPackageShare("tier4_control_launch"),
"/config/vehicle_cmd_gate/vehicle_cmd_gate.param.yaml",
],
"path to the parameter file of vehicle_cmd_gate",
)
add_launch_arg(
"lane_departure_checker_param_path",
[FindPackageShare("lane_departure_checker"), "/config/lane_departure_checker.param.yaml"],
)
add_launch_arg(
"operation_mode_transition_manager_param_path",
[
FindPackageShare("tier4_control_launch"),
"/config/operation_mode_transition_manager/operation_mode_transition_manager.param.yaml",
],
"path to the parameter file of vehicle_cmd_gate",
)

# velocity controller
add_launch_arg("show_debug_info", "false", "show debug information")
Expand Down