DRCL-USC / Hector_Simulation

Simulation Software (ROS/MATLAB) for HECTOR Humanoid Robot Locomotion Control/Bipedal Locomotion Control/Force-and-moment-based MPC
https://youtu.be/NcW-NFwjMh0
Other
393 stars 121 forks source link

Robot cannot keep standing #23

Closed TsuruMasato closed 4 months ago

TsuruMasato commented 4 months ago

Hello, I want to see the robot standing in Gazebo.

https://github.com/DRCL-USC/Hector_Simulation/blob/5e0ca67ce4ca5b1879391438c6f54c7224ec4da1/Hector_ROS_Simulation/hector_control/src/FSM/FSMState_Walking.cpp#L36

This line changes the gait pattern. But in Gazebo, the robot always jumps backword. It cannot keep standing.

In your videos on YouTube, real Hector often keeps standing. Did you add new algorithm or a standing mode with conventional Joint PD Control? Or the same code, same Centroidal Model + Force/Moment input MPC-QP?

https://github.com/DRCL-USC/Hector_Simulation/assets/14979823/7a562652-5d43-4aa5-8b05-48849b3a3cef

https://github.com/DRCL-USC/Hector_Simulation/assets/14979823/da97fb4a-21e2-4469-a01e-ec743a56b285

Also, we would like to buy Hector V2.

Best,

junhengl commented 4 months ago

Hello,

Thanks for your questions. For standing, you can directly use Cmpc.setGaitNum(1), where 1 is the gait number for double stance. It should work right out of the box. I have given it a few tries and it seems to work fine. The hardware also uses just MPC to balance in double stance without any additional joint PD. However, for better performance, it is recommended to retune the weights in https://github.com/DRCL-USC/Hector_Simulation/blob/5e0ca67ce4ca5b1879391438c6f54c7224ec4da1/Hector_ROS_Simulation/hector_control/ConvexMPC/ConvexMPCLocomotion.cpp#L321 to give more weights to position tracking for assisting stable standing, for instance {100, 100, 250, 400, 400, 400, 1, 1, 1, 1, 1, 1};

For purchase inquiries about HECTOR V2, please email support@laser-robotics.com for more details!

Thanks, Junheng

https://github.com/DRCL-USC/Hector_Simulation/assets/70034147/c7359745-4ea6-4413-9b48-81db90575338

TsuruMasato commented 4 months ago

Dear Dr. Junhengl,

Thank you so much for your swift reply!

Yes, I was aware that Cmpc.setGaitNum(1) changes the gait pattern to stance mode. The video I posted last week demonstrates this case.

Today, I have tuned the Q gains. For my case, the following values worked best: double Q[12] = {30, 30, 30, 300, 300, 100, 1, 1, 1, 10, 10, 10};

These settings managed to maintain balance for about 5 seconds, but eventually, the robot diverged.

https://github.com/DRCL-USC/Hector_Simulation/assets/14979823/591f34b5-7762-4ed2-bb53-87a583f6aa2b

Interestingly, the configuration with Q = {100, 100, 250, 400, 400, 400, 1, 1, 1, 1, 1, 1} did not enhance stability on my local machine. This discrepancy might be due to differences in our CPUs or qpOASES versions.

Regardless, the Hector project and your papers are truly remarkable in both theory and implementation. I will continue to follow your work closely.

Thank you very much.