abr / abr_jaco2

A repository for the Jaco2 robot arm interface and configuration files, intended for use with the abr/control repo.
Other
17 stars 4 forks source link

about jaco2's torque control #19

Closed xuhuairuogu closed 3 years ago

xuhuairuogu commented 4 years ago

Hi, Studywolf FIrst of all, thanks for providing such a good package for Jaco2 position and torque control.
My research is Nolinear Model Predictive Control based Multi Task Control Framework for Wheeled Mobile Manipulator. Now I have finished the simulation of NMPC based path following on Jaco2 in V-rep and want to implement it on real Jaco2.Because I use dynamics model for prediction and joint torques as control input, I should learn how to use torque control interface provided by Jaco2. Before abr_jaco2, I tried kinova_ros package. However, its communication frequency is up to 100Hz, which is not high enough for good torque control performance. In addition, I am confused about the internal force controller of Jaco2. It seems that Jaco2 has a default gravity compensation after switching to torque control mode by High Level API. However, if I send torque command as [0,0,0,0,0,0] to Jaco2, it will fall down; if I calculate torque command based on the dynamics model with zero gravity, Jaco2 will track the target trajectory , but the tracking error is really big. Occasionally, I find abr_jaco2 and have tested all python files in the examples directory. connection test, control loop speed test, joint space position control osc and reaching osc python files all work normally. As for floating.py, Jaco2 cannot hold itself after entering force control mode. And for adaptive reach.py, there will appear ERROR MESSAGE 9 in the terminal after entering force control mode. Since I am only familiar with C++ and MATLAB, I wanna know how to communicate with and control Jaco2 only by C++ based on abr_jaco2 or Low Level API.

studywolf commented 4 years ago

Hello! I am happy to help.

Yes, the very low communication speed using the kinova_ros package is why we developed this package, which is able to achieve about 350Hz. Far from ideal, but it makes it possible to use force control, at least!

So if I'm understanding correctly, all of the files in the examples directory run properly, except for the floating.py and adaptive_reach.py files.

Floating.py When you say that the arm is unable to hold itself up, can you elaborate on this? Does it free-fall to the ground, does it work in some configurations but not others? I'll need more information.

Adaptive_reach.py @p3jawors is on vacation for this week, but when he's back on Wednesday he'll be able to address this issue with you

If you'd like to just use the C++ to communicate with the arm you can go into the interfacing files and check out the functions that we've defined there https://github.com/abr/abr_jaco2/blob/master/abr_jaco2/interface/jaco2_rs485.cpp

    // main functions
    void Connect();
    void Disconnect();
    void InitForceMode();
    void InitPositionMode();
    int SendAndReceive(RS485_Message message[6], bool loop);
    int SendAndReceiveHand(RS485_Message message[3], bool loop);
    void SendForces(float u[6]);
    int SendTargetAngles(float q_target[6]);
    void SendTargetAnglesSetup();
    void SendTargetAnglesHand(bool open);
    void PrintError(int index, int current_motor);
    void ProcessFeedback();

To send torque signals, you have to Connect, InitForceMode, and then SendForces. The SendForces function will also update the angles and velocity feedback from the arm, which can be found in the pos and vel arrays.

If you have any specific questions about it I'll be happy to answer them!

p3jawors commented 4 years ago

One thing you can try for the floating controller is setting the velocity input to osc.generate to zeros (np.zeros(6)), which should improve the performance a bit. The velocity feedback isn't the greatest because of the communication delays with the jaco.

As for adaptive_reach.py, can you check your loop speed with timeit.default_timer()? The connection_test script only checks with a basic pd controller, the adaptive control will add some overhead.

Can you also confirm what branches / commits you are on for abr_jaco2 and abr_control?

p3jawors commented 3 years ago

Closing due to inactivity. Feel free to reopen if you are experiencing issues.