Reputation: 139
I am currently trying to implement a pure gravity compensation control on the Kuka iiwa 7 using Drake. I have implemented my code into 2 files: simulation and controller. My simulation contains my visualizer which takes in commands and sends out status'. My controller takes in status' and outputs commands. To create this, I have looked at drake's example code for kuka_simulation, move_iiwa_ee, and kuka_plan_runner. However, I have some questions regarding these 3 files.
If this is true, sending a torque value of 0 to all the joints should not let the arm fall and maintain its position. But if a torque controller does not exist in the physical arm, I would have to change my simulation code by removing KukaTorqueController and placing it in my controller code instead.
/**
* The reference joint positions. They should always be sent regardless of
* whether the arm is in position control mode or torque control mode.
*/
int32_t num_joints;
std::vector< double > joint_position;
Why would we need to send commanded positions of the arm when running on torque control mode? For example, if the arm was at the 0 position and if I were to send a position command of 0 to each joint while sending a torque of 1 to each joint, wouldn't this create a contradiction? The arm would try to keep its current position while trying to apply torque.
Upvotes: 1
Views: 340
Reputation: 121
This torque controller has gravity compensation. However, since the whole purpose of the simulation is create a copy of the physical kuka arm, does this mean that a torque controller already exists in the physical kuka arm?
Yes. I have not found any way to disable gravity compensation on the physical iiwa arm. It's always active, even when sending torques to the arm. On the physical arm, the torque value being sent is additive (roughly) to the force the arm is already commanding to reach the target position.
Which brings me to:
Why would we need to send commanded positions of the arm when running on torque control mode? For example, if the arm was at the 0 position and if I were to send a position command of 0 to each joint while sending a torque of 1 to each joint, wouldn't this create contradiction? The arm would try to keep it's current position while trying to apply a torque.
Short version: The position control is always in effect, even in torque control mode... and yes, that's a bit of a contradiction. If you send positions and zero torques, you get a position (well, impedance) controlled robot. In your example, if you sent a position of 0 and a torque of 1, the arm would move away from the 0 point with the specified torque (until it deviated too much from the commanded position, in which case a fault would occur).
There's a better description in https://github.com/RobotLocomotion/drake/issues/11955 which goes into more detail regarding how the commands are handled by the real arm (and how drake doesn't properly model this yet).
Upvotes: 2