Skip to content
This repository was archived by the owner on Oct 27, 2020. It is now read-only.

Commit 14ac54a

Browse files
authored
Merge pull request #222 from FIRST-Tech-Challenge/v5.4
V5.4
2 parents 2a92ac0 + 515bf43 commit 14ac54a

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

45 files changed

+1650
-125
lines changed

FtcRobotController/build.gradle

+1-1
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ android {
77

88
defaultConfig {
99
minSdkVersion 19
10-
targetSdkVersion 26
10+
targetSdkVersion 28
1111
}
1212

1313
compileSdkVersion 28

FtcRobotController/src/main/AndroidManifest.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,8 @@
22
<manifest xmlns:android="http://schemas.android.com/apk/res/android"
33
xmlns:tools="http://schemas.android.com/tools"
44
package="com.qualcomm.ftcrobotcontroller"
5-
android:versionCode="35"
6-
android:versionName="5.3">
5+
android:versionCode="36"
6+
android:versionName="5.4">
77

88
<uses-permission android:name="android.permission.RECEIVE_BOOT_COMPLETED" />
99

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,222 @@
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+

FtcRobotController/src/main/java/org/firstinspires/ftc/robotcontroller/internal/PermissionValidatorWrapper.java

+7-1
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,8 @@ public class PermissionValidatorWrapper extends PermissionValidatorActivity {
5252
add(Manifest.permission.READ_EXTERNAL_STORAGE);
5353
add(Manifest.permission.CAMERA);
5454
add(Manifest.permission.ACCESS_COARSE_LOCATION);
55+
add(Manifest.permission.ACCESS_FINE_LOCATION);
56+
add(Manifest.permission.READ_PHONE_STATE);
5557
}};
5658

5759
private final static Class startApplication = FtcRobotControllerActivity.class;
@@ -64,7 +66,11 @@ public String mapPermissionToExplanation(final String permission) {
6466
} else if (permission.equals(Manifest.permission.CAMERA)) {
6567
return Misc.formatForUser(R.string.permRcCameraExplain);
6668
} else if (permission.equals(Manifest.permission.ACCESS_COARSE_LOCATION)) {
67-
return Misc.formatForUser(R.string.permAccessCoarseLocationExplain);
69+
return Misc.formatForUser(R.string.permAccessLocationExplain);
70+
} else if (permission.equals(Manifest.permission.ACCESS_FINE_LOCATION)) {
71+
return Misc.formatForUser(R.string.permAccessLocationExplain);
72+
} else if (permission.equals(Manifest.permission.READ_PHONE_STATE)) {
73+
return Misc.formatForUser(R.string.permReadPhoneState);
6874
}
6975
return Misc.formatForUser(R.string.permGenericExplain);
7076
}

README.md

+42-2
Original file line numberDiff line numberDiff line change
@@ -48,8 +48,48 @@ Documentation for the FTC SDK is also included with this repository. There is a
4848
### Online User Forum
4949
For technical questions regarding the Control System or the FTC SDK, please visit the FTC Technology forum:
5050

