Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

tuning force controller #178

Closed
shrutichakraborty opened this issue Mar 18, 2024 · 3 comments
Closed

tuning force controller #178

shrutichakraborty opened this issue Mar 18, 2024 · 3 comments

Comments

@shrutichakraborty
Copy link

Hi! I'm using the cartesian force controller. I've noticed that when sending a traget wrench in purely z (aiming for the robot to move vertically down while keepng perpendicular to the surface), it starts to drift in x and y as well. Can anyone give a hit on which parameters of the controllers could I tune to avoid this ? In my application I am checking the sensor wrench values and commanding the robot to continue to move downwards in z until it comes in contact with the surface (experiences a certain force threshold)? I am using a UR10e robot.

@captain-yoshi
Copy link

Can you post your controller's configuration ?

Be sure to read the force controller README :

Note that the controller does not strictly move only in the commanded direction. Although its behavior is linearized in operational space, there might be small drifts in other axes. This is a feature of the forward dynamics-based solver. In fact, there is no error reduction on axes orthogonal to the published target wrench. The benefit is that the controller finds approximate solutions near singular configurations.

This is a feature of the force controller. @stefanscherzinger Would it be possible to setup a maximum permitted position deviation per axe ? If so, could you point out where we could make this modification ?

Lowering the P Gains for the X/Y axis might help lowering the motion in those directions. There might be other causes creating the drift, e.g. drift in your force torque sensor.

@shrutic12
Copy link

shrutic12 commented Apr 8, 2024

Can you post your controller's configuration ?

Be sure to read the force controller README :

Note that the controller does not strictly move only in the commanded direction. Although its behavior is linearized in operational space, there might be small drifts in other axes. This is a feature of the forward dynamics-based solver. In fact, there is no error reduction on axes orthogonal to the published target wrench. The benefit is that the controller finds approximate solutions near singular configurations.

This is a feature of the force controller. @stefanscherzinger Would it be possible to setup a maximum permitted position deviation per axe ? If so, could you point out where we could make this modification ?

Lowering the P Gains for the X/Y axis might help lowering the motion in those directions. There might be other causes creating the drift, e.g. drift in your force torque sensor.

`
solver:
error_scale: 0.5
publish_state_feedback: True

pd_gains:
    trans_x: {p: 0.05}
    trans_y: {p: 0.05}
    trans_z: {p: 0.05}
    rot_x: {p: 0.01}
    rot_y: {p: 0.01}
    rot_z: {p: 0.01}`

Hi @captain-yoshi , I am using the default values for the force controller.

Also I am having issues with the cartesian compliance controller: changing the stiffness values of the axes, does not seem to make any difference on the robot (ur10e). It tries to go to commanded position and does not stabilize and stop at obstacles. Any ideas sould be greatly appreciated! Here is the config for the controller (same as default), I have tested stiffness as low as 90 in all directions.

`stiffness: # w.r.t. compliance_ref_link coordinates
trans_x: 500.0
trans_y: 500.0
trans_z: 500.0
rot_x: 20.0
rot_y: 20.0
rot_z: 20.0

solver:
    error_scale: 0.5
    iterations: 1
    publish_state_feedback: True

# For all controllers, these gains are w.r.t. the robot_base_link coordinates.
pd_gains:
    trans_x: {p: 0.05, d: 0.005}
    trans_y: {p: 0.05, d: 0.005}
    trans_z: {p: 0.05, d: 0.005}
    rot_x: {p: 1.5}
    rot_y: {p: 1.5}
    rot_z: {p: 1.5}`

@stefanscherzinger
Copy link
Contributor

@captain-yoshi

This is a feature of the force controller. @stefanscherzinger Would it be possible to setup a maximum permitted position deviation per axe ? If so, could you point out where we could make this modification ?

This would require some form of error rejection. The cartesian_compliance_controller could be used for this. However, I like the idea of locking individual Cartesian axes.. That would require a new solver and a new thinking though. Not sure where to put it at the moment..

@shrutic12

It tries to go to commanded position and does not stabilize and stop at obstacles.

It the robot doesn't stop, then probably the signals from the force-torque sensor are not connected to the controller. I suggest moving the robot by hand and feel if the robot is responsive. If it isn't, check whether the relevant topics are published and subscribed correctly.

ros2 topic list | grep sensor

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

4 participants