ROBOTIS-GIT / Dynamixel2Arduino

DYNAMIXEL protocol library for Arduino
Apache License 2.0
88 stars 55 forks source link

Non blocking sync read / bulk read / read in general #55

Open drachezoil opened 4 years ago

drachezoil commented 4 years ago

Hi,

I have 30ish XM dynamixels to control and I try to find easy way to pull actual position and hardware errors on all of them(2 separate actions) I am using sync read on a teensy 4.1 to do that. Using the exact same functions than the example from the library. I am getting a lot of "[SyncRead] Fail, Lib error code: 0" meaning I don't have libs error because of the 0 but I also don't have any responses from the dynamixels, recv_cnt = 0. Some time that works and I get responses, most of the time I get this error. Do I do something wrong? should I increase the timeout value? I am not sure if it's a problem or not but for the moment I think the sync read function should be a non blocking one, sending the request then running a listener on the background until the packets have been all received then setup a flag that we can check to then read the values. On the SDK they have a similar approach: https://emanual.robotis.com/docs/en/software/dynamixel/dynamixel_sdk/sample_code/python_sync_read_write_protocol_2_0/

groupSyncWriteAddParam() function stores the Dynamixel ID and its LEN_PRO_GOAL_POSITION bytes goal position dxl_goal_position to the syncwrite target Dynamixel list.

groupSyncWriteTxPacket() function sends an instruction to the Dynamixel #DXL1_ID and #DXL2_ID at the same time through #port_num, making it possible to write same pre-listed length bytes to same pre-listed address. The function checks Tx/Rx result. getLastTxRxResult() function gets it, and then printTxRxResult() function shows result on the console window if any communication error has been occurred.

groupSyncWriteClearParam() function clears the Dynamixel list of groupsyncwrite.

groupSyncReadTxRxPacket() function sends an instruction to the Dynamixel #DXL1_ID and #DXL2_ID at the same time through #port_num port, making it possible to read same pre-listed length(LEN_PRO_PRESENT_POSITION) of bytes from same pre-listed address(ADDR_PRO_PRESENT_POSITION). The function checks Tx/Rx result. getLastTxRxResult() function gets it, and then printTxRxResult() function shows result on the console window if any communication error has been occurred.

groupSyncReadIsAvailable() function checks if available data is in the groupsyncread data storage. The function returns false if no data is available in the storage.

groupSyncReadGetData() function pop the data received by groupSyncReadTxRxPacket() function out. In the example, it stores LEN_PRO_PRESENT_POSITION byte data got from ADDR_PRO_PRESENT_POSITION address of DXL1_ID andDXL2_ID DYNAMIXEL.

groupSyncReadClearParam() function clears the Dynamixel list of groupsyncread.

Thank you for your help

ROBOTIS-Will commented 4 years ago

Hi @drachezoil , I'm not sure how you connected DYNAMIXEL to Teensy, but it could be the timing issue of your direction switching. DYNAMIXEL is asynchronous communication that can only listens or speak at a time. Also, if you are using TTL(3pin) DYNAMIXEL, please note that DYNAMIXEL uses 5V level TTL signal. 3.3V may be just enough for High level, but cannot guarantee its stability. Thank you.

drachezoil commented 4 years ago

Hi Will, Completely forgot that for sure. But I don't think it's the problème. I a using rs485 communication, no 3.3v problem. For example if I sync read the hardware error item on 30 dynamixel every 10s, that works for 5-6 time at the beginning then little by little only one dynamixel give me answers. Is that an half duplex asynchronous communication problem? In this case sync read shouldn't exist because more than one slave will always collide no? When you do a sync read each servo have 10ms(timeout) to answer before the next one start emitting? In this case I could increase the timeout to make sure each of them have enough time to answer but that mean we definitely need a non blocking answer pulling

ROBOTIS-Will commented 4 years ago

Hi, Based on an assumption that you are correctly following the hardware specification of RS-485 communication, when sync read instruction is transmitted, each DYNAMIXEL responds to the controller on their turn and it doesn't take 10ms, but much faster. The controller has to properly collect all the message from each DYNAMIXEL until the end(or timeout) to transmit the next packet (because it is asynchronous). If you have devices to visualize these signal (such as logic analyzer or oscilloscope), you might be able to see where the communication error occurs. Thank you.

drachezoil commented 4 years ago

I don't have any logic analyzer yet, soon. In the meantime I decided to read the error only when I don't do any critical task with a normal readfromcontroltable. I have an other question, do we get a status packet back of each dynamixel when we do a syncwrite? If yes I could pull the error flag(alert bit) to then check only the ones that may have a problem. What will be the best solution for that? From what I understand on the syncWrite function you call this line: pport->write(p_packetbuf, info_txpacket.generated_packet_length); is that waiting for any answer or just transmitting and not receiving?

ROBOTIS-Will commented 4 years ago

Unlike write instruction, syncWrite does not collect response packet as DYNAMIXELs do not return status packets when receiving the syncWrite instruction. The timeout in the write() function is to prevent holding the tx buffer if there's an error.

LegacyMecha commented 3 years ago

I've been dealing with 20+ Dynamixels on Teensy 4.0 too and works great without Sync Read. Maybe possible that your RX serial buffer is getting overflowed? If you don't read the incoming data fast enough, just a few Dynamixel's data will fill it up fast. Just a thought. Also, try higher baud rate (2mb+) and set the Dynamixels "Reply Delay" to 20us (value of 10), instead of the default 500us (250).

Consider if you are at 2mb baud rate, you can still command one by one and be pretty fast, probably send 30 commands in less than 10ms maybe (haven't done the actually calculation, just an estimate) if you set the "Reply Delay" down to 20us.

I also only send commands to Dynamixels that have updated data to send.

Just some ideas. Hope it helps.