autonomous work right side almost done

This commit is contained in:
SpencerPiha
2023-01-28 11:15:33 -06:00
parent 7545b36d8a
commit 8d94c5dbfe
37 changed files with 90 additions and 87 deletions

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive; package org.RoadRunner.drive;
import androidx.annotation.NonNull; import androidx.annotation.NonNull;
@@ -26,11 +26,6 @@ import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import com.qualcomm.robotcore.hardware.VoltageSensor; import com.qualcomm.robotcore.hardware.VoltageSensor;
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType; import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;
import org.firstinspires.ftc.teamcode.trajectorysequence.TrajectorySequence;
import org.firstinspires.ftc.teamcode.trajectorysequence.TrajectorySequenceBuilder;
import org.firstinspires.ftc.teamcode.trajectorysequence.TrajectorySequenceRunner;
import org.firstinspires.ftc.teamcode.util.LynxModuleUtil;
import java.util.ArrayList; import java.util.ArrayList;
import java.util.Arrays; import java.util.Arrays;
import java.util.List; import java.util.List;
@@ -47,6 +42,11 @@ import static org.RoadRunner.drive.DriveConstants.kA;
import static org.RoadRunner.drive.DriveConstants.kStatic; import static org.RoadRunner.drive.DriveConstants.kStatic;
import static org.RoadRunner.drive.DriveConstants.kV; import static org.RoadRunner.drive.DriveConstants.kV;
import org.RoadRunner.trajectorysequence.TrajectorySequence;
import org.RoadRunner.trajectorysequence.TrajectorySequenceBuilder;
import org.RoadRunner.trajectorysequence.TrajectorySequenceRunner;
import org.RoadRunner.util.LynxModuleUtil;
/* /*
* Simple mecanum drive hardware implementation for REV hardware. * Simple mecanum drive hardware implementation for REV hardware.
*/ */

View File

