ImpedanceController weight gains interpretation? #52
-
Hello! I'm interested in having the RBY-1 manipulate a set of drawers using the provided ImpedanceController, but am having a hard time finding an interpretation of the 'weight' gains. Would it be possible provide any details on how position and weights are converted into a control signal? Having the equations used (like the ones provided for the OptimalController in the RBY-1 documentation) would be very helpful. Thanks! |
Beta Was this translation helpful? Give feedback.
Replies: 2 comments 7 replies
-
First, apologies for the delayed response. Providing specific equations is currently under consideration. In the meantime, you can indirectly understand the behavior by reviewing the 07_impedance_control.py example. If you examine the example_impedance_control_command_1 section, specifically the right_arm_command, you’ll notice that the weight values [3000, 3000, 0] are applied to the XYZ positions. This means the Z direction becomes significantly smoother, as a weight of 0 effectively disables position control in that direction, making it feel “free” or “smooth.” You might already be aware of this general behavior, and we understand you are likely asking for detailed equations. The team in charge is currently evaluating whether to release the equations or provide additional materials to facilitate understanding. Thank you for your patience and understanding while we work on this. @keunjun-choi please provide your feedback on this. |
Beta Was this translation helpful? Give feedback.
-
We're also wondering how the impedance controller performs EE force control when there is no force/torque sensing at the joints? |
Beta Was this translation helpful? Give feedback.
I sincerely apologize for the extremely delayed response—I realize it's been nearly one month. Thank you for your patience.
The impedance controller is designed as follows:
where the force$F$ is defined as:
with
where$T_d$ represents the desired position and orientation in $SE(3)$ .
The stiffness and damping matrices are defined as:
translation-weight
is defined asand
rotation-weight
is defined as