Skip to content

Commit 25c8dfb

Browse files
committed
Merge branch 'develop'
2 parents 36ce141 + b93ec29 commit 25c8dfb

File tree

114 files changed

+1988
-1563
lines changed

Some content is hidden

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

114 files changed

+1988
-1563
lines changed

.travis.yml

Lines changed: 7 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -9,26 +9,18 @@ after_success:
99
deploy:
1010
- provider: pages
1111
skip_cleanup: true
12-
github_token: "$GITHUB_TOKEN"
12+
github_token: $GITHUB_TOKEN
1313
local_dir: docs
1414
on:
1515
branch: master
1616
- provider: releases
1717
api_key:
1818
secure: VawxVLIOq2XSIRsgsZUPEw5y1f6iWXqY6ujvhydIDO150KXEBjytHIv3BOkpDmtkM4PAjfe3LzXdL2gJ7xLjuvDiuE1+aD/eM5PtHD4omPtzBVxWBot/jwvsxP2zTmZsGvBGvkffvA2GalOdSFnfa5S18W5L5DgyGe1nJFCwLhMwNXTnSIBr01W8LemcN7PAu/rtpSB1iYPI75Weiyaq1SsjRYJ6La2/tIMhQUnEWEgWcJh1mg0DikcDE8A5pXDDmhHrIvEFa8Q3SJQmIC0ZiVdiWTlnV4LjPt8knfegPZXyrO6VvitIZxwHP+U5P6N7JsFIhVpU6N2isF40dgoXm9d/Nyi3HdsYTcqmbK1JpzcArx5XqjXolwpPPnZ5/KV5DLcZyOZqar2NOGVjs5h55WHnxdgHZqYP30nP9nc1SY8Bw/4Tm6aebOLFXR1PAnilxYfhbk666IQwGsAsPUxDK2ZpB3fBZfr0j2Mwi3ZwkBK0Cqike6E2PQKDkdSiGAkCHUKORepKy+iJC7/8B/ToakI2ena8pi763BBDegyHxllH4EZ+gep0Q/MNKmBvrEIvv8oRgcovV6RZ6JFy4NaosHFVWGoi242Sn9Z0CDg+LTq2uGc1YIuVMzsPi8jCPmTCR7Di4OtGyeaujFqrv0HhYGH9mekoaSU3avfot3Zo/Ws=
1919
file:
20-
- "tct/build/libs/tct.jar"
21-
- "tct/script/tct.sh"
20+
- tct/build/libs/tct.jar
21+
- tct/script/tct.sh
2222
skip_cleanup: true
23-
body: |
24-
This command-line utility runs on your robot's hardware or a bench system. When run manually, it will run in the place of your robot program. When not being run manually, it will not interfere with normal robot program execution.
25-
26-
Any commands below run in a SSH session on the roboRIO.
27-
28-
1. Download `tct.jar` and the `tct.sh` shell script from above and copy to the same directory on the roboRIO, for example `/home/admin`
29-
2. Make the `tct.sh` shell script executable with `chmod +x tct.sh`.
30-
3. Optional, but recommended, stop the auto-run of any existing robot code on the roboRIO with `/etc/init.d/nilvrt stop`. Reboot the roboRIO to restore auto-run.
31-
4. Run with `./tct.sh`
23+
body: "This command-line utility runs on your robot's hardware or a bench system. When run manually, it will run in the place of your robot program. When not being run manually, it will not interfere with normal robot program execution.\n\nAny commands below run in a SSH session on the roboRIO.\n\n1. Download `tct.jar` and the `tct.sh` shell script from above and copy to the same directory on the roboRIO, for example `/home/admin`\n2. Make the `tct.sh` shell script executable with `chmod +x tct.sh`.\n3. Optional, but recommended, stop the fauto-run of any existing robot code on the roboRIO with `/etc/init.d/nilvrt stop`. Reboot the roboRIO to restore auto-run.\n4. Run with `./tct.sh`\n"
3224
on:
3325
tags: true
3426

