@@ -51,6 +51,7 @@ def launch_setup(context, *args, **kwargs):
5151 controllers_file = LaunchConfiguration ("controllers_file" )
5252 description_package = LaunchConfiguration ("description_package" )
5353 description_file = LaunchConfiguration ("description_file" )
54+ kinematics_params_file = LaunchConfiguration ("kinematics_params_file" )
5455 tf_prefix = LaunchConfiguration ("tf_prefix" )
5556 use_fake_hardware = LaunchConfiguration ("use_fake_hardware" )
5657 fake_sensor_commands = LaunchConfiguration ("fake_sensor_commands" )
@@ -72,9 +73,6 @@ def launch_setup(context, *args, **kwargs):
7273 joint_limit_params = PathJoinSubstitution (
7374 [FindPackageShare (description_package ), "config" , ur_type , "joint_limits.yaml" ]
7475 )
75- kinematics_params = PathJoinSubstitution (
76- [FindPackageShare (description_package ), "config" , ur_type , "default_kinematics.yaml" ]
77- )
7876 physical_params = PathJoinSubstitution (
7977 [FindPackageShare (description_package ), "config" , ur_type , "physical_parameters.yaml" ]
8078 )
@@ -104,7 +102,7 @@ def launch_setup(context, *args, **kwargs):
104102 joint_limit_params ,
105103 " " ,
106104 "kinematics_params:=" ,
107- kinematics_params ,
105+ kinematics_params_file ,
108106 " " ,
109107 "physical_params:=" ,
110108 physical_params ,
@@ -418,6 +416,20 @@ def generate_launch_description():
418416 description = "URDF/XACRO description file with the robot." ,
419417 )
420418 )
419+ declared_arguments .append (
420+ DeclareLaunchArgument (
421+ "kinematics_params_file" ,
422+ default_value = PathJoinSubstitution (
423+ [
424+ FindPackageShare (LaunchConfiguration ("description_package" )),
425+ "config" ,
426+ LaunchConfiguration ("ur_type" ),
427+ "default_kinematics.yaml" ,
428+ ]
429+ ),
430+ description = "The calibration configuration of the actual robot used." ,
431+ )
432+ )
421433 declared_arguments .append (
422434 DeclareLaunchArgument (
423435 "tf_prefix" ,
0 commit comments