Page 2 of 3 FirstFirst 123 LastLast
Results 11 to 20 of 21

Thread: reading entire Dynamixel table in one packet

  1. #11
    Join Date
    May 2016
    Location
    USA
    Posts
    145
    Images
    12
    Rep Power
    23

    Re: reading entire Dynamixel table in one packet

    Jwatte, I was thinking about what you are saying last night, just didn't get around to experimenting with it yet. Basically, instead of a long wait, have a short wait and keep reading new bytes until the full packet is received. I'm new to doing this kind of byte-level stuff over serial ports, so I'm learning as I go. I will try to implement this tonight if I have time.

  2. Re: reading entire Dynamixel table in one packet

    There are indeed a lot of things to consider if you want fast reading of a lot of data.
    The way to read data that Jwatte suggests is indeed much needed to avoid waiting for nothing.

    On the host, there are delays that can be created by the OS interrupting your task: on a platform with limited ressources (embedded computer) it might play a big role.

    Then the driver has buffers and timeout to flush them when they are not full. This is a big problem with FTDI chips, that can be mitigated by setting the buffer size low and the timeout to the lowest value (still 1ms...) (see http://knowledge.digi.com/articles/K...-port-settings for example).

    Then the USB layer sends the data in Bulk transfer mode (for FTDI an USB2AX alike), which has a lower priority than some other transfer modes, meaning that if you have other things transmitting a lot on the USB controller (a controller usually serves multiple USB ports, and in laptops some of these can be used internally), the lowly virtual serial packets will not move as fast as possible. So the more stuff you have on the USB ports of the machine, and the more talking they do, the worst your timing repeatability and overall latency will be. When checking for performances of other parts of the system, remove all other USB devices to cut the noise down.

    The adapter itself can have some latency, for example the USB2AX parses all the trafic coming from the Host to see if there are commands aimed at it (it behaves like a limited Dynamixel device for some things), but this is comparatively small (maybe a few µs tops).

    Sending stuff on the bus takes a known time: take the baud rate, and divid by 10, that's the number of bytes you can send/receive in a second (because the bus uses 8N1 encoding, which transmits 8 bytes, plus a start bit and 1 stop bit, so 10 signs per character).
    So if you do not use the fastest baud rate, you're losing microseconds or maybe even miliseconds...
    At 1Mbps, you can transmit 1 char in 10us, so a 60 bytes sync_write will take 0.6ms just to get out on the bus (if there aren't any other delays)...

    Then the servo takes some time to parse and validate the packet and start queuing up the response data. This will depend on the lenght of the packet, and the command itself (some take more time to be processed). This usually takes about 10 to 25us, maybe more on very complex packets (reading the full table might be in that category).

    During the time it responds, the AX servo can stop for a moment between two char while the motor control task is done. This can add up to 130us delay to the response of the servo. This task is done once every miliseconds, so it can only affect a servo once every ms.

    Then the data goes the other way, and can have the same problems. The USB2AX transmits data from the servo to the host directly, as fast as possible, with as little latency as possible. The FTDI chips might sit on data for some time, waiting for more to come...

    Then data goes back up to the host, lingering in a buffer of the driver/OS, until your application finally reads it.
    The way this buffer is accessed can make a lot of differences depending on the OS and libs used. Checking the number of bytes available might take as long as to get one (and manage the error if there were none), getting one might take as long as getting 20... then reading that data byte by byte might take some more time (I'm looking at you Python)... check your code for preformance, you might be able to gain some more here, mostly on slow embedded plateforms.

    As mentionned, some precautions have to be taken on the servo side to make sure you're getting acceptable performances.
    - Return delay time : set to zero. It's an artificial delay that the servo can wait before responding in case the thing that is talking to it is very slow. And it's set to 250 by default (1ms delay before responding, the support website http://support.robotis.com/en/ is still wrong about saying it's 2us per unit: tests show it's 4us per unit).
    - baudrate : set to 1mbps. Technically you could push to 2mpbs, as jwatte does, but most adapter do not support such speed (USB2dynamixel and USB2AX included).
    - Status return level : if you plan on ignoring the return packet when sending write_data commands, then just tell the servo not to send them, that's something les to think about. There are no status packet when sending broadcast commands (like sync_write) so it might not matter to you.

    Check your cables as the timeout delays will kill any perf you gained elsewhere tenfold, plus you will get unreliable results.

    Then in your code, you can optimize the way access to the servo is done.
    For writing positions (writing values at the same spot on multiple servos), just sync_write. Unless you want to check that every transaction has not raised any error, in which case abandon the idea of doing things fast...

    For reading stuff, the best thing right now is to use the sync_read of the USB2AX or the similar "one packet to read multiple servos" on the Arbotix, or maybe others. The time it takes to read something from a servo is very largely dominated by the USB transaction, which in itself does not vary noticably based on the quantity of data exchanged. Reading 1 byte or the whole table will have the same USB overhead, and it's still the same for one sync_read operation which can read many bytes from 25 servos.

    A loop that reads and writes from every of the sevos of a robot can take very little time with sync_write + sync_read. All the more if you use sync_read asynchronously (ie send the packet, go do something else, then come back to read the result). If you do this: send in one big chunk the sync_write and sync_read packets (can save some more compared to writing the two packets one after the other, and even more compared to writing byte by byte), then go do something else (like computing IK from the data collected with the previous sync_read), and when you're finished start again, then you can effectively take the time lost with communications down to 2~3ms, with a loop time of maybe 6 to 10ms for a full robot.

    Some tests I did a few years ago with the USB2AX and the slightly updated Dynamixel SDK : https://docs.google.com/document/d/1...it?usp=sharing

    You can also use multiple lines in parallele. And mixed with the previous trick, you can read a HUGE number of servos in very little time... On the USB2AX reading 6 bytes and writing 4 each loop, it looked like 8~12 servos per line would be the sweet spot.
    In my Xachikoma robot I used 2 lines (it was also easier to wire that way), and the Poppy Humanoid too ( poppy-project.org ).

    If you are using the USB2Dynamixel however, you can not get to such fast loops. But you can still do some fun tricks to speed things up.
    For reading things from many servos, the only thing that you actually have to avoid is the communication on the bus getting corrupted by having the servo and USB2dynamixel try to talk on the bus at the same time. Anything else if fair game. And since you know that the resonse of the servo will have passed on the bus in less than Host to device delay + device write to bus delay + servo parse delay + servo resonse delay + servo motor control delay...
    By sending read commands one after the other with a small delay in between, and letting the return packets pile up in the driver's input buffer before reading them all at once at the end, you can interleave the USB overheads, effectively decreasing the time it took to get all the data out of the sevos.
    The delay should be long enough to make sure the data is out, but not long enough for the return packet to be back all the way up to the host. I did it with about 0.4ms successfully on a Beagleboard xM running python code, so not the fastest thing around.
    When reading all the packets, you just have to match each with the servo it concerns and know what register adress were queried. It might require to move away from the "one servo - one command sent - one response received" paradigm though.

    There, that's about most of what I have gathered on the subject. I really should have written that low-latency communication guide I've been thinking about for years... :/
    Last edited by Xevel; 05-16-2016 at 05:29 PM.
    ---
    Personal blog: http://xevel.org
    USB2AX documentation: http://xevelabs.com

  3. #13
    Join Date
    Jan 2008
    Location
    Norway, Stavanger
    Posts
    790
    Images
    276
    Rep Power
    87

    Re: reading entire Dynamixel table in one packet

    Very interesting topic indeed. Xevel's post make this thread sticky-worthy. Looking forward to read more about your findings.
    Kåre Halvorsen aka Zenta
    ---------------------------------
    Zenta's YouTube channel
    Zenta's Blog
    Zenta's Instagram

  4. #14
    Join Date
    May 2016
    Location
    USA
    Posts
    145
    Images
    12
    Rep Power
    23

    Re: reading entire Dynamixel table in one packet

    Wow, Xevel my mind is blown by your post. So much there to digest and comment on, when I have more time. I have to say, this community may be small these days, but I am truly inspired by the depth of knowledge and willingness to share displayed here.

    Even though I will likely abandon the "naive" approach of waiting N milliseconds before reading, I decided to still go ahead and do some performance testing with that approach using the USB2AX. Again, this is AX full control table read (50 bytes) at 1Mbps.

    Here is some code just so that it's clear what I'm talking about:
    Code:
        public synchronized StatusPacket sendInstruction(InstructionPacket instruction) throws DynamixelException {
            send(instruction.getPacketBytes());
            sleep(receiveWaitTimeMillis);
            return new StatusPacket(instruction, receive());
        }
    With the USB2Dynamixel, I was using a 20ms timeout, and I was getting greater than 99.99% reliability, but I was getting an occasional failure on a longer run that I tried.

    It turns out that the USB2AX is ridiculously fast. Ludicrous speed. Maybe it's more accurate to say the USB2Dynamixel is ridiculously slow, but the speed difference is dramatic. With the USB2AX, I was able to run the same benchmark that was 99.99% reliable with the USB2Dynamixel at 20ms and get 100% reliability from the USB2AX at 15ms, then 10ms, then 5ms, then 2ms. I don't really feel its necessary to go any further with this approach. Point has been made.

    I also wrote code to use the method jwatte described, and I did a little testing, but I don't have enough data to share yet. I'm cobbling together some new classes in my mini benchmarking suite to be able to run various types of reads over a period of time and calculate average total read time. Should have that testing wrapped up tomorrow night, and I'll have a good idea of exactly how fast these devices are in different scenarios.

    I may need to go to nanoseconds to benchmark the USB2AX! Beautiful piece of hardware.

    When I have a bigger assembly going, I will test the SYNC_READ as well. I'm curious to see how that performs vs reading each individually. Also, one final note since it's been mentioned a couple times, Return Delay Time is still default (250), will change that to 0 when I implement WRITE_DATA, probably tomorrow. Also curious to see if that ends up mattering much in terms of total read time.

    Thanks again to all who have commented. You folks are brilliant.
    Last edited by _ADAM_; 05-17-2016 at 10:47 AM.

  5. Re: reading entire Dynamixel table in one packet

    You're welcome

    Quote Originally Posted by _ADAM_ View Post
    Also, one final note since it's been mentioned a couple times, Return Delay Time is still default (250), will change that to 0 when I implement WRITE_DATA, probably tomorrow. Also curious to see if that ends up mattering much in terms of total read time.
    Yeah, I do think that removing the 1ms delay in the servo response might help xD


    To be fair to the USB2Dynamixel, I think that you could have gotten better results with it by adjusting the driver settings. With an internal timeout and buffers set to the minimum, I used to get pretty reliable reads at <2ms. But then with the USB2AX I could still go lower than that...
    ---
    Personal blog: http://xevel.org
    USB2AX documentation: http://xevelabs.com

  6. #16
    Join Date
    May 2016
    Location
    USA
    Posts
    145
    Images
    12
    Rep Power
    23

    Re: reading entire Dynamixel table in one packet

    Didn't get too much time to spend on this tonight, but I did run some timing tests using the new sendInstruction implementation.

    Test setup is three AX-12+ on a bus with 1Mbps baud rate and reading the entire 50 byte table. Return Delay Time is 0.

    Here is a receive code snippet:
    Code:
            byte[] status = new byte[instruction.getReturnPacketLength()];
            int bytesReceived = 0;
            long startTime = System.nanoTime();
            while (bytesReceived < status.length && (System.nanoTime() - startTime) < receiveTimeoutNanos) {
                byte[] bytes = receive();
                if (bytes != null) {
                    System.arraycopy(bytes, 0, status, bytesReceived, bytes.length);
                    bytesReceived += bytes.length;
                }
            }
    I now include the duration in nanos, which I need for the timeout anway, in the status return object. This makes it easy to benchmark.

    Here are the numbers.

    USB2AX
    fastestTimeMillis = 0.742871
    slowestTimeMillis = 1.263982
    averageTimeMillis = 1.0172655466666665

    USB2Dynamixel
    fastestTimeMillis = 1.008165
    slowestTimeMillis = 16.386709
    averageTimeMillis = 8.790776

    These numbers validate the times that I had settled on using the send/wait/receive approach (2 millis for USB2AX and ~20 millis for USB2Dynamixel). And as Xevel mentioned, I should also state that the USB2Dynamixel driver has not been tuned.
    Last edited by _ADAM_; 05-18-2016 at 10:00 PM.

  7. #17
    Join Date
    May 2016
    Location
    USA
    Posts
    145
    Images
    12
    Rep Power
    23

    Re: reading entire Dynamixel table in one packet

    Here are the final numbers I am going to post on this for now. I'm moving on to other things, but I still want to benchmark SYNC_READ vs sequential reads when I have an actual robot to work with.

    Setup: Windows 8, USB2AX, three AX-12+ on the bus, 1Mbps, Return Delay Time is 0.

    address = 46, numAddresses = 1
    fastestTimeMillis = 0.065299
    slowestTimeMillis = 0.4827
    averageTimeMillis = 0.3515166666666666

    address = 30, numAddresses = 2
    fastestTimeMillis = 0.292949
    slowestTimeMillis = 0.534427
    averageTimeMillis = 0.3676586999999999

    address = 36, numAddresses = 8
    fastestTimeMillis = 0.380014
    slowestTimeMillis = 0.600494
    averageTimeMillis = 0.4562476633333337

    address = 0, numAddresses = 50
    fastestTimeMillis = 0.910088
    slowestTimeMillis = 1.144908
    averageTimeMillis = 0.9971423900000002

    As you can see, it's fast, but it gets slower the more data you read. There is not a big difference between reading, one, two or all eigth "Present" values. Reading the whole table takes more than twice as long to read than reading the eight Present values. I don't see any reason to read the whole table in one packet unless it's for logging or displaying purposes. Reading the chunk of Present values gives the most bang for the buck.

    Reading multiple values as single bytes doesn't make much sense either. Reading the eight Present value addresses individually would take six times as long as reading them at once.

    Also, it's interesting that reading a single byte can be crazy fast sometimes (0.065 millis!!).

    I'm happy with these numbers. If they generally hold for a larger bus, I think it's plenty fast enough for communication speed to not affect robot performance. I was definitely a bit concerned with the times I was seeing for the USB2Dynamixel.

    I will revisit later when I have something resembling a robot.
    Last edited by _ADAM_; 05-18-2016 at 10:16 PM.

  8. Re: reading entire Dynamixel table in one packet

    Something is wrong in your test code, 65us to read a value is not possible.
    Just to output the read_data packet (8 bytes) on the bus at 1mbps already takes 80us.

    Could be that the function returned prematurely, or that the way time is measured is not accurate, or that there is something left in the input buffer... I did not really analyze the details of your piece of code so I don't know for sure, sorry.


    Actually, a note on latency benchmarking: personally I find that the only reliable way to get acurate timing of fast operations is to measure them externally.
    When I benchmark a piece of communication code like that, I look at the bus with a logic analyzer (I upgraded to the Saleae Logic Pro 16 at the beginning of the year, it's magical <3 ) and measure the actual time elapsed between the beginning of consecutive packets. But anyway, your test, even if quantitatively inacurate, led you to a valid conclusion.
    Last edited by Xevel; 05-19-2016 at 01:36 AM.
    ---
    Personal blog: http://xevel.org
    USB2AX documentation: http://xevelabs.com

  9. #19
    Join Date
    May 2016
    Location
    USA
    Posts
    145
    Images
    12
    Rep Power
    23

    Re: reading entire Dynamixel table in one packet

    I don't think it's the my code per se, but there could be a glitch in the underlying nano time implementation. I added some logging, and it's only the very first read of the run that records a super fast time. Also, I get a valid response packet.

    If I leave the first iteration out of the averaging, the single address read average nudges up a bit (~9us).

    address = 46, numAddresses = 1
    fastestTimeMillis = 0.039435
    slowestTimeMillis = 0.58257
    averageTimeMillis = 0.3609035622895622


    address = 30, numAddresses = 2
    fastestTimeMillis = 0.290133
    slowestTimeMillis = 0.498576
    averageTimeMillis = 0.3644584646464648


    address = 36, numAddresses = 8
    fastestTimeMillis = 0.349541
    slowestTimeMillis = 0.624309
    averageTimeMillis = 0.45329809090909085


    address = 0, numAddresses = 50
    fastestTimeMillis = 0.894724
    slowestTimeMillis = 1.152591
    averageTimeMillis = 1.010406363636364

  10. #20

    Re: reading entire Dynamixel table in one packet

    Good information,

    FYI - I don't leave home without my Saleae Logic analyzer either

    Click image for larger version. 

Name:	screenshot.jpg 
Views:	201 
Size:	42.9 KB 
ID:	6593

    Helps to verify things, like above shows that simple read of 1 byte, the AX-BUSS takes about .176ms. Plus then you need to add in all of the additional overhead of USB...

    On Odroid C1, if I run test to read in all registers of a servo, I currently read in 10 bytes at a time. If I measure the timings between the start of each read, I see something like 1.2ms... But the actual time on AX-Buss maybe is .2ms... Some of this is overhead in my code, some is libraries...

Thread Information

Users Browsing this Thread

There are currently 1 users browsing this thread. (0 members and 1 guests)

Similar Threads

  1. MX-28 dynamixel error COMM_RXCORRUPT: Incorrect status packet
    By bootstrap in forum DYNAMIXEL & Robot Actuators
    Replies: 1
    Last Post: 08-27-2015, 12:09 PM
  2. Replies: 8
    Last Post: 06-01-2015, 05:22 PM
  3. Question(s) Excuse me, in phoenix code whad does the arccos table mean?
    By maynight in forum Humanoids, Walkers & Crawlers
    Replies: 5
    Last Post: 11-26-2014, 03:40 PM
  4. Dynamixel packet analyzer ?
    By Xevel in forum Software and Programming
    Replies: 34
    Last Post: 10-26-2014, 01:10 AM
  5. Contest Entry Autonomous Foosball Table
    By eski in forum Project Showcase
    Replies: 6
    Last Post: 12-28-2007, 01:24 PM

Posting Permissions

  • You may not post new threads
  • You may not post replies
  • You may not post attachments
  • You may not edit your posts
  •