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

Add calibration file to launch arguments #1001

Merged
merged 4 commits into from
May 22, 2024
Merged
Show file tree
Hide file tree
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
20 changes: 16 additions & 4 deletions ur_bringup/launch/ur_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ def launch_setup(context, *args, **kwargs):
controllers_file = LaunchConfiguration("controllers_file")
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
kinematics_params_file = LaunchConfiguration("kinematics_params_file")
tf_prefix = LaunchConfiguration("tf_prefix")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
fake_sensor_commands = LaunchConfiguration("fake_sensor_commands")
Expand All @@ -72,9 +73,6 @@ def launch_setup(context, *args, **kwargs):
joint_limit_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"]
)
kinematics_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "default_kinematics.yaml"]
)
physical_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "physical_parameters.yaml"]
)
Expand Down Expand Up @@ -104,7 +102,7 @@ def launch_setup(context, *args, **kwargs):
joint_limit_params,
" ",
"kinematics_params:=",
kinematics_params,
kinematics_params_file,
" ",
"physical_params:=",
physical_params,
Expand Down Expand Up @@ -418,6 +416,20 @@ def generate_launch_description():
description="URDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"kinematics_params_file",
default_value=PathJoinSubstitution(
[
FindPackageShare(LaunchConfiguration("description_package")),
"config",
LaunchConfiguration("ur_type"),
"default_kinematics.yaml",
]
),
description="The calibration configuration of the actual robot used.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tf_prefix",
Expand Down
20 changes: 16 additions & 4 deletions ur_robot_driver/launch/ur_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ def launch_setup(context, *args, **kwargs):
controllers_file = LaunchConfiguration("controllers_file")
description_package = LaunchConfiguration("description_package")
description_file = LaunchConfiguration("description_file")
kinematics_params_file = LaunchConfiguration("kinematics_params_file")
tf_prefix = LaunchConfiguration("tf_prefix")
use_fake_hardware = LaunchConfiguration("use_fake_hardware")
fake_sensor_commands = LaunchConfiguration("fake_sensor_commands")
Expand Down Expand Up @@ -78,9 +79,6 @@ def launch_setup(context, *args, **kwargs):
joint_limit_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "joint_limits.yaml"]
)
kinematics_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "default_kinematics.yaml"]
)
physical_params = PathJoinSubstitution(
[FindPackageShare(description_package), "config", ur_type, "physical_parameters.yaml"]
)
Expand Down Expand Up @@ -110,7 +108,7 @@ def launch_setup(context, *args, **kwargs):
joint_limit_params,
" ",
"kinematics_params:=",
kinematics_params,
kinematics_params_file,
" ",
"physical_params:=",
physical_params,
Expand Down Expand Up @@ -445,6 +443,20 @@ def generate_launch_description():
description="URDF/XACRO description file with the robot.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"kinematics_params_file",
default_value=PathJoinSubstitution(
[
FindPackageShare(LaunchConfiguration("description_package")),
"config",
LaunchConfiguration("ur_type"),
"default_kinematics.yaml",
]
),
description="The calibration configuration of the actual robot used.",
)
)
declared_arguments.append(
DeclareLaunchArgument(
"tf_prefix",
Expand Down
Loading