51-
&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;[FTC Technology Forum](https://ftcforum.firstinspires.org/forumdisplay.php?156-FTC-Technology)
51+
&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp;[FTC Technology Forum](https://ftcforum.usfirst.org/forumdisplay.php?156-FTC-Technology)
5252

53+
**************************************************************************************
54+
# Release Information
55+
**************************************************************************************
56+
57+
Version 5.4 (20200108-101156)
58+
59+
* Fixes [SkyStone issue #88](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/88)
60+
* Adds an inspection item that notes when a robot controller (Control Hub) is using the factory default password.
61+
* Fixes [SkyStone issue #61](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/61)
62+
* Fixes [SkyStone issue #142](https://github.com/FIRST-Tech-Challenge/SkyStone/issues/142)
63+
* Fixes [ftc_app issue #417](https://github.com/ftctechnh/ftc_app/issues/417) by adding more current and voltage monitoring capabilities for REV Hubs.
64+
* Fixes [a crash sometimes caused by OnBotJava activity](https://ftcforum.firstinspires.org/forum/ftc-technology/76217-onbotjava-crashes-robot-controller)
65+
* Improves OnBotJava autosave functionality [ftc_app #738](https://github.com/ftctechnh/ftc_app/issues/738)
66+
* Fixes system responsiveness issue when an Expansion Hub is disconnected
67+
* Fixes issue where IMU initialization could prevent Op Modes from stopping
68+
* Fixes issue where AndroidTextToSpeech.speak() would fail if it was called too early
69+
* Adds telemetry.speak() methods and blocks, which cause the Driver Station (if also updated) to speak text
70+
* Adds and improves Expansion Hub-related warnings
71+
* Improves Expansion Hub low battery warning
72+
* Displays the warning immediately after the hub reports it
73+
* Specifies whether the condition is current or occurred temporarily during an OpMode run
74+
* Displays which hubs reported low battery
75+
* Displays warning when hub loses and regains power during an OpMode run
76+
* Fixes the hub's LED pattern after this condition
77+
* Displays warning when Expansion Hub is not responding to commands
78+
* Specifies whether the condition is current or occurred temporarily during an OpMode run
79+
* Clarifies warning when Expansion Hub is not present at startup
80+
* Specifies that this condition requires a Robot Restart before the hub can be used.
81+
* The hub light will now accurately reflect this state
82+
* Improves logging and reduces log spam during these conditions
83+
* Syncs the Control Hub time and timezone to a connected web browser programming the robot, if a Driver Station is not available.
84+
* Adds bulk read functionality for REV Hubs
85+
* A bulk caching mode must be set at the Hub level with `LynxModule#setBulkCachingMode()`. This applies to all relevant SDK hardware classes that reference that Hub.
86+
* The following following Hub bulk caching modes are available:
87+
* `BulkCachingMode.OFF` (default): All hardware calls operate as usual. Bulk data can read through `LynxModule#getBulkData()` and processed manually.
88+
* `BulkCachingMode.AUTO`: Applicable hardware calls are served from a bulk read cache that is cleared/refreshed automatically to ensure identical commands don't hit the same cache. The cache can also be cleared manually with `LynxModule#clearBulkCache()`, although this is not recommended.
89+
* (advanced users) `BulkCachingMode.MANUAL`: Same as `BulkCachingMode.AUTO` except the cache is never cleared automatically. To avoid getting stale data, the cache must be manually cleared at the beginning of each loop body or as the user deems appropriate.
90+
* Removes PIDF Annotation values added in Rev 5.3 (to AndyMark, goBILDA and TETRIX motor configurations).
91+
* The new motor types will still be available but their Default control behavior will revert back to Rev 5.2
92+
* Adds new `ConceptMotorBulkRead` sample Opmode to demonstrate and compare Motor Bulk-Read modes for reducing I/O latencies.
5393

5494
**************************************************************************************
5595
# Release Information
@@ -87,7 +127,7 @@ Version 5.3 (20191004-112306)
87127
# Release Information
88128
**************************************************************************************
89129

90-
Version 5.2 (20190905-083227)
130+
Version 5.2 (20190905-083277)
91131

92132
* Fixes extra-wide margins on settings activities, and placement of the new configuration button
93133
* Adds Skystone Vuforia image target data.

build.common.gradle

+4-3
Original file line numberDiff line numberDiff line change
@@ -37,9 +37,10 @@ android {
3737
}
3838

3939
defaultConfig {
40+
signingConfig signingConfigs.debug
4041
applicationId 'com.qualcomm.ftcrobotcontroller'
4142
minSdkVersion 19
42-
targetSdkVersion 26
43+
targetSdkVersion 28
4344

4445
/**
4546
* We keep the versionCode and versionName of robot controller applications in sync with
@@ -77,15 +78,15 @@ android {
7778
// Disable debugging for release versions so it can be uploaded to Google Play.
7879
//debuggable true
7980
ndk {
80-
abiFilters "armeabi-v7a"
81+
abiFilters "armeabi-v7a", "arm64-v8a"
8182
}
8283
}
8384
debug {
8485
debuggable true
8586
jniDebuggable true
8687
renderscriptDebuggable true
8788
ndk {
88-
abiFilters "armeabi-v7a"
89+
abiFilters "armeabi-v7a", "arm64-v8a"
8990
}
9091
}
9192
}

doc/apk/FtcDriverStation-release.apk

7.04 MB
Binary file not shown.
8.18 MB
Binary file not shown.

0 commit comments

Comments
 (0)