diff --git a/README.md b/README.md index e56dd4d..5d00b3a 100644 --- a/README.md +++ b/README.md @@ -2,9 +2,10 @@ This repository contains support packages that can be used with real KUKA robots as well as with simulations. -Github CI ------------- -[![Build Status](https://github.com/kroshu/kuka_robot_descriptions/workflows/CI/badge.svg?branch=main)](https://github.com/kroshu/kuka_robot_descriptions/actions) +ROS2 Distro | Branch | Github CI +------------ | -------------- | -------------- +**Jazzy** | [`master`](https://github.com/kroshu/kuka_robot_descriptions/tree/master) | [![Build Status](https://github.com/kroshu/kuka_robot_descriptions/actions/workflows/industrial_ci.yml/badge.svg?branch=master)](https://github.com/kroshu/kuka_robot_descriptions/actions) +**Humble** | [`humble`](https://github.com/kroshu/kuka_robot_descriptions/tree/humble) | [![Build Status](https://github.com/kroshu/kuka_robot_descriptions/actions/workflows/industrial_ci.yml/badge.svg?branch=humble)](https://github.com/kroshu/kuka_robot_descriptions/actions) ## What is included? @@ -67,8 +68,7 @@ Collision meshes are provided for the robots to speed up collision avoidance and ### Joint limit configurations -The support packages contain a joint limits file for every supported robot model, necessary time parametrization of MoveIt-planned paths. They contain the velocity limits also available in the URDF model and additional acceleration limits. Acceleration limits can never be global, these values are calculated from the worst-case ramp-up time to reach maximum velocity. The easiest way to modify the allowed velocities and accelerations is to change the velocity and acceleration scaling factors also available in the same configuration files. (The scaling factor can never be smaller than 1.) - +The support packages contain a joint limits file for every supported robot model, necessary time parametrization of MoveIt-planned paths. They contain the velocity limits also available in the URDF model and additional acceleration limits. Acceleration limits can never be global, these values are calculated from the worst-case ramp-up time to reach maximum velocity. The easiest way to modify the allowed velocities and accelerations is to change the velocity and acceleration scaling factors also available in the same configuration files. (The scaling factor can never be greater than 1.) ### Extending the models diff --git a/kuka_agilus_support/config/kr10_r1100_2_joint_limits.yaml b/kuka_agilus_support/config/kr10_r1100_2_joint_limits.yaml index 0b2ab1d..3493474 100644 --- a/kuka_agilus_support/config/kr10_r1100_2_joint_limits.yaml +++ b/kuka_agilus_support/config/kr10_r1100_2_joint_limits.yaml @@ -9,30 +9,36 @@ joint_limits: joint_1: has_velocity_limits: true max_velocity: 5.23599 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 10.06528 has_jerk: false joint_2: has_velocity_limits: true max_velocity: 3.926991 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.72508 has_jerk: false joint_3: has_velocity_limits: true max_velocity: 5.75959 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 2.68644 has_jerk: false joint_4: has_velocity_limits: true max_velocity: 6.28319 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 56.49428 has_jerk: false joint_5: has_velocity_limits: true max_velocity: 6.28319 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 49.23361 has_jerk: false joint_6: has_velocity_limits: true max_velocity: 7.55728 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 125.45374 has_jerk: false diff --git a/kuka_agilus_support/config/kr6_r700_sixx_joint_limits.yaml b/kuka_agilus_support/config/kr6_r700_sixx_joint_limits.yaml index 64f30ee..2b4228c 100644 --- a/kuka_agilus_support/config/kr6_r700_sixx_joint_limits.yaml +++ b/kuka_agilus_support/config/kr6_r700_sixx_joint_limits.yaml @@ -9,30 +9,36 @@ joint_limits: joint_1: has_velocity_limits: true max_velocity: 6.283185 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 41.672910 has_jerk: false joint_2: has_velocity_limits: true max_velocity: 5.23599 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 21.620884 has_jerk: false joint_3: has_velocity_limits: true max_velocity: 6.283185 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 46.224233 has_jerk: false joint_4: has_velocity_limits: true max_velocity: 6.64970 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 145.820923 has_jerk: false joint_5: has_velocity_limits: true max_velocity: 6.77188 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 152.326213 has_jerk: false joint_6: has_velocity_limits: true max_velocity: 10.73377 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 292.626544 has_jerk: false diff --git a/kuka_agilus_support/config/kr6_r900_sixx_joint_limits.yaml b/kuka_agilus_support/config/kr6_r900_sixx_joint_limits.yaml index 64f30ee..1850669 100644 --- a/kuka_agilus_support/config/kr6_r900_sixx_joint_limits.yaml +++ b/kuka_agilus_support/config/kr6_r900_sixx_joint_limits.yaml @@ -9,30 +9,36 @@ joint_limits: joint_1: has_velocity_limits: true max_velocity: 6.283185 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 21.666156 has_jerk: false joint_2: has_velocity_limits: true max_velocity: 5.23599 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 6.889457 has_jerk: false joint_3: has_velocity_limits: true max_velocity: 6.283185 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 31.415926 has_jerk: false joint_4: has_velocity_limits: true max_velocity: 6.64970 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 133.055688 has_jerk: false joint_5: has_velocity_limits: true max_velocity: 6.77188 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 135.557707 has_jerk: false joint_6: has_velocity_limits: true max_velocity: 10.73377 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 268.382564 has_jerk: false diff --git a/kuka_cybertech_support/config/kr16_r2010_2_joint_limits.yaml b/kuka_cybertech_support/config/kr16_r2010_2_joint_limits.yaml index 525daa4..b5b3ddf 100644 --- a/kuka_cybertech_support/config/kr16_r2010_2_joint_limits.yaml +++ b/kuka_cybertech_support/config/kr16_r2010_2_joint_limits.yaml @@ -12,30 +12,36 @@ joint_limits: joint_1: has_velocity_limits: true max_velocity: 3.490656 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 7.505672 has_jerk: false joint_2: has_velocity_limits: true - max_velocity: 3.05432 - has_acceleration_limits: false + max_velocity: 2.994851 + has_acceleration_limits: true + max_acceleration: 1.350277 has_jerk: false joint_3: has_velocity_limits: true max_velocity: 3.31613 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 13.412379 has_jerk: false joint_4: has_velocity_limits: true max_velocity: 7.50492 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 99.514484 has_jerk: false joint_5: has_velocity_limits: true max_velocity: 7.50492 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 95.957307 has_jerk: false joint_6: has_velocity_limits: true max_velocity: 10.99557 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 120.049850 has_jerk: false diff --git a/kuka_fortec_support/config/kr560_r3100_2_joint_limits.yaml b/kuka_fortec_support/config/kr560_r3100_2_joint_limits.yaml index dd42cc3..7a05d88 100644 --- a/kuka_fortec_support/config/kr560_r3100_2_joint_limits.yaml +++ b/kuka_fortec_support/config/kr560_r3100_2_joint_limits.yaml @@ -12,30 +12,36 @@ joint_limits: joint_1: has_velocity_limits: true max_velocity: 1.5708 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.1500 has_jerk: false joint_2: has_velocity_limits: true max_velocity: 1.3962 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 0.9308 has_jerk: false joint_3: has_velocity_limits: true max_velocity: 1.3090 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.5038 has_jerk: false joint_4: has_velocity_limits: true max_velocity: 1.5708 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.5816 has_jerk: false joint_5: has_velocity_limits: true max_velocity: 1.5708 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.6486 has_jerk: false joint_6: has_velocity_limits: true max_velocity: 2.2689 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 2.1579 has_jerk: false diff --git a/kuka_iontec_support/config/kr70_r2100_joint_limits.yaml b/kuka_iontec_support/config/kr70_r2100_joint_limits.yaml index 3b4d247..b290680 100644 --- a/kuka_iontec_support/config/kr70_r2100_joint_limits.yaml +++ b/kuka_iontec_support/config/kr70_r2100_joint_limits.yaml @@ -12,30 +12,36 @@ joint_limits: joint_1: has_velocity_limits: true max_velocity: 3.1416 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 6.1985 has_jerk: false joint_2: has_velocity_limits: true max_velocity: 2.7576 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.2580 has_jerk: false joint_3: has_velocity_limits: true max_velocity: 2.7925 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.4709 has_jerk: false joint_4: has_velocity_limits: true max_velocity: 4.01426 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 17.6323 has_jerk: false joint_5: has_velocity_limits: true max_velocity: 4.01426 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 14.9965 has_jerk: false joint_6: has_velocity_limits: true max_velocity: 5.58505 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 16.8623 has_jerk: false diff --git a/kuka_lbr_iisy_moveit_config/config/chomp_planning.yaml b/kuka_lbr_iisy_moveit_config/config/chomp_planning.yaml index 2d9fdb8..9dba26e 100644 --- a/kuka_lbr_iisy_moveit_config/config/chomp_planning.yaml +++ b/kuka_lbr_iisy_moveit_config/config/chomp_planning.yaml @@ -1,10 +1,14 @@ -planning_plugin: chomp_interface/CHOMPPlanner -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - chomp_interface/CHOMPPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath start_state_max_bounds_error: 0.1 planning_time_limit: 10.0 max_iterations: 200 diff --git a/kuka_lbr_iisy_moveit_config/config/ompl_planning.yaml b/kuka_lbr_iisy_moveit_config/config/ompl_planning.yaml index 85aa81b..db6bbea 100644 --- a/kuka_lbr_iisy_moveit_config/config/ompl_planning.yaml +++ b/kuka_lbr_iisy_moveit_config/config/ompl_planning.yaml @@ -1,13 +1,16 @@ -planning_plugin: ompl_interface/OMPLPlanner -# To optionally use Ruckig for jerk-limited smoothing, add this line to the request adapters below -# default_planner_request_adapters/AddRuckigTrajectorySmoothing -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/ResolveConstraintFrames - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - ompl_interface/OMPLPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +# To optionally use Ruckig for jerk-limited smoothing, add this line to the response adapters below +# default_planning_response_adapters/AddRuckigTrajectorySmoothing +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath start_state_max_bounds_error: 0.1 planner_configs: APSConfigDefault: @@ -16,7 +19,16 @@ planner_configs: hybridize: 1 # Compute hybrid solution trajectories max_hybrid_paths: 36 # Number of hybrid paths generated per iteration num_planners: 8 # The number of default planners to use for planning - planners: "RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" + # Optionally, planner parameters can be passed to change the default: "PRM[max_nearest_neighbors=5]", "EST[goal_bias=.5]", "RRT[range=10. goal_bias=.1]" + planners: + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect SBLkConfigDefault: type: geometric::SBL range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() diff --git a/kuka_lbr_iisy_moveit_config/config/stomp_planning.yaml b/kuka_lbr_iisy_moveit_config/config/stomp_planning.yaml index a6fe92f..7d83d32 100644 --- a/kuka_lbr_iisy_moveit_config/config/stomp_planning.yaml +++ b/kuka_lbr_iisy_moveit_config/config/stomp_planning.yaml @@ -1,10 +1,14 @@ -planning_plugin: stomp_moveit/StompPlanner -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - stomp_moveit/StompPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath stomp_moveit: num_timesteps: 60 diff --git a/kuka_lbr_iisy_support/config/lbr_iisy3_r760_joint_limits.yaml b/kuka_lbr_iisy_support/config/lbr_iisy3_r760_joint_limits.yaml index 3c5815c..4033d78 100644 --- a/kuka_lbr_iisy_support/config/lbr_iisy3_r760_joint_limits.yaml +++ b/kuka_lbr_iisy_support/config/lbr_iisy3_r760_joint_limits.yaml @@ -38,7 +38,7 @@ joint_limits: has_jerk: false joint_6: has_velocity_limits: true - max_velocity: 5.235983 + max_velocity: 6.981317 has_acceleration_limits: true max_acceleration: 112.291689 has_jerk: false diff --git a/kuka_lbr_iiwa_moveit_config/config/chomp_planning.yaml b/kuka_lbr_iiwa_moveit_config/config/chomp_planning.yaml index 2d9fdb8..9dba26e 100644 --- a/kuka_lbr_iiwa_moveit_config/config/chomp_planning.yaml +++ b/kuka_lbr_iiwa_moveit_config/config/chomp_planning.yaml @@ -1,10 +1,14 @@ -planning_plugin: chomp_interface/CHOMPPlanner -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - chomp_interface/CHOMPPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath start_state_max_bounds_error: 0.1 planning_time_limit: 10.0 max_iterations: 200 diff --git a/kuka_lbr_iiwa_moveit_config/config/ompl_planning.yaml b/kuka_lbr_iiwa_moveit_config/config/ompl_planning.yaml index 85aa81b..db6bbea 100644 --- a/kuka_lbr_iiwa_moveit_config/config/ompl_planning.yaml +++ b/kuka_lbr_iiwa_moveit_config/config/ompl_planning.yaml @@ -1,13 +1,16 @@ -planning_plugin: ompl_interface/OMPLPlanner -# To optionally use Ruckig for jerk-limited smoothing, add this line to the request adapters below -# default_planner_request_adapters/AddRuckigTrajectorySmoothing -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/ResolveConstraintFrames - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - ompl_interface/OMPLPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +# To optionally use Ruckig for jerk-limited smoothing, add this line to the response adapters below +# default_planning_response_adapters/AddRuckigTrajectorySmoothing +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath start_state_max_bounds_error: 0.1 planner_configs: APSConfigDefault: @@ -16,7 +19,16 @@ planner_configs: hybridize: 1 # Compute hybrid solution trajectories max_hybrid_paths: 36 # Number of hybrid paths generated per iteration num_planners: 8 # The number of default planners to use for planning - planners: "RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect,RRTConnect" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]" + # Optionally, planner parameters can be passed to change the default: "PRM[max_nearest_neighbors=5]", "EST[goal_bias=.5]", "RRT[range=10. goal_bias=.1]" + planners: + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect + - RRTConnect SBLkConfigDefault: type: geometric::SBL range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() diff --git a/kuka_lbr_iiwa_moveit_config/config/stomp_planning.yaml b/kuka_lbr_iiwa_moveit_config/config/stomp_planning.yaml index a6fe92f..7d83d32 100644 --- a/kuka_lbr_iiwa_moveit_config/config/stomp_planning.yaml +++ b/kuka_lbr_iiwa_moveit_config/config/stomp_planning.yaml @@ -1,10 +1,14 @@ -planning_plugin: stomp_moveit/StompPlanner -request_adapters: >- - default_planner_request_adapters/AddTimeOptimalParameterization - default_planner_request_adapters/FixWorkspaceBounds - default_planner_request_adapters/FixStartStateBounds - default_planner_request_adapters/FixStartStateCollision - default_planner_request_adapters/FixStartStatePathConstraints +planning_plugins: + - stomp_moveit/StompPlanner +request_adapters: + - default_planning_request_adapters/ResolveConstraintFrames + - default_planning_request_adapters/ValidateWorkspaceBounds + - default_planning_request_adapters/CheckStartStateBounds + - default_planning_request_adapters/CheckStartStateCollision +response_adapters: + - default_planning_response_adapters/AddTimeOptimalParameterization + - default_planning_response_adapters/ValidateSolution + - default_planning_response_adapters/DisplayMotionPath stomp_moveit: num_timesteps: 60 diff --git a/kuka_quantec_support/config/kr210_r2700_2_joint_limits.yaml b/kuka_quantec_support/config/kr210_r2700_2_joint_limits.yaml index 0436d70..c9a2923 100644 --- a/kuka_quantec_support/config/kr210_r2700_2_joint_limits.yaml +++ b/kuka_quantec_support/config/kr210_r2700_2_joint_limits.yaml @@ -11,31 +11,37 @@ default_acceleration_scaling_factor: 1.0 joint_limits: joint_1: has_velocity_limits: true - max_velocity: 2.0944 - has_acceleration_limits: false + max_velocity: 2.0384 + has_acceleration_limits: true + max_acceleration: 1.98271 has_jerk: false joint_2: has_velocity_limits: true - max_velocity: 2.0071 - has_acceleration_limits: false + max_velocity: 1.9451 + has_acceleration_limits: true + max_acceleration: 1.26288 has_jerk: false joint_3: has_velocity_limits: true - max_velocity: 1.9548 - has_acceleration_limits: false + max_velocity: 1.95476 + has_acceleration_limits: true + max_acceleration: 2.56508 has_jerk: false joint_4: has_velocity_limits: true - max_velocity: 3.1241 - has_acceleration_limits: false + max_velocity: 3.12413 + has_acceleration_limits: true + max_acceleration: 7.03857 has_jerk: false joint_5: has_velocity_limits: true - max_velocity: 3.0000 - has_acceleration_limits: false + max_velocity: 3.00196 + has_acceleration_limits: true + max_acceleration: 1.76397 has_jerk: false joint_6: has_velocity_limits: true - max_velocity: 3.8397 - has_acceleration_limits: false + max_velocity: 3.83972 + has_acceleration_limits: true + max_acceleration: 1.87268 has_jerk: false diff --git a/kuka_quantec_support/config/kr210_r3100_2_joint_limits.yaml b/kuka_quantec_support/config/kr210_r3100_2_joint_limits.yaml index c7fd18f..f55bbd9 100644 --- a/kuka_quantec_support/config/kr210_r3100_2_joint_limits.yaml +++ b/kuka_quantec_support/config/kr210_r3100_2_joint_limits.yaml @@ -12,30 +12,36 @@ joint_limits: joint_1: has_velocity_limits: true max_velocity: 1.8326 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.4647 has_jerk: false joint_2: has_velocity_limits: true max_velocity: 1.6406 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 0.5173 has_jerk: false joint_3: has_velocity_limits: true max_velocity: 1.7453 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 1.3139 has_jerk: false joint_4: has_velocity_limits: true max_velocity: 2.3726 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 6.9234 has_jerk: false joint_5: has_velocity_limits: true max_velocity: 2.2460 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 7.0213 has_jerk: false joint_6: has_velocity_limits: true max_velocity: 3.5933 - has_acceleration_limits: false + has_acceleration_limits: true + max_acceleration: 7.9141 has_jerk: false diff --git a/kuka_quantec_support/urdf/kr210_r2700_2_macro.xacro b/kuka_quantec_support/urdf/kr210_r2700_2_macro.xacro index 5b8a7cc..5223f85 100644 --- a/kuka_quantec_support/urdf/kr210_r2700_2_macro.xacro +++ b/kuka_quantec_support/urdf/kr210_r2700_2_macro.xacro @@ -112,14 +112,14 @@ - + - +