@@ -1,8 +1,7 @@
package org.firstinspires.ftc.teamcode.drive; package org.RoadRunner.drive;
import androidx.annotation.NonNull; import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.roadrunner.control.PIDCoefficients; import com.acmerobotics.roadrunner.control.PIDCoefficients;
import com.acmerobotics.roadrunner.drive.DriveSignal; import com.acmerobotics.roadrunner.drive.DriveSignal;
import com.acmerobotics.roadrunner.drive.TankDrive; import com.acmerobotics.roadrunner.drive.TankDrive;
@@ -26,10 +25,10 @@ import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import com.qualcomm.robotcore.hardware.VoltageSensor; import com.qualcomm.robotcore.hardware.VoltageSensor;
import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType; import com.qualcomm.robotcore.hardware.configuration.typecontainers.MotorConfigurationType;
import org.firstinspires.ftc.teamcode.trajectorysequence.TrajectorySequence; import org.RoadRunner.trajectorysequence.TrajectorySequence;
import org.firstinspires.ftc.teamcode.trajectorysequence.TrajectorySequenceBuilder; import org.RoadRunner.trajectorysequence.TrajectorySequenceBuilder;
import org.firstinspires.ftc.teamcode.trajectorysequence.TrajectorySequenceRunner; import org.RoadRunner.trajectorysequence.TrajectorySequenceRunner;
import org.firstinspires.ftc.teamcode.util.LynxModuleUtil; import org.RoadRunner.util.LynxModuleUtil;
import java.util.Arrays; import java.util.Arrays;
import java.util.List; import java.util.List;
@@ -49,7 +48,6 @@ import static org.RoadRunner.drive.DriveConstants.kV;
/* /*
* Simple tank drive hardware implementation for REV hardware. * Simple tank drive hardware implementation for REV hardware.
*/ */
@Config
public class SampleTankDrive extends TankDrive { public class SampleTankDrive extends TankDrive {
public static PIDCoefficients AXIAL_PID = new PIDCoefficients(0, 0, 0); public static PIDCoefficients AXIAL_PID = new PIDCoefficients(0, 0, 0);
public static PIDCoefficients CROSS_TRACK_PID = new PIDCoefficients(0, 0, 0); public static PIDCoefficients CROSS_TRACK_PID = new PIDCoefficients(0, 0, 0);

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive; package org.RoadRunner.drive;
import androidx.annotation.NonNull; import androidx.annotation.NonNull;
@@ -7,7 +7,8 @@ import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer; import com.acmerobotics.roadrunner.localization.ThreeTrackingWheelLocalizer;
import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.HardwareMap;
import org.firstinspires.ftc.teamcode.util.Encoder;
import org.RoadRunner.util.Encoder;
import java.util.Arrays; import java.util.Arrays;
import java.util.List; import java.util.List;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import static org.RoadRunner.drive.DriveConstants.MAX_RPM; import static org.RoadRunner.drive.DriveConstants.MAX_RPM;
import static org.RoadRunner.drive.DriveConstants.RUN_USING_ENCODER; import static org.RoadRunner.drive.DriveConstants.RUN_USING_ENCODER;
@@ -13,11 +13,11 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.util.RobotLog; import com.qualcomm.robotcore.util.RobotLog;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.RoadRunner.util.LoggingUtil;
import org.RoadRunner.util.RegressionUtil;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.robotcore.internal.system.Misc; import org.firstinspires.ftc.robotcore.internal.system.Misc;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
import org.firstinspires.ftc.teamcode.util.LoggingUtil;
import org.firstinspires.ftc.teamcode.util.RegressionUtil;
import java.util.ArrayList; import java.util.ArrayList;
import java.util.List; import java.util.List;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
@@ -6,7 +6,7 @@ import com.acmerobotics.roadrunner.trajectory.Trajectory;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive; import org.RoadRunner.drive.SampleMecanumDrive;
/* /*
* Op mode for preliminary tuning of the follower PID coefficients (located in the drive base * Op mode for preliminary tuning of the follower PID coefficients (located in the drive base

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import static org.RoadRunner.drive.DriveConstants.MAX_ACCEL; import static org.RoadRunner.drive.DriveConstants.MAX_ACCEL;
import static org.RoadRunner.drive.DriveConstants.MAX_VEL; import static org.RoadRunner.drive.DriveConstants.MAX_VEL;
@@ -19,8 +19,8 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.RobotLog; import com.qualcomm.robotcore.util.RobotLog;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
import java.util.List; import java.util.List;

View File

@@ -1,12 +1,12 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive; import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.teamcode.trajectorysequence.TrajectorySequence; import org.RoadRunner.trajectorysequence.TrajectorySequence;
/* /*
* Op mode for preliminary tuning of the follower PID coefficients (located in the drive base * Op mode for preliminary tuning of the follower PID coefficients (located in the drive base

View File

@@ -1,11 +1,11 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotor;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive; import org.RoadRunner.drive.SampleMecanumDrive;
/** /**
* This is a simple teleop routine for testing localization. Drive the robot around like a normal * This is a simple teleop routine for testing localization. Drive the robot around like a normal

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import static org.RoadRunner.drive.DriveConstants.MAX_ACCEL; import static org.RoadRunner.drive.DriveConstants.MAX_ACCEL;
import static org.RoadRunner.drive.DriveConstants.MAX_VEL; import static org.RoadRunner.drive.DriveConstants.MAX_VEL;
@@ -20,8 +20,8 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.util.RobotLog; import com.qualcomm.robotcore.util.RobotLog;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
import java.util.Objects; import java.util.Objects;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -9,8 +9,8 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime; import com.qualcomm.robotcore.util.ElapsedTime;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
import java.util.Objects; import java.util.Objects;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -10,9 +10,9 @@ import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.VoltageSensor; import com.qualcomm.robotcore.hardware.VoltageSensor;
import com.qualcomm.robotcore.util.ElapsedTime; import com.qualcomm.robotcore.util.ElapsedTime;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.RoadRunner.drive.DriveConstants; import org.RoadRunner.drive.DriveConstants;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
import java.util.Objects; import java.util.Objects;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -7,8 +7,8 @@ import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
/** /**
* This is a simple teleop routine for debugging your motor configuration. * This is a simple teleop routine for debugging your motor configuration.

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.geometry.Vector2d; import com.acmerobotics.roadrunner.geometry.Vector2d;
@@ -6,7 +6,7 @@ import com.acmerobotics.roadrunner.trajectory.Trajectory;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive; import org.RoadRunner.drive.SampleMecanumDrive;
/* /*
* This is an example of a more complex path to really test the tuning. * This is an example of a more complex path to really test the tuning.

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -8,8 +8,8 @@ import com.acmerobotics.roadrunner.trajectory.Trajectory;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
/* /*
* This is a simple routine to test translational drive capabilities. * This is a simple routine to test translational drive capabilities.

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -8,9 +8,8 @@ import com.acmerobotics.roadrunner.trajectory.Trajectory;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
/* /*
* This is a simple routine to test translational drive capabilities. * This is a simple routine to test translational drive capabilities.
*/ */

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -9,10 +9,10 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.util.MovingStatistics; import com.qualcomm.robotcore.util.MovingStatistics;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.robotcore.internal.system.Misc; import org.firstinspires.ftc.robotcore.internal.system.Misc;
import org.RoadRunner.drive.DriveConstants; import org.RoadRunner.drive.DriveConstants;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
/* /*
* This routine determines the effective track width. The procedure works by executing a point turn * This routine determines the effective track width. The procedure works by executing a point turn

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
@@ -10,10 +10,10 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.util.MovingStatistics; import com.qualcomm.robotcore.util.MovingStatistics;
import com.qualcomm.robotcore.util.RobotLog; import com.qualcomm.robotcore.util.RobotLog;
import org.RoadRunner.drive.SampleMecanumDrive;
import org.RoadRunner.drive.StandardTrackingWheelLocalizer;
import org.firstinspires.ftc.robotcore.external.Telemetry; import org.firstinspires.ftc.robotcore.external.Telemetry;
import org.firstinspires.ftc.robotcore.internal.system.Misc; import org.firstinspires.ftc.robotcore.internal.system.Misc;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
import org.firstinspires.ftc.teamcode.drive.StandardTrackingWheelLocalizer;
/** /**
* This routine determines the effective forward offset for the lateral tracking wheel. * This routine determines the effective forward offset for the lateral tracking wheel.

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
@@ -7,8 +7,8 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.util.RobotLog; import com.qualcomm.robotcore.util.RobotLog;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive; import org.RoadRunner.drive.SampleMecanumDrive;
import org.firstinspires.ftc.teamcode.drive.StandardTrackingWheelLocalizer; import org.RoadRunner.drive.StandardTrackingWheelLocalizer;
/** /**
* Opmode designed to assist the user in tuning the `StandardTrackingWheelLocalizer`'s * Opmode designed to assist the user in tuning the `StandardTrackingWheelLocalizer`'s

View File

@@ -1,10 +1,11 @@
package org.firstinspires.ftc.teamcode.drive.opmode; package org.RoadRunner.drive.opmode;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive; import org.RoadRunner.drive.SampleMecanumDrive;
/* /*
* This is a simple routine to test turning capabilities. * This is a simple routine to test turning capabilities.

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.trajectorysequence; package org.RoadRunner.trajectorysequence;
public class EmptySequenceException extends RuntimeException { } public class EmptySequenceException extends RuntimeException { }

View File

@@ -1,8 +1,8 @@
package org.firstinspires.ftc.teamcode.trajectorysequence; package org.RoadRunner.trajectorysequence;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.SequenceSegment; import org.RoadRunner.trajectorysequence.sequencesegment.SequenceSegment;
import java.util.Collections; import java.util.Collections;
import java.util.List; import java.util.List;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.trajectorysequence; package org.RoadRunner.trajectorysequence;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.geometry.Vector2d; import com.acmerobotics.roadrunner.geometry.Vector2d;
@@ -19,10 +19,10 @@ import com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryAcceleration
import com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint; import com.acmerobotics.roadrunner.trajectory.constraints.TrajectoryVelocityConstraint;
import com.acmerobotics.roadrunner.util.Angle; import com.acmerobotics.roadrunner.util.Angle;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.SequenceSegment; import org.RoadRunner.trajectorysequence.sequencesegment.SequenceSegment;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.TrajectorySegment; import org.RoadRunner.trajectorysequence.sequencesegment.TrajectorySegment;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.TurnSegment; import org.RoadRunner.trajectorysequence.sequencesegment.TurnSegment;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.WaitSegment; import org.RoadRunner.trajectorysequence.sequencesegment.WaitSegment;
import java.util.ArrayList; import java.util.ArrayList;
import java.util.Collections; import java.util.Collections;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.trajectorysequence; package org.RoadRunner.trajectorysequence;
import androidx.annotation.Nullable; import androidx.annotation.Nullable;
@@ -16,11 +16,11 @@ import com.acmerobotics.roadrunner.trajectory.Trajectory;
import com.acmerobotics.roadrunner.trajectory.TrajectoryMarker; import com.acmerobotics.roadrunner.trajectory.TrajectoryMarker;
import com.acmerobotics.roadrunner.util.NanoClock; import com.acmerobotics.roadrunner.util.NanoClock;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.SequenceSegment; import org.RoadRunner.trajectorysequence.sequencesegment.SequenceSegment;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.TrajectorySegment; import org.RoadRunner.trajectorysequence.sequencesegment.TrajectorySegment;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.TurnSegment; import org.RoadRunner.trajectorysequence.sequencesegment.TurnSegment;
import org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment.WaitSegment; import org.RoadRunner.trajectorysequence.sequencesegment.WaitSegment;
import org.firstinspires.ftc.teamcode.util.DashboardUtil; import org.RoadRunner.util.DashboardUtil;
import java.util.ArrayList; import java.util.ArrayList;
import java.util.Collections; import java.util.Collections;
@@ -69,12 +69,12 @@ public class TrajectorySequenceRunner {
dashboard.setTelemetryTransmissionInterval(25); dashboard.setTelemetryTransmissionInterval(25);
} }
public void followTrajectorySequenceAsync(TrajectorySequence trajectorySequence) { // public void followTrajectorySequenceAsync(TrajectorySequence trajectorySequence) {
currentTrajectorySequence = trajectorySequence; // currentTrajectorySequence = trajectorySequence;
currentSegmentStartTime = clock.seconds(); // currentSegmentStartTime = clock.seconds();
currentSegmentIndex = 0; // currentSegmentIndex = 0;
lastSegmentIndex = -1; // lastSegmentIndex = -1;
} // }
public @Nullable public @Nullable
DriveSignal update(Pose2d poseEstimate, Pose2d poseVelocity) { DriveSignal update(Pose2d poseEstimate, Pose2d poseVelocity) {
@@ -270,4 +270,7 @@ public class TrajectorySequenceRunner {
public boolean isBusy() { public boolean isBusy() {
return currentTrajectorySequence != null; return currentTrajectorySequence != null;
} }
public void followTrajectorySequenceAsync(TrajectorySequence trajectorySequence) {
}
} }

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment; package org.RoadRunner.trajectorysequence.sequencesegment;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.trajectory.TrajectoryMarker; import com.acmerobotics.roadrunner.trajectory.TrajectoryMarker;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment; package org.RoadRunner.trajectorysequence.sequencesegment;
import com.acmerobotics.roadrunner.trajectory.Trajectory; import com.acmerobotics.roadrunner.trajectory.Trajectory;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment; package org.RoadRunner.trajectorysequence.sequencesegment;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.profile.MotionProfile; import com.acmerobotics.roadrunner.profile.MotionProfile;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.trajectorysequence.sequencesegment; package org.RoadRunner.trajectorysequence.sequencesegment;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;
import com.acmerobotics.roadrunner.trajectory.TrajectoryMarker; import com.acmerobotics.roadrunner.trajectory.TrajectoryMarker;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
import androidx.annotation.Nullable; import androidx.annotation.Nullable;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
/** /**
* IMU axes signs in the order XYZ (after remapping). * IMU axes signs in the order XYZ (after remapping).

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
/** /**
* A direction for an axis to be remapped to * A direction for an axis to be remapped to

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
import com.qualcomm.hardware.bosch.BNO055IMU; import com.qualcomm.hardware.bosch.BNO055IMU;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
import com.acmerobotics.dashboard.canvas.Canvas; import com.acmerobotics.dashboard.canvas.Canvas;
import com.acmerobotics.roadrunner.geometry.Pose2d; import com.acmerobotics.roadrunner.geometry.Pose2d;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
import com.acmerobotics.roadrunner.util.NanoClock; import com.acmerobotics.roadrunner.util.NanoClock;
import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorEx;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
import org.firstinspires.ftc.robotcore.internal.system.AppUtil; import org.firstinspires.ftc.robotcore.internal.system.AppUtil;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
import com.qualcomm.hardware.lynx.LynxModule; import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.HardwareMap;

View File

@@ -1,4 +1,4 @@
package org.firstinspires.ftc.teamcode.util; package org.RoadRunner.util;
import androidx.annotation.Nullable; import androidx.annotation.Nullable;

View File

@@ -20,6 +20,7 @@ dependencies {
implementation 'androidx.appcompat:appcompat:1.2.0' implementation 'androidx.appcompat:appcompat:1.2.0'
implementation 'org.firstinspires.ftc:gameAssets-PowerPlay:1.0.0' implementation 'org.firstinspires.ftc:gameAssets-PowerPlay:1.0.0'
implementation 'org.apache.commons:commons-math3:3.6.1' implementation 'org.apache.commons:commons-math3:3.6.1'
implementation 'com.acmerobotics.roadrunner:core:0.5.1' implementation 'com.acmerobotics.roadrunner:core:0.5.6'
implementation 'com.acmerobotics.dashboard:dashboard:0.4.8'
} }