Skip to content

Commit

Permalink
Using Velocity Profile of Dynamixel to make the motion smoother
Browse files Browse the repository at this point in the history
  • Loading branch information
Woojin-Crive committed Jan 26, 2025
1 parent ff88b9e commit 0737960
Show file tree
Hide file tree
Showing 2 changed files with 26 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,8 @@
<param name="Position P Gain">800</param>
<param name="Position I Gain">100</param>
<param name="Position D Gain">100</param>
<param name="Profile Velocity">200</param>
<param name="Profile Acceleration">50</param>
<param name="Drive Mode">0</param>
</gpio>

Expand All @@ -132,6 +134,8 @@
<param name="Position P Gain">800</param>
<param name="Position I Gain">100</param>
<param name="Position D Gain">100</param>
<param name="Profile Velocity">200</param>
<param name="Profile Acceleration">50</param>
<param name="Drive Mode">0</param>
</gpio>

Expand All @@ -147,6 +151,8 @@
<param name="Position P Gain">800</param>
<param name="Position I Gain">100</param>
<param name="Position D Gain">100</param>
<param name="Profile Velocity">200</param>
<param name="Profile Acceleration">50</param>
<param name="Drive Mode">0</param>
</gpio>

Expand All @@ -162,6 +168,8 @@
<param name="Position P Gain">800</param>
<param name="Position I Gain">100</param>
<param name="Position D Gain">100</param>
<param name="Profile Velocity">200</param>
<param name="Profile Acceleration">50</param>
<param name="Drive Mode">0</param>
</gpio>

Expand Down
36 changes: 18 additions & 18 deletions open_manipulator_x_moveit_config/config/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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

0 comments on commit 0737960

Please sign in to comment.