From 9d957cc72832785b79c98d88329a2b1cd604299e Mon Sep 17 00:00:00 2001 From: Jelmer de Wolde Date: Fri, 1 Nov 2024 08:58:12 +0100 Subject: [PATCH] Moveit from source (#6) * Add acceleration limits, required for new moveit. Signed-off-by: Jelmer de Wolde * Decrease servo publish period, required for new moveit. Signed-off-by: Jelmer de Wolde * Set pub_frame for joy_to_twist node. Signed-off-by: Jelmer de Wolde --------- Signed-off-by: Jelmer de Wolde --- rcdt_franka/config/servo_params.yaml | 2 +- rcdt_franka/launch/franka.launch.py | 1 + .../config/joint_limits.yaml | 36 +++++++++---------- 3 files changed, 20 insertions(+), 19 deletions(-) diff --git a/rcdt_franka/config/servo_params.yaml b/rcdt_franka/config/servo_params.yaml index ecbcc6f..0261f8c 100644 --- a/rcdt_franka/config/servo_params.yaml +++ b/rcdt_franka/config/servo_params.yaml @@ -20,7 +20,7 @@ scale: # override_velocity_scaling_factor = 0.0 # valid range [0.0:1.0] ## Properties of outgoing commands -publish_period: 0.034 # 1/Nominal publish rate [seconds] +publish_period: 0.033 # 1/Nominal publish rate [seconds] low_latency_mode: false # Set this to true to publish as soon as an incoming Twist command is received (publish_period is ignored) # What type of topic does your robot driver expect? diff --git a/rcdt_franka/launch/franka.launch.py b/rcdt_franka/launch/franka.launch.py index bebbe4c..17551ee 100644 --- a/rcdt_franka/launch/franka.launch.py +++ b/rcdt_franka/launch/franka.launch.py @@ -87,6 +87,7 @@ def launch_setup(context: LaunchContext) -> None: parameters=[ {"pub_topic": "/servo_node/delta_twist_cmds"}, {"config_pkg": "rcdt_franka"}, + {"pub_frame": "fr3_hand"}, ], ) diff --git a/rcdt_franka_moveit_config/config/joint_limits.yaml b/rcdt_franka_moveit_config/config/joint_limits.yaml index 4dac898..e985710 100644 --- a/rcdt_franka_moveit_config/config/joint_limits.yaml +++ b/rcdt_franka_moveit_config/config/joint_limits.yaml @@ -15,45 +15,45 @@ joint_limits: fr3_finger_joint1: has_velocity_limits: true max_velocity: 0.20000000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 10.0 fr3_finger_joint2: has_velocity_limits: true max_velocity: 0.20000000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 10.0 fr3_joint1: has_velocity_limits: true max_velocity: 2.6200000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 10.0 fr3_joint2: has_velocity_limits: true max_velocity: 2.6200000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 10.0 fr3_joint3: has_velocity_limits: true max_velocity: 2.6200000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 10.0 fr3_joint4: has_velocity_limits: true max_velocity: 2.6200000000000001 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 10.0 fr3_joint5: has_velocity_limits: true max_velocity: 5.2599999999999998 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 10.0 fr3_joint6: has_velocity_limits: true max_velocity: 4.1799999999999997 - has_acceleration_limits: false - max_acceleration: 0 + has_acceleration_limits: true + max_acceleration: 10.0 fr3_joint7: has_velocity_limits: true max_velocity: 5.2599999999999998 - has_acceleration_limits: false - max_acceleration: 0 \ No newline at end of file + has_acceleration_limits: true + max_acceleration: 10.0 \ No newline at end of file