diff --git a/kuka_iiqka_eac_driver/config/joint_trajectory_controller_config.yaml b/kuka_iiqka_eac_driver/config/joint_trajectory_controller_config.yaml index 0fb9c446..f164cb1e 100644 --- a/kuka_iiqka_eac_driver/config/joint_trajectory_controller_config.yaml +++ b/kuka_iiqka_eac_driver/config/joint_trajectory_controller_config.yaml @@ -12,5 +12,6 @@ joint_trajectory_controller: - position state_interfaces: - position - state_publish_rate: 250.0 + state_publish_rate: 50.0 action_monitor_rate: 20.0 + allow_nonzero_velocity_at_trajectory_end: True diff --git a/kuka_iiqka_eac_driver/launch/startup.launch.py b/kuka_iiqka_eac_driver/launch/startup.launch.py index 35cf85ff..e65f0fbf 100644 --- a/kuka_iiqka_eac_driver/launch/startup.launch.py +++ b/kuka_iiqka_eac_driver/launch/startup.launch.py @@ -34,7 +34,7 @@ def launch_setup(context, *args, **kwargs): "urdf", robot_model.perform(context) + ".urdf.xacro"] ), " ", - ] + ], on_stderr='capture' ) # Get URDF via xacro diff --git a/kuka_kss_rsi_driver/config/joint_trajectory_controller_config.yaml b/kuka_kss_rsi_driver/config/joint_trajectory_controller_config.yaml index 85b8feaa..2d4cece3 100644 --- a/kuka_kss_rsi_driver/config/joint_trajectory_controller_config.yaml +++ b/kuka_kss_rsi_driver/config/joint_trajectory_controller_config.yaml @@ -14,3 +14,5 @@ joint_trajectory_controller: - position state_publish_rate: 50.0 action_monitor_rate: 20.0 + allow_nonzero_velocity_at_trajectory_end: True + diff --git a/kuka_kss_rsi_driver/launch/startup.launch.py b/kuka_kss_rsi_driver/launch/startup.launch.py index 736cbbd9..25455a79 100644 --- a/kuka_kss_rsi_driver/launch/startup.launch.py +++ b/kuka_kss_rsi_driver/launch/startup.launch.py @@ -24,32 +24,22 @@ def launch_setup(context, *args, **kwargs): robot_model = LaunchConfiguration('robot_model') + robot_family = LaunchConfiguration('robot_family') use_fake_hardware = LaunchConfiguration('use_fake_hardware') - # TODO(Svastits):better way to handle supported robot models and families - if robot_model.perform(context) in ["kr6_r700_sixx", "kr6_r900_sixx"]: - robot_family = "agilus" - elif robot_model.perform(context) in ["kr16_r2010_2"]: - robot_family = "cybertech" - elif robot_model.perform(context) in ["kr210_r2700_2", "kr210_r3100_2"]: - robot_family = "quantec" - else: - print("[ERROR] [launch]: robot model not recognized") - raise Exception - # Get URDF via xacro robot_description_content = Command( [ PathJoinSubstitution([FindExecutable(name="xacro")]), " ", PathJoinSubstitution( - [FindPackageShare('kuka_{}_support'.format(robot_family)), + [FindPackageShare('kuka_{}_support'.format(robot_family.perform(context))), "urdf", robot_model.perform(context) + ".urdf.xacro"] ), " ", "use_fake_hardware:=", use_fake_hardware, - ] + ], on_stderr='capture' ) robot_description = {'robot_description': robot_description_content} @@ -116,6 +106,10 @@ def generate_launch_description(): 'robot_model', default_value='kr6_r700_sixx' )) + launch_arguments.append(DeclareLaunchArgument( + 'robot_family', + default_value='agilus' + )) launch_arguments.append(DeclareLaunchArgument( 'use_fake_hardware', default_value="false" diff --git a/kuka_sunrise_fri_driver/config/joint_trajectory_controller_config.yaml b/kuka_sunrise_fri_driver/config/joint_trajectory_controller_config.yaml index 62619923..55e008d5 100644 --- a/kuka_sunrise_fri_driver/config/joint_trajectory_controller_config.yaml +++ b/kuka_sunrise_fri_driver/config/joint_trajectory_controller_config.yaml @@ -13,5 +13,7 @@ joint_trajectory_controller: - position state_interfaces: - position - state_publish_rate: 100.0 + state_publish_rate: 50.0 action_monitor_rate: 20.0 + allow_nonzero_velocity_at_trajectory_end: True + diff --git a/kuka_sunrise_fri_driver/launch/startup.launch.py b/kuka_sunrise_fri_driver/launch/startup.launch.py index 5ecc763b..46673079 100644 --- a/kuka_sunrise_fri_driver/launch/startup.launch.py +++ b/kuka_sunrise_fri_driver/launch/startup.launch.py @@ -34,7 +34,7 @@ def launch_setup(context, *args, **kwargs): "urdf", robot_model.perform(context) + ".urdf.xacro"] ), " ", - ] + ], on_stderr='capture' ) # Get URDF via xacro