@@ -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" )
@@ -78,9 +79,6 @@ def launch_setup(context, *args, **kwargs):
7879 joint_limit_params = PathJoinSubstitution (
7980 [FindPackageShare (description_package ), "config" , ur_type , "joint_limits.yaml" ]
8081 )
81- kinematics_params = PathJoinSubstitution (
82- [FindPackageShare (description_package ), "config" , ur_type , "default_kinematics.yaml" ]
83- )
8482 physical_params = PathJoinSubstitution (
8583 [FindPackageShare (description_package ), "config" , ur_type , "physical_parameters.yaml" ]
8684 )
@@ -110,7 +108,7 @@ def launch_setup(context, *args, **kwargs):
110108 joint_limit_params ,
111109 " " ,
112110 "kinematics_params:=" ,
113- kinematics_params ,
111+ kinematics_params_file ,
114112 " " ,
115113 "physical_params:=" ,
116114 physical_params ,
@@ -445,6 +443,20 @@ def generate_launch_description():
445443 description = "URDF/XACRO description file with the robot." ,
446444 )
447445 )
446+ declared_arguments .append (
447+ DeclareLaunchArgument (
448+ "kinematics_params_file" ,
449+ default_value = PathJoinSubstitution (
450+ [
451+ FindPackageShare (LaunchConfiguration ("description_package" )),
452+ "config" ,
453+ LaunchConfiguration ("ur_type" ),
454+ "default_kinematics.yaml" ,
455+ ]
456+ ),
457+ description = "The calibration configuration of the actual robot used." ,
458+ )
459+ )
448460 declared_arguments .append (
449461 DeclareLaunchArgument (
450462 "tf_prefix" ,
0 commit comments