Upgrade to Gradle 7.2 and WPILib 2022 (#316)

This commit is contained in:
Tyler Veness
2021-11-21 17:22:56 -08:00
committed by GitHub
parent ffe34f00fe
commit 5ca39e7f84
316 changed files with 671 additions and 1019 deletions

View File

@@ -6,25 +6,44 @@ apply plugin: "edu.wpi.first.NativeUtils"
apply from: "${rootDir}/shared/config.gradle"
// Configure wpigui, libglass, libglassnt.
nativeUtils {
dependencyConfigs {
gui {
groupId = "edu.wpi.first.halsim"
artifactId = "halsim_gui"
headerClassifier = "headers"
sourceClassifier = "sources"
ext = "zip"
version = wpilibVersion
sharedPlatforms << "osxx86-64" << "linuxx86-64" << "windowsx86-64"
}
nativeDependencyContainer {
wpigui(getNativeDependencyTypeClass('WPIStaticMavenDependency')) {
groupId = "edu.wpi.first.wpigui"
artifactId = "wpigui-cpp"
headerClassifier = "headers"
sourceClassifier = "sources"
ext = "zip"
version = wpilibVersion
targetPlatforms.addAll(nativeUtils.wpi.platforms.desktopPlatforms)
}
combinedDependencyConfigs {
halsim_gui {
libraryName = "halsim_gui"
targetPlatforms << "osxx86-64" << "linuxx86-64" << "windowsx86-64"
dependencies << "gui_shared"
}
libglass(getNativeDependencyTypeClass('WPIStaticMavenDependency')) {
groupId = "edu.wpi.first.glass"
artifactId = "libglass"
headerClassifier = "headers"
sourceClassifier = "sources"
ext = "zip"
version = wpilibVersion
targetPlatforms.addAll(nativeUtils.wpi.platforms.desktopPlatforms)
}
libglassnt(getNativeDependencyTypeClass('WPIStaticMavenDependency')) {
groupId = "edu.wpi.first.glass"
artifactId = "libglassnt"
headerClassifier = "headers"
sourceClassifier = "sources"
ext = "zip"
version = wpilibVersion
targetPlatforms.addAll(nativeUtils.wpi.platforms.desktopPlatforms)
}
// Combined
gui(getNativeDependencyTypeClass('AllPlatformsCombinedNativeDependency')) {
dependencies = [
"libglassnt", "libglass", "wpigui", "imgui_static",
"wpimath_static", "ntcore_static", "wpiutil_static"]
}
}
}
ext {
@@ -42,11 +61,10 @@ dependencies {
implementation "edu.wpi.first.wpiutil:wpiutil-java:$wpilibVersion"
implementation "edu.wpi.first.wpimath:wpimath-java:$wpilibVersion"
implementation "edu.wpi.first.hal:hal-java:$wpilibVersion"
implementation "org.ejml:ejml-simple:0.38"
implementation "com.fasterxml.jackson.core:jackson-annotations:2.10.0"
implementation "com.fasterxml.jackson.core:jackson-core:2.10.0"
implementation "com.fasterxml.jackson.core:jackson-databind:2.10.0"
implementation "edu.wpi.first.thirdparty.frc2020.opencv:opencv-java:3.4.7-3"
implementation "edu.wpi.first.thirdparty.frc2022.opencv:opencv-java:$opencvVersion"
}
model {
@@ -67,10 +85,6 @@ model {
binaries.all { binary ->
nativeUtils.useRequiredLibrary(binary, "wpilib_executable_shared")
nativeUtils.useRequiredLibrary(binary, "opencv_shared")
if (binary.targetPlatform.name == NativePlatforms.desktop) {
nativeUtils.useRequiredLibrary(binary, "halsim_gui")
}
}
}
}

View File

@@ -1,8 +1,18 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2020 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
int main() {}
/*
* Copyright (C) Photon Vision.
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
int main() {}

View File

@@ -14,7 +14,6 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.aimandrange;
import edu.wpi.first.wpilibj.RobotBase;

View File

@@ -14,16 +14,14 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.aimandrange;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.PWMVictorSPX;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
import org.photonvision.PhotonCamera;
import org.photonvision.PhotonUtils;
@@ -83,11 +81,11 @@ public class Robot extends TimedRobot {
// Use this range as the measurement we give to the PID controller.
// -1.0 required to ensure positive PID controller effort _increases_ range
forwardSpeed = -1.0 * forwardController.calculate(range, GOAL_RANGE_METERS);
forwardSpeed = -forwardController.calculate(range, GOAL_RANGE_METERS);
// Also calculate angular power
// -1.0 required to ensure positive PID controller effort _increases_ yaw
rotationSpeed = -1.0 * turnController.calculate(result.getBestTarget().getYaw(), 0);
rotationSpeed = -turnController.calculate(result.getBestTarget().getYaw(), 0);
} else {
// If we have no targets, stay still.
forwardSpeed = 0;
@@ -95,8 +93,8 @@ public class Robot extends TimedRobot {
}
} else {
// Manual Driver Mode
forwardSpeed = -1.0 * xboxController.getY(GenericHID.Hand.kRight);
rotationSpeed = xboxController.getX(GenericHID.Hand.kLeft);
forwardSpeed = -xboxController.getRightY();
rotationSpeed = xboxController.getLeftX();
}
// Use our forward/turn speeds to control the drivetrain

View File

@@ -14,7 +14,6 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.aimattarget;
import edu.wpi.first.wpilibj.RobotBase;

View File

@@ -14,16 +14,14 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.aimattarget;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.PWMVictorSPX;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
import org.photonvision.PhotonCamera;
/**
@@ -66,7 +64,7 @@ public class Robot extends TimedRobot {
double forwardSpeed;
double rotationSpeed;
forwardSpeed = -1.0 * xboxController.getY(GenericHID.Hand.kRight);
forwardSpeed = -xboxController.getRightY();
if (xboxController.getAButton()) {
// Vision-alignment mode
@@ -76,14 +74,14 @@ public class Robot extends TimedRobot {
if (result.hasTargets()) {
// Calculate angular turn power
// -1.0 required to ensure positive PID controller effort _increases_ yaw
rotationSpeed = -1.0 * turnController.calculate(result.getBestTarget().getYaw(), 0);
rotationSpeed = -turnController.calculate(result.getBestTarget().getYaw(), 0);
} else {
// If we have no targets, stay still.
rotationSpeed = 0;
}
} else {
// Manual Driver Mode
rotationSpeed = xboxController.getX(GenericHID.Hand.kLeft);
rotationSpeed = xboxController.getLeftX();
}
// Use our forward/turn speeds to control the drivetrain

View File

@@ -59,4 +59,4 @@
"dependencies": [],
"foldername": "simposeest"
}
]
]

View File

@@ -14,7 +14,6 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.getinrange;
import edu.wpi.first.wpilibj.RobotBase;

View File

@@ -14,16 +14,14 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.getinrange;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.PWMVictorSPX;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
import org.photonvision.PhotonCamera;
import org.photonvision.PhotonUtils;
@@ -67,7 +65,7 @@ public class Robot extends TimedRobot {
@Override
public void teleopPeriodic() {
double forwardSpeed;
double rotationSpeed = xboxController.getX(GenericHID.Hand.kLeft);
double rotationSpeed = xboxController.getLeftX();
if (xboxController.getAButton()) {
// Vision-alignment mode
@@ -85,14 +83,14 @@ public class Robot extends TimedRobot {
// Use this range as the measurement we give to the PID controller.
// -1.0 required to ensure positive PID controller effort _increases_ range
forwardSpeed = -1.0 * controller.calculate(range, GOAL_RANGE_METERS);
forwardSpeed = -controller.calculate(range, GOAL_RANGE_METERS);
} else {
// If we have no targets, stay still.
forwardSpeed = 0;
}
} else {
// Manual Driver Mode
forwardSpeed = -1.0 * xboxController.getY(GenericHID.Hand.kRight);
forwardSpeed = -xboxController.getRightY();
}
// Use our forward/turn speeds to control the drivetrain

View File

@@ -14,7 +14,6 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simaimandrange;
import edu.wpi.first.wpilibj.RobotBase;

View File

@@ -14,16 +14,14 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simaimandrange;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.PWMVictorSPX;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
import org.photonlib.examples.simaimandrange.sim.DrivetrainSim;
import org.photonvision.PhotonCamera;
import org.photonvision.PhotonUtils;
@@ -86,11 +84,11 @@ public class Robot extends TimedRobot {
// Use this range as the measurement we give to the PID controller.
// -1.0 required to ensure positive PID controller effort _increases_ range
forwardSpeed = -1.0 * forwardController.calculate(range, GOAL_RANGE_METERS);
forwardSpeed = -forwardController.calculate(range, GOAL_RANGE_METERS);
// Also calculate angular power
// -1.0 required to ensure positive PID controller effort _increases_ yaw
rotationSpeed = -1.0 * turnController.calculate(result.getBestTarget().getYaw(), 0);
rotationSpeed = -turnController.calculate(result.getBestTarget().getYaw(), 0);
} else {
// If we have no targets, stay still.
forwardSpeed = 0;
@@ -98,8 +96,8 @@ public class Robot extends TimedRobot {
}
} else {
// Manual Driver Mode
forwardSpeed = -1.0 * xboxController.getY(GenericHID.Hand.kRight);
rotationSpeed = xboxController.getX(GenericHID.Hand.kLeft);
forwardSpeed = -xboxController.getRightY();
rotationSpeed = xboxController.getLeftX();
}
// Use our forward/turn speeds to control the drivetrain

View File

@@ -14,24 +14,23 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simaimandrange.sim;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.numbers.N2;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.geometry.Transform2d;
import edu.wpi.first.wpilibj.geometry.Translation2d;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
import edu.wpi.first.wpilibj.simulation.PWMSim;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.system.LinearSystem;
import edu.wpi.first.wpilibj.system.plant.DCMotor;
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.wpiutil.math.numbers.N2;
import org.photonlib.examples.simaimandrange.Robot;
import org.photonvision.SimVisionSystem;
import org.photonvision.SimVisionTarget;
@@ -44,7 +43,6 @@ import org.photonvision.SimVisionTarget;
* real motors/sensors/physics are used instead.
*/
public class DrivetrainSim {
// Simulated Motor Controllers
PWMSim leftLeader = new PWMSim(0);
PWMSim rightLeader = new PWMSim(1);
@@ -53,7 +51,7 @@ public class DrivetrainSim {
// Configure these to match your drivetrain's physical dimensions
// and characterization results.
LinearSystem<N2, N2, N2> drivetrainSystem =
LinearSystemId.identifyDrivetrainSystem(1.98, 0.2, 1.5, 0.3);
LinearSystemId.identifyDrivetrainSystem(1.98, 0.2, 1.5, 0.3, 1.0);
DifferentialDrivetrainSim drivetrainSimulator =
new DifferentialDrivetrainSim(
drivetrainSystem,
@@ -114,11 +112,10 @@ public class DrivetrainSim {
* physics forward by a single 20ms step.
*/
public void update() {
double leftMotorCmd = 0;
double rightMotorCmd = 0;
if (DriverStation.getInstance().isEnabled() && !RobotController.isBrownedOut()) {
if (DriverStation.isEnabled() && !RobotController.isBrownedOut()) {
leftMotorCmd = leftLeader.getSpeed();
rightMotorCmd = rightLeader.getSpeed();
}

View File

@@ -14,7 +14,6 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest;
import edu.wpi.first.wpilibj.RobotBase;

View File

@@ -14,17 +14,16 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest.robot;
import edu.wpi.first.math.controller.RamseteController;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.controller.RamseteController;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.trajectory.Trajectory;
import edu.wpi.first.wpilibj.trajectory.TrajectoryConfig;
import edu.wpi.first.wpilibj.trajectory.TrajectoryGenerator;
import java.util.List;
/**
@@ -34,7 +33,6 @@ import java.util.List;
* thinks it ought to be.
*/
public class AutoController {
private Trajectory trajectory;
private RamseteController ramsete = new RamseteController();
@@ -46,7 +44,6 @@ public class AutoController {
Trajectory.State desiredDtState;
public AutoController() {
// Change this trajectory if you need the robot to follow different paths.
trajectory =
TrajectoryGenerator.generateTrajectory(
@@ -83,7 +80,6 @@ public class AutoController {
* @return The commanded drivetrain motion
*/
public ChassisSpeeds getCurMotorCmds(Pose2d curEstPose) {
if (isRunning) {
double elapsed = timer.get();
desiredDtState = trajectory.sample(elapsed);

View File

@@ -14,14 +14,13 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest.robot;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.geometry.Transform2d;
import edu.wpi.first.wpilibj.geometry.Translation2d;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import org.photonvision.SimVisionTarget;
/**
@@ -31,7 +30,6 @@ import org.photonvision.SimVisionTarget;
* at the field drawings 3) Match with how your vision coprocessor is configured.
*/
public class Constants {
//////////////////////////////////////////////////////////////////
// Drivetrain Physical
//////////////////////////////////////////////////////////////////

View File

@@ -14,18 +14,17 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest.robot;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PWMVictorSPX;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.controller.PIDController;
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX;
/**
* Implements a controller for the drivetrain. Converts a set of chassis motion commands into motor
@@ -33,15 +32,14 @@ import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
* speed.
*/
public class Drivetrain {
// PWM motor controller output definitions
PWMVictorSPX leftLeader = new PWMVictorSPX(Constants.kDtLeftLeaderPin);
PWMVictorSPX leftFollower = new PWMVictorSPX(Constants.kDtLeftFollowerPin);
PWMVictorSPX rightLeader = new PWMVictorSPX(Constants.kDtRightLeaderPin);
PWMVictorSPX rightFollower = new PWMVictorSPX(Constants.kDtRightFollowerPin);
SpeedControllerGroup leftGroup = new SpeedControllerGroup(leftLeader, leftFollower);
SpeedControllerGroup rightGroup = new SpeedControllerGroup(rightLeader, rightFollower);
MotorControllerGroup leftGroup = new MotorControllerGroup(leftLeader, leftFollower);
MotorControllerGroup rightGroup = new MotorControllerGroup(rightLeader, rightFollower);
// Drivetrain wheel speed sensors
// Used both for speed control and pose estimation.

View File

@@ -14,21 +14,20 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest.robot;
import edu.wpi.first.math.Matrix;
import edu.wpi.first.math.VecBuilder;
import edu.wpi.first.math.estimator.DifferentialDrivePoseEstimator;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.math.numbers.N5;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.estimator.DifferentialDrivePoseEstimator;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Transform2d;
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.wpiutil.math.Matrix;
import edu.wpi.first.wpiutil.math.VecBuilder;
import edu.wpi.first.wpiutil.math.numbers.N1;
import edu.wpi.first.wpiutil.math.numbers.N3;
import edu.wpi.first.wpiutil.math.numbers.N5;
import org.photonvision.PhotonCamera;
/**
@@ -37,7 +36,6 @@ import org.photonvision.PhotonCamera;
* filter. This in turn creates a best-guess at a Pose2d of where our drivetrain is currently at.
*/
public class DrivetrainPoseEstimator {
// Sensors used as part of the Pose Estimation
private final AnalogGyro gyro = new AnalogGyro(Constants.kGyroPin);
private PhotonCamera cam = new PhotonCamera(Constants.kCamName);
@@ -75,7 +73,6 @@ public class DrivetrainPoseEstimator {
*/
public void update(
DifferentialDriveWheelSpeeds actWheelSpeeds, double leftDist, double rightDist) {
m_poseEstimator.update(gyro.getRotation2d(), actWheelSpeeds, leftDist, rightDist);
var res = cam.getLatestResult();

View File

@@ -14,11 +14,9 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest.robot;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.SlewRateLimiter;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.XboxController;
public class OperatorInterface {
@@ -34,7 +32,7 @@ public class OperatorInterface {
public double getFwdRevSpdCmd() {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
return -speedLimiter.calculate(opCtrl.getY(GenericHID.Hand.kLeft)) * Constants.kMaxSpeed;
return -speedLimiter.calculate(opCtrl.getLeftY()) * Constants.kMaxSpeed;
}
public double getRotateSpdCmd() {
@@ -42,7 +40,7 @@ public class OperatorInterface {
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
return -rotLimiter.calculate(opCtrl.getX(GenericHID.Hand.kRight)) * Constants.kMaxAngularSpeed;
return -rotLimiter.calculate(opCtrl.getRightX()) * Constants.kMaxAngularSpeed;
}
public boolean getSimKickCmd() {

View File

@@ -14,16 +14,14 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest.robot;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/** Reports our expected, desired, and actual poses to dashboards */
public class PoseTelemetry {
Field2d field = new Field2d();
Pose2d actPose = new Pose2d();

View File

@@ -14,16 +14,14 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest.robot;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
import org.photonlib.examples.simposeest.sim.DrivetrainSim;
public class Robot extends TimedRobot {
AutoController autoCtrl = new AutoController();
Drivetrain dt = new Drivetrain();
OperatorInterface opInf = new OperatorInterface();

View File

@@ -14,23 +14,22 @@
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*/
package org.photonlib.examples.simposeest.sim;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.numbers.N2;
import edu.wpi.first.math.system.LinearSystem;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.geometry.Pose2d;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.geometry.Transform2d;
import edu.wpi.first.wpilibj.geometry.Translation2d;
import edu.wpi.first.wpilibj.simulation.AnalogGyroSim;
import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
import edu.wpi.first.wpilibj.simulation.PWMSim;
import edu.wpi.first.wpilibj.system.LinearSystem;
import edu.wpi.first.wpilibj.system.plant.DCMotor;
import edu.wpi.first.wpilibj.system.plant.LinearSystemId;
import edu.wpi.first.wpiutil.math.numbers.N2;
import org.photonlib.examples.simposeest.robot.Constants;
import org.photonvision.SimVisionSystem;
@@ -42,7 +41,6 @@ import org.photonvision.SimVisionSystem;
* real motors/sensors/physics are used instead.
*/
public class DrivetrainSim {
// Simulated Sensors
AnalogGyroSim gyroSim = new AnalogGyroSim(Constants.kGyroPin);
EncoderSim leftEncoderSim = EncoderSim.createForChannel(Constants.kDtLeftEncoderPinA);
@@ -100,11 +98,10 @@ public class DrivetrainSim {
* physics forward by a single 20ms step.
*/
public void update() {
double leftMotorCmd = 0;
double rightMotorCmd = 0;
if (DriverStation.getInstance().isEnabled() && !RobotController.isBrownedOut()) {
if (DriverStation.isEnabled() && !RobotController.isBrownedOut()) {
// If the motor controllers are enabled...
// Roughly model the effect of leader and follower motor pushing on the same
// gearbox.