unitreerobotics / unitree_legged_sdk

SDK tools for control robots.
BSD 3-Clause "New" or "Revised" License
295 stars 163 forks source link

Go1 Pro, no reaction to command (unitree_legged_sdk, High-level) #24

Closed devemin closed 2 years ago

devemin commented 2 years ago

Hello unitree and every user,

I got my Go1 Pro . It's very nice :-)

I tried to use this unitree_legged_sdk, and execute the 'example_walk' source with sudo, on the Go1's Raspberry pi.

sudo ./example_walk

I received the state value (IMU or rotation or velocity). But when I send the command (LED, torque, High-level mode), No reaction happen at LED or Motors...

[ Question ] Is this the limitation of the model's firmware ?

Can I move the Go1 Pro with C++ source ? Which port No. should I send the command ? (192.168.123.161:8082, right ?)

Custom(uint8_t level): safe(LeggedType::Go1), udp(8090, "192.168.123.161", 8082, sizeof(HighCmd), sizeof(HighState)){

Could you tell me about this ?

This is the source. (About version: I modified the one that was already in the home directory of the Raspberry Pi.)

tried source. click this triangle. ``` /***************************************************************** Copyright (c) 2020, Unitree Robotics.Co.Ltd. All rights reserved. ******************************************************************/ #include "unitree_legged_sdk/unitree_legged_sdk.h" #include #include #include #include using namespace UNITREE_LEGGED_SDK; class Custom { public: // Custom(uint8_t level): safe(LeggedType::A1), udp(level){ Custom(uint8_t level): safe(LeggedType::Go1), udp(8090, "192.168.123.161", 8082, sizeof(HighCmd), sizeof(HighState)){ //udp address: 192.168.123.161 (raspi) :port 8082 -> high mode, successed to got IMU data. OK //udp address: 192.168.123.10 (controller) :port 8007 -> Got Motor Weakness, NG //When the motor got weakness, need to restart. // Custom(uint8_t level): safe(LeggedType::A1), udp(8090, "192.168.123.161", 8082, sizeof(HighCmd), sizeof(HighState)){ udp.InitCmdData(cmd); udp.SetDisconnectTime(dt, 1); // udp.SetDisconnectTime(0, 0); } void UDPRecv(); void UDPSend(); void RobotControl(); Safety safe; UDP udp; HighCmd cmd = {0}; HighState state = {0}; int motiontime = 0; float dt = 0.002; // 0.001~0.01 }; void Custom::UDPRecv() { udp.Recv(); } void Custom::UDPSend() { udp.Send(); } void Custom::RobotControl() { motiontime += 2; udp.GetRecv(state); // printf("%d %f\n", motiontime, state.forwardSpeed); // printf("%f %f \n", state.imu.quaternion[0], state.imu.quaternion[1]); // printf("%f %f \n", state.imu.rpy[1], state.imu.rpy[2]); printf("%f %f %f %f %f\n", state.imu.rpy[1], state.imu.rpy[2], state.position[0], state.position[1], state.velocity[0]); cmd.mode = 0; // 0:idle, default stand 1:forced stand 2:walk continuously cmd.gaitType = 0; cmd.speedLevel = 0; cmd.footRaiseHeight = 0; cmd.bodyHeight = 0; cmd.euler[0] = 0; cmd.euler[1] = 0; cmd.euler[2] = 0; cmd.velocity[0] = 0.0f; cmd.velocity[1] = 0.0f; cmd.yawSpeed = 0.0f; cmd.led[0].r = 255; cmd.led[0].g = 0; cmd.led[0].b = 0; // if(motiontime > 0){ // cmd.mode = 1; // cmd.euler[2] = 0.4; // ??????????????????????????????? // } // if(motiontime > 0){ // cmd.mode = 2; // cmd.gaitType = 1; // cmd.velocity[0] = 0.6f; // -1 ~ +1 // cmd.footRaiseHeight = 0.; // } if(motiontime > 0 && motiontime < 1000){ cmd.mode = 1; cmd.euler[0] = -0.3; } if(motiontime > 1000 && motiontime < 2000){ cmd.mode = 1; cmd.euler[0] = 0.3; } if(motiontime > 2000 && motiontime < 3000){ cmd.mode = 1; cmd.euler[1] = -0.2; } if(motiontime > 3000 && motiontime < 4000){ cmd.mode = 1; cmd.euler[1] = 0.2; } if(motiontime > 4000 && motiontime < 5000){ cmd.mode = 1; cmd.euler[2] = -0.2; } if(motiontime > 5000 && motiontime < 6000){ cmd.mode = 1; cmd.euler[2] = 0.2; } if(motiontime > 6000 && motiontime < 7000){ cmd.mode = 1; cmd.bodyHeight = -0.2; } if(motiontime > 7000 && motiontime < 8000){ cmd.mode = 1; cmd.bodyHeight = 0.1; } if(motiontime > 8000 && motiontime < 9000){ cmd.mode = 1; cmd.bodyHeight = 0.0; } if(motiontime > 9000 && motiontime < 11000){ cmd.mode = 5; } if(motiontime > 11000 && motiontime < 13000){ cmd.mode = 6; } if(motiontime > 13000 && motiontime < 14000){ cmd.mode = 0; } if(motiontime > 14000 && motiontime < 18000){ cmd.mode = 2; cmd.gaitType = 2; cmd.velocity[0] = 0.4f; // -1 ~ +1 cmd.yawSpeed = 2; cmd.footRaiseHeight = 0.1; // printf("walk\n"); } if(motiontime > 18000 && motiontime < 20000){ cmd.mode = 0; cmd.velocity[0] = 0; } if(motiontime > 20000 && motiontime < 24000){ cmd.mode = 2; cmd.gaitType = 1; cmd.velocity[0] = 0.2f; // -1 ~ +1 cmd.bodyHeight = 0.1; // printf("walk\n"); } // printf("%f\n", cmd.bodyHeight); // if(motiontime > 0000 && motiontime < 2000){ // cmd.mode = 2; // cmd.gaitType = 2; // cmd.velocity[0] = 0.4f; // -1 ~ +1 // cmd.yawSpeed = 2; // cmd.footRaiseHeight = 0.1; // // printf("walk\n"); // } // if(motiontime > 2000 && motiontime < 3000){ // cmd.mode = 0; // cmd.velocity[0] = 0; // } // if(motiontime > 0 && motiontime < 2000){ // cmd.mode = 2; // cmd.gaitType = 2; // cmd.velocity[0] = 0.2f; // -1 ~ +1 // cmd.bodyHeight = 0.1; // cmd.footRaiseHeight = 0.1; // // printf("walk\n"); // } // if(motiontime > 0000 && motiontime < 3000){ // cmd.mode = 1; // cmd.bodyHeight = -0.2; // } // if(motiontime > 3000 && motiontime < 6000){ // cmd.mode = 1; // cmd.bodyHeight = 0.1; // } udp.SetSend(cmd); } int main(void) { std::cout << "Communication level is set to HIGH-level." << std::endl << "WARNING: Make sure the robot is standing on the ground." << std::endl << "Press Enter to continue..." << std::endl; std::cin.ignore(); Custom custom(HIGHLEVEL); InitEnvironment(); LoopFunc loop_control("control_loop", custom.dt, boost::bind(&Custom::RobotControl, &custom)); LoopFunc loop_udpSend("udp_send", custom.dt, 3, boost::bind(&Custom::UDPSend, &custom)); LoopFunc loop_udpRecv("udp_recv", custom.dt, 3, boost::bind(&Custom::UDPRecv, &custom)); loop_udpSend.start(); loop_udpRecv.start(); loop_control.start(); while(1){ sleep(10); }; return 0; } ```

And I show the point of edited source.


    cmd.led[0].r = 255;
    cmd.led[0].g = 0;
    cmd.led[0].b = 0;
        cmd.mode = 2;
        cmd.gaitType = 2;
        cmd.velocity[0] = 0.4f; // -1  ~ +1
        cmd.yawSpeed = 2;
        cmd.footRaiseHeight = 0.1;
        // printf("walk\n");

I received the state (IMU, motor angle). But LED didn't flash and Motor Didn't move .

DSC_6094

Thanks.

devemin

suiduck commented 2 years ago

We have the same issue as @devemin. We tried all examples but none of them work as expected, although UDP connection seems work fine and is able to receive the values from IMU. We tried to run the examples in the internal Raspberry and from an external device through an Ethernet cable, but both are not working. Is there something tricky we missed? Please help. Thanks.

我們是大學的研究部門,同樣遇到問題。程式能收到UDP發出來的IMU數值,但是機器狗對發出的CMD完全沒有反應。我們嘗試用內建的樹莓派及網線接駁另一台電腦執行示範程序,兩者同樣失敗。請問我們是否遺留了什麼?請幫忙,謝謝。

TrivasZhang commented 2 years ago

Please make sure that the Go1 is an EDU version.

suiduck commented 2 years ago

Please make sure that the Go1 is an EDU version.

It should be the Edu version as our University bought the Go1 for a while and we have the development docs. And as I remembered Unitree team members Ackles and Irving (sorry if I misspell their names) told us we can ask in here if we got development problems. Thanks.

TrivasZhang commented 2 years ago

OK, let check it one by one.

  1. Use methods at Go1_update to check versions. A screenshot is good.
  2. Is it EDU version?
  3. After reboot, can this robot auto standup and control by gamepad? This will diagnose if the sport mode still works.
  4. $ cd ~/Unitree/autostart/sportMode $./bin/Legged_sport -v Then check the sport mode version. It should seems like _Leggedsport version:x.xx I need this version to assure the according firmware version.
  5. Can the origin sdk examples work? You can find it at ~/Unitree/sdk/unitree_legged_sdk
  6. When tried the SDK, please quit sport mode to normal node, then run _examplevelocity to check if low-level control work.
suiduck commented 2 years ago

OK, let check it one by one.

  1. Is it EDU version?
  2. After reboot, can this robot auto standup and control by gamepad? This will diagnose if the sport mode still works.
  3. $ cd ~/Unitree/autostart/sportMode $./bin/Legged_sport -v Then check the sport mode version. It should seems like _Leggedsport version:x.xx I need this version to assure the according firmware version.
  4. Can the origin sdk examples work? You can find it at ~/Unitree/sdk/unitree_legged_sdk
  5. When tried the SDK, please quit sport mode to normal node, then run _examplevelocity to check if low-level control work.

Thanks for your prompt reply. We will go through the process you suggested.

Just a quick question, our professor just reminded me he downloaded the firmware and packages from Unitree website and updated the robot last month. Knowing that we got some exclusive materials for the edu version, would the firmware and packages downloaded from the public website (it doesn’t specify whether the updates are for air, pro, or edu) mess things up? Thank you.

TrivasZhang commented 2 years ago

The update about firmware and software are not distinguish AIR or EDU version. The version message is flash loaded when manufactured, and upper software has different reaction to different version. Did the low-level works before professor upgrade the firmware?

TrivasZhang commented 2 years ago

Use methods at Go1_update to check versions. A screenshot is good.

Affonso-Gui commented 2 years ago

I was also having troubles with this. However, the robot seemed to work fine when setting the levelFlag to 0.

    cmd.levelFlag = 0;

It also seems to work with cmd.levelFlag = LOWLEVEL; or cmd.levelFlag = TRIGGERLEVEL; or in fact with anything other than the default HIGHLEVEL value.

@devemin

devemin commented 2 years ago

Hello @Affonso-Gui

I got success to moving with example_walk.cpp (High-level) !! Grateful thanks!

But example_position / velocity / torque was not worked.

Can you give me some advice ? Thanks.

[supplementary explanation]

I added 'cmd.levelFlag = 0; (or LOWLEVEL or TRIGERLEVEL )' at Line No.64 in example_position.cpp. (and I tried 'cmd.motorCmd[FR_0].mode = 0x0A; ( or 0x00) ' )

But It is not work.

https://github.com/unitreerobotics/unitree_legged_sdk/blob/376b4f7d874ac9a42bed9099d2dab217a79eeb0e/examples/example_position.cpp#L64

Affonso-Gui commented 2 years ago

Actually I haven't tried the other examples yet, but I'll have a look!

TrivasZhang commented 2 years ago

When command with low-level control, please make sure the robot has quit sport mode, and command with high-level control, please make sure the robot is under sport mode.

devemin commented 2 years ago

@TrivasZhang

Hello.

In the Go1 documents, No description about how to change the mode (sport / normal). It confuse me.

Could you tell me about how to change the mode ?

(And maybe Unitree should modify or add the document :-) )

Masahito

Iron-Fatty commented 2 years ago
  1. switch sport mode(HighLevel mode) to normal mode(LowLevel mode) L2+B (switch to damping mode) L1+L2+START (switch to normal mode) L2+B twice (swtich to damping mode with noise) L2+A twice (switch to stand postion)

  2. switch normal mode(LowLevel mode) to sport mode(HighLevel mode) L2+B (switch to damping mode) L1+START (switch to sport mode)

devemin commented 2 years ago

@Iron-Fatty I got it, thanks.

I tried this. When I pushed the button L1+L2+START, the robot was quiet.

And I executed 'sudo ./example_position ', But It was not work.

I think this is a function limitation resulting from differences in product lineup models maybe. (I am using Go1 pro. Maybe low-level mode need Edu ).

I will use High-level mode. Thank you!