ROBOTIS-GIT / OpenCR

Software for ROS Embedded board (a.k.a. OpenCR). OpenCR means Open-source Control Module for ROS.
Apache License 2.0
384 stars 238 forks source link

turtlebot3_setup_motors: maybe corrupted servos - baud rate issues #148

Closed KurtE closed 5 years ago

KurtE commented 5 years ago

I was/am setting up a Turtlebot3 burger to try out some ROS2 stuff. So I needed to setup the motors as I did not have them in velocity mode...

After I tried to do the update of left and right motors (both were previously set to ID 1 and ID 2), the servos became corrupt, and the DXL output was bad. One of them was not returning valid messages. So I rigged up an OpenCM board and was able restore the firmware... Again not exactly sure what happened.

Note: this was mostly user error: I did not see the section in the Turtlebot3 e-manual which was under FAQ (I looked under Setup)

Maybe there should be some warning message that shows up in this sketch saying that only one servo should be connected. Especially if your function findMotor finds more than one... Which looks like it leaves tb3_id set to the last one found.

As if it found 1 and 2 (my case), and I tried to do a setup left motor, it will then set the ID of servo 2 to be number 1, which then gives us two number ones... Which then give you errors.

Also wonder about the set code:

bool setupMotorLeft(void)
{
  CMD_SERIAL.println("Setup Motor Left...");

  if (tb3_id < 0)
  {
       CMD_SERIAL.println("    no dxl motors");
  }
  else
  {
    write(portHandler, packetHandler2, tb3_id,64, 1, 0);
    write(portHandler, packetHandler2, tb3_id, 7, 1, 1);
    tb3_id = 1;
    write(portHandler, packetHandler2, tb3_id, 8, 1, 3);
    portHandler->setBaudRate(1000000);
    write(portHandler, packetHandler2, tb3_id, 10, 1, 0);
    write(portHandler, packetHandler2, tb3_id, 11, 1, 1);
    CMD_SERIAL.println("    ok");
  }
}

That once you setup the id that was 2 to now be 1: write(portHandler, packetHandler2, tb3_id, 7, 1, 1);

Will that servo get the next packets which are still being sent to 2?

Also wonder if when you setup the baud rate to 1000000, you do quickly tell the system to change the baud rate to 1000000, but does the servo need some time to switch it's baud? Maybe not.

Again mostly user error, but maybe need to do a little pass through to help other users to minimize this. Especially since if they need to do this and their TB3 is fully assembled it may be hard to get to the servo wires...

KurtE commented 5 years ago

I don't like to just complain about things ;) so I did a quick update to the sketch that hopefully helps others to not make some of the same mistakes that I did.

https://github.com/ROBOTIS-GIT/OpenCR/pull/149

routiful commented 5 years ago

Thanks to contribution! But I don't understand that mean.

Will that servo get the next packets which are still being sent to 2?

After ping dynamixel motor and get id, torque off -> change id -> set new id (1) -> change baudrate -> set new baudrate(1000000) -> change drive mode -> change operating mode.

That procedure seems to be not occured problem. But, I'm appreciate your PR and check it as soon as possible :)

KurtE commented 5 years ago

@routiful (and @opusk) , Sorry I meant to remove that comment as yes the code sets the variable to the new ID right after it outputs the register write that sets the ID to 1 or 2... So that part works.

The main problem I ran into was self induced. This is, I was building the burger, and partially setup the servos (Set IDs 1 and 2 and baud rate). I built the ROS2 code, tried running it and the wheels did not turn... So figured I screwed up... Wondered if the motors needed additional configuration stuff. So did quick look in E-Manual and did not find anything obvious (later found information in FAQ section)... But when I looked at the OpenCR Arduino install I found this sketch which looked promising.

So, I unplugged the USB connection on the OpenCR from the UP board and connected to my PC, and downloaded this sketch and ran it. Then ran setup Left motor... I believe it listed both servos at the start, and I said update... So here is where it then took Servo 2 last one found and the one remembered, and then changed it's ID to 1 which now conflicts with the existing 1... And now it tries to write the rest of setup commands to servo 1, and the two two servos get confused and stop working... I had to manually undo the servo connections, in this case setup an OpenCM9.04 board with default firmware and do a firmware recovery on both servos and start over...

So I then updated the sketch to first try to find the wanted servo id (1 or 2) and if found it uses it. It tries to ping that servo id on all of the baud rates and see if it can find it. Note: during the ping phase it also tries to confirm that there are not two of those servos with the same ID (example what happens if you have two servos with same id at 57600 and 1000000 and then set the 57600 one to 1000000...

Also I updated the test functions, to show the right motor name. Before it was always outputting one hard coded name... Also changed the test function, to not rely on first running a setup function, but instead tries to ping that servo at the expected baud rate...

routiful commented 5 years ago

I clearly understand :) Thank you for your kindly comment.

turtlebot3_setup_motor example is to setup motor before assemble turtlebot3 and this example restricts connection for ONE motor not multiple due to ID.

I couldn't find any problem when I use this example (Of course, I needed unplugged one motor) But the code can be better.

I tested it but have some problem. I connect two Dynamixel (XM series, ID 1, 2 and baudrate 57600) to OpenCR. But it gives to me failed to write message.

1. setup left  motor
2. setup right motor
3. test  left  motor
4. test  right motor
>> Do you really want to setup ? y/n : yes
setup.... left
Find Motor...
    ... SUCCESS
    [ID: 1 found at baud: 57600]
Setup Motor Left...
[TxRxResult] Communication success.
Fail to write!
[TxRxResult] Communication success.
Fail to write!
[TxRxResult] Communication success.
Fail to write!
[TxRxResult] Communication success.
Fail to write!
[TxRxResult] Communication success.
Fail to write!
    ok
KurtE commented 5 years ago

Sorry, looks like a line of code somehow was missed, that if the servo was found by ping at 57600, it still checked at 1000000 to make sure it should not create a conflict...

So fixed. Also while testing, I thought I would test again some of my open PR on OpenCM9.04 serial code, so made the sketch work on it as well...

routiful commented 5 years ago

Great! It works perpect. I accept PR and close this issue :) Thanks again!

limn3 commented 1 year ago

I clearly understand :) Thank you for your kindly comment.

turtlebot3_setup_motor example is to setup motor before assemble turtlebot3 and this example restricts connection for ONE motor not multiple due to ID.

I couldn't find any problem when I use this example (Of course, I needed unplugged one motor) But the code can be better.

I tested it but have some problem. I connect two Dynamixel (XM series, ID 1, 2 and baudrate 57600) to OpenCR. But it gives to me failed to write message.

1. setup left  motor
2. setup right motor
3. test  left  motor
4. test  right motor
>> Do you really want to setup ? y/n : yes
setup.... left
Find Motor...
    ... SUCCESS
    [ID: 1 found at baud: 57600]
Setup Motor Left...
[TxRxResult] Communication success.
Fail to write!
[TxRxResult] Communication success.
Fail to write!
[TxRxResult] Communication success.
Fail to write!
[TxRxResult] Communication success.
Fail to write!
[TxRxResult] Communication success.
Fail to write!
    ok

Hi, I am getting this same error. What did you do to resolve it?

ROBOTIS-Will commented 1 year ago

@limn3 If you have connected multiple DYNAMIXEL to OpenCR during the setup process, you may get this error. Please connect only one DYNAMIXEL at a time for the motor setup example. Thank you.

shiba-8ro commented 1 year ago

@limn3 Both of your XM430s could be ID1. Turtlebot3 requires the right motor to be set to ID2. If you connect multiple motors with the same ID to OpenCR, they will disappear.