@@ -41,9 +33,9 @@ before_cache:
4133
- rm -rf $HOME/.m2/repository/org/strykeforce
4234
cache:
4335
directories:
44-
- "$HOME/.m2/"
45-
- "$HOME/.gradle/caches/"
46-
- "$HOME/.gradle/wrapper/"
36+
- $HOME/.m2/
37+
- $HOME/.gradle/caches/
38+
- $HOME/.gradle/wrapper/
4739
env:
4840
global:
4941
secure: StbRRMHj5mEAKLzQET5dJ9wjjBU0XnOy5LWUrYHMH/EIuk1RueCcofngmsS6V70Nr54F8/9xv4voL2JLSINtoVcQzJ6PTMLjB1Ujsm+xbW5aii29kFtVy4dY4N/fmRALEP8Be9o8Yve686bOUJFEyyGlYZsVqsipILyz/eHjhmqEv7s9QSA5IZzwyd4lEyCb1RY3xgPepXEDt2Du/AvOK6+mJM1mqHxE0awDS5jrORH8aigmugF7wtUcBWkgsvTO4MeelVi3l4uXRp/5a8JoJ0vTP3iMvVKADzS/g6s3fWSPIyvJYzWQoYuW85mKr63mJS+FXggzFXIDholYb27TqLGmU4HAbTl/bmWllWJe3FbkZSK5VFyGKpypNOBugzRgyubxAB1TBbGj0kW2fgncLsrKYPq63DhJzCXpPc4LsT9XaZxxTI47BhFRnsWGIaSvmBavBWD0Qq9WP0BMvJMxUR/PJ6C8D+YG+AHrs3w3zZLHe7iuaXyVwq97IC7IhAnkYWnX+bG6KIwY08QLki8DYYBeGPxkPHsyBep84tPfKqxnY+xdVNylteBJt0YJZyn/rNK89a9k110DjKvKCewQpx/b6v3JLaqjju5nFHcdM7M+0kJGbKGHWJUMLWv/0UMfBG9NuiEpq6+NNv3Hi+OITeUYVvRT8/Ditverjdv6KlU=

build.gradle

Lines changed: 7 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ plugins {
22
id "java"
33
id "idea"
44
id "net.ltgt.apt-idea" version "0.13"
5-
id "jaci.openrio.gradle.GradleRIO" version "2017.11.27" apply false
5+
id "jaci.openrio.gradle.GradleRIO" version "2018.01.15" apply false
66
id "net.ltgt.errorprone" version "0.0.13"
77
id "com.diffplug.gradle.spotless" version "3.8.0"
88
}
@@ -25,9 +25,10 @@ ext {
2525
slf4j : 'org.slf4j:slf4j-api:1.7.25',
2626
spock : 'org.spockframework:spock-core:1.1-groovy-2.4',
2727
toml4j : 'com.moandjiezana.toml:toml4j:0.7.2',
28+
autoFactory : 'com.google.auto.factory:auto-factory:1.0-beta5',
2829
]
2930
specificationTitle = 'Third Coast Library'
30-
specificationVersion = '17.2.0'
31+
specificationVersion = '18.0.4'
3132
}
3233

