diff --git a/open_manipulator_x_description/ros2_control/open_manipulator_x_system.ros2_control.xacro b/open_manipulator_x_description/ros2_control/open_manipulator_x_system.ros2_control.xacro index 50090ca..2b43810 100644 --- a/open_manipulator_x_description/ros2_control/open_manipulator_x_system.ros2_control.xacro +++ b/open_manipulator_x_description/ros2_control/open_manipulator_x_system.ros2_control.xacro @@ -117,6 +117,8 @@ 800 100 100 + 200 + 50 0 @@ -132,6 +134,8 @@ 800 100 100 + 200 + 50 0 @@ -147,6 +151,8 @@ 800 100 100 + 200 + 50 0 @@ -162,6 +168,8 @@ 800 100 100 + 200 + 50 0 diff --git a/open_manipulator_x_moveit_config/config/joint_limits.yaml b/open_manipulator_x_moveit_config/config/joint_limits.yaml index b8c7d32..871a7bb 100644 --- a/open_manipulator_x_moveit_config/config/joint_limits.yaml +++ b/open_manipulator_x_moveit_config/config/joint_limits.yaml @@ -10,33 +10,33 @@ default_acceleration_scaling_factor: 0.1 joint_limits: gripper_left_joint: has_velocity_limits: true - max_velocity: 4.7999999999999998 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 4.796164779 + has_acceleration_limits: true + max_acceleration: 18.7253757 has_position_limits: true gripper_right_joint: has_velocity_limits: true - max_velocity: 4.7999999999999998 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 4.796164779 + has_acceleration_limits: true + max_acceleration: 18.7253757 joint1: has_velocity_limits: true - max_velocity: 4.7999999999999998 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 4.796164779 + has_acceleration_limits: true + max_acceleration: 18.7253757 joint2: has_velocity_limits: true - max_velocity: 4.7999999999999998 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 4.796164779 + has_acceleration_limits: true + max_acceleration: 18.7253757 joint3: has_velocity_limits: true - max_velocity: 4.7999999999999998 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 4.796164779 + has_acceleration_limits: true + max_acceleration: 18.7253757 joint4: has_velocity_limits: true - max_velocity: 4.7999999999999998 - has_acceleration_limits: false - max_acceleration: 0 + max_velocity: 4.796164779 + has_acceleration_limits: true + max_acceleration: 18.7253757