I2C inefficiency caused by the use of read windows with REV Expansion Hubs
rbrott opened this issue · 14 comments
The implementation of I2cDeviceSynchImplOnSimple
used to wrap LynxI2cDeviceSynch
instances for all REV I2C devices will read extra registers according to the read window that are never used. This isn't really problematic except that the duration of I2C read commands are linear, not constant in the number of registers.
By bypassing the read window, one can achieve fairly significant speedups. In particular, here is the difference between an unoptimized and optimized (read window-less) BNO055 Euler angle read: (This was generated using https://github.com/acmerobotics/relic-recovery/blob/master/TeamCode/src/main/java/com/acmerobotics/relicrecovery/opmodes/test/ExpansionHubBenchmark.java)
To remedy this, one can subclass I2cDeviceSynchImplOnSimple
and use it to construct I2cDeviceSynch
instances without read windows:
public class BetterI2cDeviceSynchImplOnSimple extends I2cDeviceSynchImplOnSimple {
public BetterI2cDeviceSynchImplOnSimple(I2cDeviceSynchSimple simple, boolean isSimpleOwned) {
super(simple, isSimpleOwned);
}
@Override
public void setReadWindow(ReadWindow window) {
// intentionally do nothing
}
}
I2cDeviceSynch optimizedI2cDeviceSynch = new BetterI2cDeviceSynchImplOnSimple(
new LynxI2cDeviceSynchV1(AppUtil.getDefContext(), module, bus), true);
I'd like to see you repeat your benchmark using firmware 1.8.2.
I would, but unfortunately I no longer have access to a hub for testing. It'd be great if others could reproduce my initial results with 3.x/1.7.2 and see how much has changed in 4.x/1.8.2. Given that I2cDeviceSynchImplOnSimple
was not changed, I suspect this issue still exists although LynxI2cDeviceSynchV2
will help reduce the overall I2C latency.
It appears that this issue is still present with 4.x/1.8.2. Here are the results for a similar benchmark measuring IMU Euler angle reads (i.e., BNO055IMU.getAngularOrientation()
):
(courtesy of @Epsilon10)
Here is the benchmark code.
Thanks for refreshing this post. Although I only use the one internal I2C device, our latencies are going up, so I'll be interested to see the impact of this tweak. Have your studies shown any other methods for reducing cycle times?
The main other trick is bulk input reads. This feature exists in the current SDK although you have to use the command directly (LynxGetBulkInputDataCommand
). Alternatively, you can use a library like RE2. This command returns the state of analog inputs, digital inputs, and encoders for a single hub.
Unfortunately, there's no equivalent for bulk writes (aside from LynxSetAllDIOOutputsCommand
). I haven't found a good way to minimize write times aside from only issuing them when absolutely necessary. Certain actuators only need new commands every few cycles.
I also recommend that teams have a separate thread purely for hardware commands to ensure maximum utilization of the bus.
Finally, if you're very adventurous, you could remove the USB-level lock and replace it with a hub-level lock (as suggested by this comment) and theoretically send commands concurrently with a two-hub configuration.
Great info... thanks.
Finally, if you're very adventurous, you could remove the USB-level lock and replace it with a hub-level lock (as suggested by this comment) and theoretically send commands concurrently with a two-hub configuration.
But, that would require that both Hubs be connected via USB, though. (Which is allowed according to GDC btw)
I've implemented both the faster I2C (for my IMU only) and bulk reads for my 6 encoders.
I've been able to lower the average teleop loop cycle time from 65ms to about 24mS.
This is a pretty respectable improvement, especially when the loop time bounces up.
It used to max out at about 130ms, and now it never gets above 90ms
Thanks for the research and libs guys.
@gearsincorg you could get that loop time down even further if REV implements bulk I2C reads (some pulling apart of the Hub interface software indicates that may be a future feature) and/or bulk writes. The fact of the matter is, every command takes about 3ms to send over the bus and then have an ack come back. So every hardware call you make adds a minimum of 3ms to your loop time.
Could someone lay out how to implement these improvements to someone who doesn't understand the internal working of the SDK? Our robot has 8 motors, 7 with encoders, so speeding up reading encoder values could be quite useful for our TeleOp and Auto.
@qwertychouskie check out the bulk data example OpMode in RevExtensions2
@FROGbots-4634 Is the isMotorAtTargetPosition
in the example just the inverse of isBusy
changed to use bulk data reads, or is there some subtle difference?
@qwertychouskie heh, that thought never even crossed my mind when I was writing the library, lol. Well, by taking a look at LynxDcMotorController it seems that isBusy()
just returns the opposite of isAtTargetPostition()
Fixed in v5.3