Kinovarobotics / Kinova-kortex2_Gen3_G3L

Code examples and API documentation for KINOVA® KORTEX™ robotic arms
https://www.kinovarobotics.com/
Other
117 stars 87 forks source link

Changing control loops active - TORQUE control #110

Closed mattia-risiglione closed 1 year ago

mattia-risiglione commented 2 years ago

Hi all,

when using control mode set to TORQUE, the control loops active are: torque, velocity and current. I refer to issue #77 for the control diagram in torque control.

When using methods of class ControlLoop to set MOTOR_VELOCITY to false, is the output of the torque control loop directly sent to the current control loop? Meaning, velocity loop and the feedback velocity are removed from the cascade controller.

felixmaisonneuve commented 2 years ago

Hi @mattia-risiglione,

The function SetActivatedControlLoop is not implemented and should return an UNIMPLEMNETED subErrorCode. Unless your are talking about another function, it does not work.

Best, Felix

mattia-risiglione commented 2 years ago

thanks @felixmaisonneuve for the reply.

Is there any specific reason for which the velocity loop has been put there? What is the best way to remove the velocity loop (setting just the first element of KBz to 1, all others to 0?) and the velocity feedback then? If someone wants to improve performance in torque control, by changing the coefficients of transfer functions with the methods provided, to me not having this loop would simplify the design of a new transfer function at the torque control loop.

felixmaisonneuve commented 2 years ago

Hi @mattia-risiglione,

I finally got an answer.

The velocity loop is there to add stability to the controller. We can therefore have higher gains on the torque loop and have better accuracy when the speed is reduced (in rigid contact). However, it reduces speed performance. Only the torque command is taken into account. Torque -> speed -> current.

That's why we added the torque control high velocity which doesn't have this speed loop, so directly torque -> motor current. Much more efficient in dynamics, but less precise in rigid contact.

Best, Felix

karinaGarcia98 commented 2 years ago

Hello, I want to apply a torque control method on the Kinova Gen3 robot. From what I have read on issue #77 , there is a series of control loops on each actuator, including a control loop for the position, velocity, torque and current. The TORQUE control mode has the velocity, torque and current control loops active (which I am able to confirm by printing the contents of the bitmask of ControlLoopSelection, obtaining a value of 56 when an actuator is used in this mode: motor current + joint torque + motor velocity = 32 + 16 + 8 = 56 ). Here, on issue #110 , it was clarified that the function SetActiveControlLoops() is not implemented but that the TORQUE_HIGH_VELOCITY control mode is supposed to have only the torque and current control loops active. First, when trying to print the value of the ControlLoopSelection bitmask with the TORQUE_HIGH_VELOCITY control mode active, I am getting a 288, which does not make sense with respect to the enumeration of ControlLoopSelection, as I would expect to get a 48. While that could be just a problem within my printing process, I also observed an unexpected behaviour when sending a zero torque command to the 6th actuator of the 7DoF Kinova Gen3. I am using the 2.3.0 API release.

  1. When sending a zero torque command and actualizing the desired joint position to the last read joint position (just like it is recommended in the 108-Gen3_torque_control/01-torque_control_cyclic.cpp example ‘[..] instead of disabling the following error’), the joint reaches an approximate 45° angle with respect to the vertical and stops there, while I would expect for the link to fall completely and reach the vertical (which in fact happens in the TORQUE control mode). Is this control mode working properly? or, does this odd observed behaviour has to do with a bug on this control mode?
  2. On the other hand, when sending a zero torque command and not actualizing the desired position to the last read joint position, the error WRONG_SERVOING_MODE => <srv: 3, fct: 1, msgType: 3 > occurs and, from what I gathered reading around and exploring the faults that these attempt activated on the web app, this has to do with the arm reaching the threshold of the ‘Following error’. Is this an expected behaviour even when the position and velocity control loops are not supposed to be active? Is there a way I can disable this safety? How could I workaround the need to send a position command?

Thank you for your time, Karina

felixmaisonneuve commented 2 years ago

