CentroEPiaggio / kuka-lwr

Software related to the KUKA LWR 4+: for real and for simulation.
The Unlicense
101 stars 81 forks source link

fril torque + position #63

Closed gpldecha closed 7 years ago

gpldecha commented 8 years ago

Sorry if I asked a similar question, but I was looking in lwr_hw_fril.hpp at the following piece of code:

for(int j=0; j < njoints; j++) { newJntPosition[j] = (float)joint_positioncommand[j]; newJntAddTorque[j] = (float)joint_effortcommand[j]; newJntStiff[j] = (float)joint_stiffnesscommand[j]; newJntDamp[j] = (float)joint_dampingcommand[j]; } device->SetCommandedJointStiffness(newJntStiff); device->SetCommandedJointPositions(newJntPosition); device->SetCommandedJointDamping(newJntDamp); device->SetCommandedJointTorques(newJntAddTorque);

It suggests that four different hardward interfaces should be present in the kuka model since one handle is associated with one resource. In the current model in the repository there is only an additional dummy link for joint_stiffness. Do you have another model in which you an additional three dummy links ?

Thanks a lot for your help.

gpldecha commented 8 years ago

So I have added damping so I can set it now I can set it in JointStateInterface controllers.

In lwr_hw.cpp :

  /// register damping
  state_interface_damp.registerHandle(hardware_interface::JointStateHandle(
  joint_names_[j]+std::string("_damping"),&joint_stiffness_[j], &joint_stiffness_[j],joint_stiffness_[j]));

 /// Damping interface
  hardware_interface::JointHandle joint_handle_damping;
  joint_handle_damping = hardware_interface::JointHandle(state_interface_damp.getHandle(joint_names_[j]+std::string("_damping")),   &joint_damping_command_[j]);

I can now set damping like the torque in my PositionJointInterface controller. I guess now all I need to do is add something for setting the torques even if I am in JointState mode instead of effort.

carlosjoserg commented 8 years ago

Hi @gpldecha

As I said in #64, this is right now the priority, working on the lwr_hw_fril.hpp interface.

To answer you question:

It suggests that four different hardward interfaces should be present in the kuka model since one handle is associated with one resource. In the current model in the repository there is only an additional dummy link for joint_stiffness. Do you have another model in which you an additional three dummy links ?

No so far. What I did do was to create a dummy hwiface called CartesianImpedanceInterface, such that using a controller on that interface would trigger that strategy in the robot. But this is still offline (WIP).

I can now set damping like the torque in my PositionJointInterface controller.

Yes, that is correct, it is basically reproducing what's been done for the stiffness, only that I've never tried with the damping anyway.

I guess now all I need to do is add something for setting the torques even if I am in JointState mode instead of effort.

I didn't fully got this part, the effort state should be already in the state interface as part of the joint. Or what do you mean?

gpldecha commented 8 years ago

Hi, thanks for your replay. I made all the changes such that I have a total of 4 resources per joint.