3334
subprojects {
@@ -36,21 +37,17 @@ subprojects {
3637
apply plugin: 'net.ltgt.apt-idea'
3738
// apply plugin: 'net.ltgt.errorprone' // FIXME: https://github.com/google/dagger/issues/1004
3839

39-
wpi {
40-
navxVersion = '3.0.331' // FIXME: remove for 2018 build
41-
}
42-
4340
repositories {
4441
jcenter()
4542
maven { url 'https://oss.sonatype.org/content/repositories/snapshots' } // nanohttpd
4643
}
4744
}
4845

4946
spotless {
50-
java {
51-
googleJavaFormat()
52-
target '**/*.java'
53-
}
47+
java {
48+
googleJavaFormat()
49+
target '**/*.java'
50+
}
5451
}
5552

5653
idea {

core/build.gradle

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,10 @@ dependencies {
2222
compile libs.slf4j
2323
compileOnly libs.jetbrainsAnnotations
2424
compileOnly libs.jsr305
25+
compileOnly libs.autoFactory
2526

2627
apt libs.daggerCompiler
28+
apt libs.autoFactory
2729

2830
testCompile libs.spock
2931
testRuntime libs.logback

core/javadoc.gradle

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -4,17 +4,17 @@ javadoc {
44
options.links = [
55
"https://docs.oracle.com/javase/8/docs/api/",
66
"http://first.wpi.edu/FRC/roborio/release/docs/java/",
7-
"http://www.ctr-electronics.com/downloads/api/java/html/",
8-
"http://www.kauailabs.com/public_files/navx-mxp/apidocs/java/"
7+
"http://www.ctr-electronics.com/downloads/api/java/html/"
8+
// "http://www.kauailabs.com/public_files/navx-mxp/apidocs/java/"
99
]
10-
options.addBooleanOption("-allow-script-in-comments", true)
11-
options.footer = "<script async src=\"https://www.googletagmanager.com/gtag/js?id=UA-108186367-1\"></script>\n" +
12-
"<script>\n" +
13-
" window.dataLayer = window.dataLayer || [];\n" +
14-
" function gtag(){dataLayer.push(arguments);}\n" +
15-
" gtag('js', new Date());\n" +
16-
"\n" +
17-
" gtag('config', 'UA-108186367-1');\n" +
18-
"</script>\n"
10+
// options.addBooleanOption("-allow-script-in-comments", true)
11+
// options.footer = "<script async src=\"https://www.googletagmanager.com/gtag/js?id=UA-108186367-1\"></script>\n" +
12+
// "<script>\n" +
13+
// " window.dataLayer = window.dataLayer || [];\n" +
14+
// " function gtag(){dataLayer.push(arguments);}\n" +
15+
// " gtag('js', new Date());\n" +
16+
// "\n" +
17+
// " gtag('config', 'UA-108186367-1');\n" +
18+
// "</script>\n"
1919

2020
}

core/src/main/java/org/strykeforce/thirdcoast/swerve/SwerveDrive.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -162,9 +162,9 @@ public void zeroAzimuthEncoders() {
162162
}
163163

164164
/**
165-
* Register the swerve wheel azimuth and drive {@link com.ctre.CANTalon} with the Telemetry
166-
* service for data collection. The Telemetry service will set the Talon status frame update rates
167-
* to default values during registration.
165+
* Register the swerve wheel azimuth and drive {@link com.ctre.phoenix.motorcontrol.can.TalonSRX}
166+
* with the Telemetry service for data collection. The Telemetry service will set the Talon status
167+
* frame update rates to default values during registration.
168168
*
169169
* @param telemetryService the active Telemetry service instance created by the robot
170170
*/

core/src/main/java/org/strykeforce/thirdcoast/swerve/Wheel.java

Lines changed: 38 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -1,11 +1,14 @@
11
package org.strykeforce.thirdcoast.swerve;
22

3-
import com.ctre.CANTalon;
3+
import com.ctre.phoenix.ErrorCode;
4+
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
45
import org.slf4j.Logger;
56
import org.slf4j.LoggerFactory;
7+
import org.strykeforce.thirdcoast.talon.Errors;
68
import org.strykeforce.thirdcoast.talon.TalonConfiguration;
79
import org.strykeforce.thirdcoast.talon.TalonFactory;
810
import org.strykeforce.thirdcoast.talon.TalonProvisioner;
11+
import org.strykeforce.thirdcoast.talon.ThirdCoastTalon;
912

1013
/**
1114
* Controls a swerve drive wheel azimuth and drive motors. The azimuth and drive Talons are
@@ -25,11 +28,11 @@
2528
*/
2629
public class Wheel {
2730

28-
static final Logger logger = LoggerFactory.getLogger(Wheel.class);
29-
31+
public static final double TICKS_PER_ROTATION = 4096;
32+
private static final Logger logger = LoggerFactory.getLogger(Wheel.class);
3033
private final TalonProvisioner talonProvisioner;
31-
private final CANTalon azimuthTalon;
32-
private final CANTalon driveTalon;
34+
private final ThirdCoastTalon azimuthTalon;
35+
private final ThirdCoastTalon driveTalon;
3336

3437
private double driveSetpointMax;
3538
private double azimuthSetpoint;
@@ -41,10 +44,10 @@ public class Wheel {
4144
* respectively. Assumes the Talon configurations have been registered.
4245
*
4346
* @param talonProvisioner the TalonProvisioner used to provision Talons
44-
* @param azimuth the azimuthTalon CANTalon
45-
* @param drive the driveTalon CANTalon
47+
* @param azimuth the azimuthTalon TalonSRX
48+
* @param drive the driveTalon TalonSRX
4649
*/
47-
public Wheel(TalonProvisioner talonProvisioner, CANTalon azimuth, CANTalon drive) {
50+
public Wheel(TalonProvisioner talonProvisioner, ThirdCoastTalon azimuth, ThirdCoastTalon drive) {
4851
final String AZIMUTH_PARAMETERS = "azimuth";
4952
final String DRIVE_PARAMETERS = "drive";
5053

@@ -65,8 +68,8 @@ public Wheel(TalonProvisioner talonProvisioner, CANTalon azimuth, CANTalon drive
6568
public Wheel(TalonFactory talonFactory, int index) {
6669
this(
6770
talonFactory.getProvisioner(),
68-
talonFactory.getTalon(index),
69-
talonFactory.getTalon(index + 10));
71+
(ThirdCoastTalon) talonFactory.getTalon(index),
72+
(ThirdCoastTalon) talonFactory.getTalon(index + 10));
7073
}
7174

7275
/**
@@ -90,11 +93,12 @@ public void set(double azimuth, double drive) {
9093
return;
9194
}
9295

93-
double azimuthPosition = azimuthTalon.getPosition();
94-
double azimuthError = Math.IEEEremainder(azimuth - azimuthPosition, 1.0);
95-
if (Math.abs(azimuthError) > 0.25) {
96-
azimuthError -= Math.copySign(0.5, azimuthError);
97-
driveSetpoint *= -1.0;
96+
double azimuthPosition = azimuthTalon.getSelectedSensorPosition(0);
97+
double azimuthError =
98+
Math.IEEEremainder(azimuth * TICKS_PER_ROTATION - azimuthPosition, TICKS_PER_ROTATION);
99+
if (Math.abs(azimuthError) > 0.25 * TICKS_PER_ROTATION) {
100+
azimuthError -= Math.copySign(0.5 * TICKS_PER_ROTATION, azimuthError);
101+
driveSetpoint = -driveSetpoint;
98102
}
99103
azimuthSetpoint = azimuthPosition + azimuthError;
100104

@@ -107,12 +111,12 @@ public void set(double azimuth, double drive) {
107111
* current position in case the wheel has been manually rotated away from its previous setpoint.
108112
*/
109113
public void stop() {
110-
azimuthSetpoint = azimuthTalon.getPosition();
114+
azimuthSetpoint = azimuthTalon.getSelectedSensorPosition(0);
111115
azimuthTalon.set(azimuthSetpoint);
112116
driveTalon.set(0);
113117
}
114118

115-
void setAzimuthParameters(String name) {
119+
public void setAzimuthParameters(String name) {
116120
try {
117121
TalonConfiguration talonConfiguration = talonProvisioner.configurationFor(name);
118122
talonConfiguration.configure(azimuthTalon);
@@ -122,7 +126,7 @@ void setAzimuthParameters(String name) {
122126
}
123127
}
124128

125-
void setDriveParameters(String name) {
129+
public void setDriveParameters(String name) {
126130
try {
127131
TalonConfiguration talonConfiguration = talonProvisioner.configurationFor(name);
128132
talonConfiguration.configure(driveTalon);
@@ -139,9 +143,10 @@ void setDriveParameters(String name) {
139143
* @param zero encoder position (in ticks) where wheel is zeroed.
140144
*/
141145
public void setAzimuthZero(int zero) {
142-
double offset = getAzimuthAbsolutePosition() - zero; // encoder ticks
143-
azimuthSetpoint = offset / 0xFFF; // wheel rotations
144-
azimuthTalon.setPosition(azimuthSetpoint);
146+
azimuthSetpoint = (double) (getAzimuthAbsolutePosition() - zero);
147+
// TODO: test this timeout value is OK
148+
ErrorCode e = azimuthTalon.setSelectedSensorPosition((int) azimuthSetpoint, 0, 10);
149+
Errors.check(e, logger);
145150
azimuthTalon.set(azimuthSetpoint);
146151
}
147152

@@ -155,15 +160,15 @@ public double getAzimuthSetpoint() {
155160
return azimuthSetpoint;
156161
}
157162

158-
/**
159-
* Return the drive speed setpoint. Note this may differ from the actual speed if the wheel is
160-
* accelerating.
161-
*
162-
* @return speed setpoint
163-
*/
164-
public double getDriveSetpoint() {
165-
return driveSetpoint;
166-
}
163+
// /**
164+
// * Return the drive speed setpoint. Note this may differ from the actual speed if the wheel is
165+
// * accelerating.
166+
// *
167+
// * @return speed setpoint
168+
// */
169+
// public double getDriveSetpoint() {
170+
// return driveSetpoint;
171+
// }
167172

168173
/**
169174
* Indicates if the wheel has reversed drive direction to optimize azimuth rotation.
@@ -180,15 +185,15 @@ public boolean isDriveReversed() {
180185
* @return 0 - 4095 encoder ticks
181186
*/
182187
public int getAzimuthAbsolutePosition() {
183-
return azimuthTalon.getPulseWidthPosition() & 0xFFF;
188+
return azimuthTalon.getSensorCollection().getPulseWidthPosition() & 0xFFF;
184189
}
185190

186191
/**
187192
* Get the azimuth Talon controller.
188193
*
189194
* @return azimuth Talon instance used by wheel
190195
*/
191-
public CANTalon getAzimuthTalon() {
196+
public TalonSRX getAzimuthTalon() {
192197
return azimuthTalon;
193198
}
194199

@@ -197,7 +202,7 @@ public CANTalon getAzimuthTalon() {
197202
*
198203
* @return drive Talon instance used by wheel
199204
*/
200-
public CANTalon getDriveTalon() {
205+
public TalonSRX getDriveTalon() {
201206
return driveTalon;
202207
}
203208

0 commit comments

Comments
 (0)