Hi @karinaGarcia98,

  1. There are known bugs with the TORQUE_HIGH_VELOCITY. As an example, I think the set_torque_joint function does not work in TORQUE_HIGH_VELOCITY. If you send torque using the api function, the joint won't move, as opposed to the TORQUE control mode where the joint will start moving according to the torque value sent. I do not think this is the same bug you have, but this clearly seems like another bug in the TORQUE_HIGH_VELOCITY. Can you detail a bit what you are doing and maybe add a code sample so I can document this (possibly) new bug correctly.
  2. Only the velocity control loop is de-activated. The position control loop is still active and you should always feed the joint's position in your command, even in TORQUE_HIGH_VELOCITY. If you do not set a position when sending your command, you will get errors (probably your case here). I would not disable the safety. You want a workaround to not send positions, why is that an issue? In our example we simply use the actuator's position from the previous feedback : https://github.com/Kinovarobotics/kortex/blob/a47c6dc4b3698812420caf8d053ec327954906b4/api_cpp/examples/108-Gen3_torque_control/01-torque_control_cyclic.cpp#L263 Is this not possible in your case?

Best, Felix

tanguy-s commented 2 years ago

Hi @felixmaisonneuve,

We are also trying to use the JOINT_TORQUE_HIGH_VELOCITY mode and indeed doesn't seem to be working at all.

The control loop is running (there are no error/warnings) but there are no torques applied on the joints. They are even less stiff than when using the "classical" TORQUE control mode.

Could you please get the information on when this bug is going to be fixed ? And also make sure that this is done with high priority ?

Velocity control has been declared as faulty since 2020 in #44 . The only low-level control modes we are left with are Current or this modified Torque-Velocity controller.

Thank you

karinaGarcia98 commented 2 years ago

Hi @felixmaisonneuve ,

  1. I have noticed that with the TORQUE_HIGH_VELOCITY on the 6th actuator, the actuator stops at an odd angle when sending a zero ‘torque command’ because of friction. I had not checked that, but with someone’s help I was able to identify that one can indeed move the articulation almost freely when sending a zero torque command. You said that the function set_torque_joint does not work in the TORQUE_HIGH_VELOCITY control mode so, how is one supposed to use this control mode?
  2. With respect to the ‘following error’ that occurs when not sending the position, I would like to be able to deactivate this safety since a future plan for the robot is to be able to perform bilateral teleoperation experiments, and this safety produces an error more times than not when moving the robot articulations (wich is something we would like to be able to do). They occur less frequently when using the CURRENT control mode, but sometimes appear again even after clearing them (without having changed anything).

Thank you again for your time,

Karina

felixmaisonneuve commented 2 years ago

Hi @tanguy-s,

TORQUE_HIGH_VELOCITY control loop has bugs and cannot be used for most use cases. We are aware of that and I do not have a time frame to give you as to when it will be fixed.

Being less stiff is the goal of the TORQUE_HIGH_VELOCITY control loop. The velocity loop is removed from the cascade controller so the joints are more responsive (less stiff, moves faster), but they are less stable and are sensitive to noise.

You actually meant #42, but yes, velocity control loop has this drifting problem when sending 0 velocity to a joint. What you can do instead is use the position control mode and find your next position based on the current and your wanted velocity like we do in our example : https://github.com/Kinovarobotics/kortex/blob/a47c6dc4b3698812420caf8d053ec327954906b4/api_cpp/examples/200-Actuator_low_level_control/01-actuator_low_level_velocity_control.cpp#L201-L205

You do not only have Torque and current control loops, you also have position control mode, which can be very helpfull

@karinaGarcia98

  1. Because set_torque_joint does not work, you cannot really use the TORQUE_HIGH_VELOCITY and you must use the TORQUE control mode if you need to do torque control.
  2. It is not possible to disable any safety on Gen3 arms

regards, Felix

felixmaisonneuve commented 1 year ago

TORQUE_HIGH_VELOCITY was fixed in the newest KortexAPI 2.6.0 release (SWU 2.5.2) and it is now possible to send torque commands in that mode.

Closing this issue