|
| 1 | +/* Copyright (c) 2019 Phil Malone. All rights reserved. |
| 2 | + * |
| 3 | + * Redistribution and use in source and binary forms, with or without modification, |
| 4 | + * are permitted (subject to the limitations in the disclaimer below) provided that |
| 5 | + * the following conditions are met: |
| 6 | + * |
| 7 | + * Redistributions of source code must retain the above copyright notice, this list |
| 8 | + * of conditions and the following disclaimer. |
| 9 | + * |
| 10 | + * Redistributions in binary form must reproduce the above copyright notice, this |
| 11 | + * list of conditions and the following disclaimer in the documentation and/or |
| 12 | + * other materials provided with the distribution. |
| 13 | + * |
| 14 | + * Neither the name of FIRST nor the names of its contributors may be used to endorse or |
| 15 | + * promote products derived from this software without specific prior written permission. |
| 16 | + * |
| 17 | + * NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS |
| 18 | + * LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
| 19 | + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, |
| 20 | + * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
| 21 | + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE |
| 22 | + * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL |
| 23 | + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR |
| 24 | + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER |
| 25 | + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, |
| 26 | + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE |
| 27 | + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. |
| 28 | + */ |
| 29 | + |
| 30 | +package org.firstinspires.ftc.robotcontroller.external.samples; |
| 31 | + |
| 32 | +import com.qualcomm.hardware.lynx.LynxModule; |
| 33 | +import com.qualcomm.robotcore.eventloop.opmode.Disabled; |
| 34 | +import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; |
| 35 | +import com.qualcomm.robotcore.eventloop.opmode.TeleOp; |
| 36 | +import com.qualcomm.robotcore.hardware.DcMotorEx; |
| 37 | +import com.qualcomm.robotcore.util.ElapsedTime; |
| 38 | + |
| 39 | +import java.util.Iterator; |
| 40 | +import java.util.List; |
| 41 | + |
| 42 | + /* |
| 43 | + This sample illustrates how to use the Expansion Hub's Bulk-Read feature to speed up control cycle times. |
| 44 | + In this example there are 4 motors that need their encoder positions, and velocities read. |
| 45 | + The sample is written to work with one or two expansion hubs, with no assumption as to where the motors are located. |
| 46 | +
|
| 47 | + Three scenarios are tested: |
| 48 | + Cache Mode = OFF This is the normal default, where no cache is used, and every read produces a discrete transaction with |
| 49 | + an expansion hub, which is the slowest approach. |
| 50 | + Cache Mode = AUTO This mode will attempt to minimize the number of discrete read commands, by performing bulk-reads |
| 51 | + and then returning values that have been cached. The cache is updated automatically whenever a specific read operation is repeated. |
| 52 | + This mode will always return fresh data, but it may perform more bulk-reads than absolutely required. |
| 53 | + Extra reads will be performed if multiple identical encoder/velocity reads are performed in one control cycle. |
| 54 | + This mode is a good compromise between the OFF and MANUAL modes. |
| 55 | + Cache Mode = MANUAL This mode enables the user's code to determine the best time to refresh the cached bulk-read data. |
| 56 | + Well organized code can place all the sensor reads in one location, and then just reset the cache once per control cycle. |
| 57 | + The approach will produce the shortest cycle times, but it does require the user to manually clear the cache. |
| 58 | +
|
| 59 | + ------------------------------------- |
| 60 | +
|
| 61 | + General tip to speed up your control cycles: |
| 62 | + No matter what method you use to read encoders and other inputs, you should try to |
| 63 | + avoid reading the same input multiple times around a control loop. |
| 64 | + Under normal conditions, this will slow down the control loop. |
| 65 | + The preferred method is to read all the required inputs ONCE at the beginning of the loop, |
| 66 | + and save the values in variable that can be used by other parts of the control code. |
| 67 | +
|
| 68 | + eg: if you are sending encoder positions to your telemetry display, putting a getCurrentPosition() |
| 69 | + call in the telemetry statement will force the code to go and get another copy which will take time. |
| 70 | + It's much better read the position into a variable once, and use that variable for control AND display. |
| 71 | + Reading saved variables takes no time at all. |
| 72 | +
|
| 73 | + Once you put all your sensor reads at the beginning of the control cycle, it's very easy to use |
| 74 | + the bulk-read AUTO mode to streamline your cycle timing. |
| 75 | +
|
| 76 | + */ |
| 77 | +@TeleOp (name = "Motor Bulk Reads", group = "Tests") |
| 78 | +@Disabled |
| 79 | +public class ConceptMotorBulkRead extends LinearOpMode { |
| 80 | + |
| 81 | + final int TEST_CYCLES = 500; // Number of control cycles to run to determine cycle times. |
| 82 | + |
| 83 | + private DcMotorEx m1, m2, m3, m4; // Motor Objects |
| 84 | + private long e1, e2, e3, e4; // Encoder Values |
| 85 | + private double v1, v2, v3, v4; // Velocities |
| 86 | + |
| 87 | + // Cycle Times |
| 88 | + double t1 = 0; |
| 89 | + double t2 = 0; |
| 90 | + double t3 = 0; |
| 91 | + |
| 92 | + @Override |
| 93 | + public void runOpMode() { |
| 94 | + |
| 95 | + int cycles; |
| 96 | + |
| 97 | + // Important Step 1: Make sure you use DcMotorEx when you instantiate your motors. |
| 98 | + m1 = hardwareMap.get(DcMotorEx.class, "m1"); // Configure the robot to use these 4 motor names, |
| 99 | + m2 = hardwareMap.get(DcMotorEx.class, "m2"); // or change these strings to match your existing Robot Configuration. |
| 100 | + m3 = hardwareMap.get(DcMotorEx.class, "m3"); |
| 101 | + m4 = hardwareMap.get(DcMotorEx.class, "m4"); |
| 102 | + |
| 103 | + // Important Step 2: Get access to a list of Expansion Hub Modules to enable changing caching methods. |
| 104 | + List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class); |
| 105 | + |
| 106 | + ElapsedTime timer = new ElapsedTime(); |
| 107 | + |
| 108 | + telemetry.addData(">", "Press play to start tests"); |
| 109 | + telemetry.addData(">", "Test results will update for each access method."); |
| 110 | + telemetry.update(); |
| 111 | + waitForStart(); |
| 112 | + |
| 113 | + // -------------------------------------------------------------------------------------- |
| 114 | + // Run control loop using legacy encoder reads |
| 115 | + // In this mode, a single read is done for each encoder position, and a bulk read is done for each velocity read. |
| 116 | + // This is the worst case scenario. |
| 117 | + // This is the same as using LynxModule.BulkCachingMode.OFF |
| 118 | + // -------------------------------------------------------------------------------------- |
| 119 | + |
| 120 | + displayCycleTimes("Test 1 of 3 (Wait for completion)"); |
| 121 | + |
| 122 | + timer.reset(); |
| 123 | + cycles = 0; |
| 124 | + while (opModeIsActive() && (cycles++ < TEST_CYCLES)) { |
| 125 | + e1 = m1.getCurrentPosition(); |
| 126 | + e2 = m2.getCurrentPosition(); |
| 127 | + e3 = m3.getCurrentPosition(); |
| 128 | + e4 = m4.getCurrentPosition(); |
| 129 | + |
| 130 | + v1 = m1.getVelocity(); |
| 131 | + v2 = m2.getVelocity(); |
| 132 | + v3 = m3.getVelocity(); |
| 133 | + v4 = m4.getVelocity(); |
| 134 | + |
| 135 | + // Put Control loop action code here. |
| 136 | + |
| 137 | + } |
| 138 | + // calculate the average cycle time. |
| 139 | + t1 = timer.milliseconds() / cycles; |
| 140 | + displayCycleTimes("Test 2 of 3 (Wait for completion)"); |
| 141 | + |
| 142 | + // -------------------------------------------------------------------------------------- |
| 143 | + // Run test cycles using AUTO cache mode |
| 144 | + // In this mode, only one bulk read is done per cycle, UNLESS you read a specific encoder/velocity item AGAIN in that cycle. |
| 145 | + // -------------------------------------------------------------------------------------- |
| 146 | + |
| 147 | + // Important Step 3: Option A. Set all Expansion hubs to use the AUTO Bulk Caching mode |
| 148 | + for (LynxModule module : allHubs) { |
| 149 | + module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO); |
| 150 | + } |
| 151 | + |
| 152 | + timer.reset(); |
| 153 | + cycles = 0; |
| 154 | + while (opModeIsActive() && (cycles++ < TEST_CYCLES)) { |
| 155 | + e1 = m1.getCurrentPosition(); // Uses 1 bulk-read for all 4 encoder/velocity reads, |
| 156 | + e2 = m2.getCurrentPosition(); // but don't do any `get` operations more than once per cycle. |
| 157 | + e3 = m3.getCurrentPosition(); |
| 158 | + e4 = m4.getCurrentPosition(); |
| 159 | + |
| 160 | + v1 = m1.getVelocity(); |
| 161 | + v2 = m2.getVelocity(); |
| 162 | + v3 = m3.getVelocity(); |
| 163 | + v4 = m4.getVelocity(); |
| 164 | + |
| 165 | + // Put Control loop action code here. |
| 166 | + |
| 167 | + } |
| 168 | + // calculate the average cycle time. |
| 169 | + t2 = timer.milliseconds() / cycles; |
| 170 | + displayCycleTimes("Test 3 of 3 (Wait for completion)"); |
| 171 | + |
| 172 | + // -------------------------------------------------------------------------------------- |
| 173 | + // Run test cycles using MANUAL cache mode |
| 174 | + // In this mode, only one block read is done each control cycle. |
| 175 | + // This is the MOST efficient method, but it does require that the cache is cleared manually each control cycle. |
| 176 | + // -------------------------------------------------------------------------------------- |
| 177 | + |
| 178 | + // Important Step 3: Option B. Set all Expansion hubs to use the MANUAL Bulk Caching mode |
| 179 | + for (LynxModule module : allHubs) { |
| 180 | + module.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL); |
| 181 | + } |
| 182 | + |
| 183 | + timer.reset(); |
| 184 | + cycles = 0; |
| 185 | + while (opModeIsActive() && (cycles++ < TEST_CYCLES)) { |
| 186 | + |
| 187 | + // Important Step 4: If you are using MANUAL mode, you must clear the BulkCache once per control cycle |
| 188 | + for (LynxModule module : allHubs) { |
| 189 | + module.clearBulkCache(); |
| 190 | + } |
| 191 | + |
| 192 | + e1 = m1.getCurrentPosition(); // Uses 1 bulk-read to obtain ALL the motor data |
| 193 | + e2 = m2.getCurrentPosition(); // There is no penalty for doing more `get` operations in this cycle, |
| 194 | + e3 = m3.getCurrentPosition(); // but they will return the same data. |
| 195 | + e4 = m4.getCurrentPosition(); |
| 196 | + |
| 197 | + v1 = m1.getVelocity(); |
| 198 | + v2 = m2.getVelocity(); |
| 199 | + v3 = m3.getVelocity(); |
| 200 | + v4 = m4.getVelocity(); |
| 201 | + |
| 202 | + // Put Control loop action code here. |
| 203 | + |
| 204 | + } |
| 205 | + // calculate the average cycle time. |
| 206 | + t3 = timer.milliseconds() / cycles; |
| 207 | + displayCycleTimes("Complete"); |
| 208 | + |
| 209 | + // wait until op-mode is stopped by user, before clearing display. |
| 210 | + while (opModeIsActive()) ; |
| 211 | + } |
| 212 | + |
| 213 | + // Display three comparison times. |
| 214 | + void displayCycleTimes(String status) { |
| 215 | + telemetry.addData("Testing", status); |
| 216 | + telemetry.addData("Cache = OFF", "%5.1f mS/cycle", t1); |
| 217 | + telemetry.addData("Cache = AUTO", "%5.1f mS/cycle", t2); |
| 218 | + telemetry.addData("Cache = MANUAL", "%5.1f mS/cycle", t3); |
| 219 | + telemetry.update(); |
| 220 | + } |
| 221 | +} |
| 222 | + |
0 commit comments