Compare commits
3 Commits
branch-int
...
branch-ash
Author | SHA1 | Date | |
---|---|---|---|
e329bbc16d | |||
cc8b126e75 | |||
1c16c6beb5 |
@ -1,7 +1,5 @@
|
|||||||
package org.firstinspires.ftc.teamcode;
|
package org.firstinspires.ftc.teamcode;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.MecanumDriveParameters.*;
|
|
||||||
|
|
||||||
import androidx.annotation.NonNull;
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.canvas.Canvas;
|
import com.acmerobotics.dashboard.canvas.Canvas;
|
||||||
@ -56,23 +54,24 @@ import java.util.List;
|
|||||||
@Config
|
@Config
|
||||||
public final class MecanumDrive {
|
public final class MecanumDrive {
|
||||||
public static class Params {
|
public static class Params {
|
||||||
|
// IMU orientation
|
||||||
/*
|
// TODO: fill in these values based on
|
||||||
IMU Orientation
|
// see https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
|
||||||
See https://ftc-docs.firstinspires.org/en/latest/programming_resources/imu/imu.html?highlight=imu#physical-hub-mounting
|
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection =
|
||||||
*/
|
RevHubOrientationOnRobot.LogoFacingDirection.DOWN;
|
||||||
public RevHubOrientationOnRobot.LogoFacingDirection logoFacingDirection = RevHubOrientationOnRobot.LogoFacingDirection.UP;
|
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection =
|
||||||
public RevHubOrientationOnRobot.UsbFacingDirection usbFacingDirection = RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
|
RevHubOrientationOnRobot.UsbFacingDirection.LEFT;
|
||||||
|
|
||||||
// drive model parameters
|
// drive model parameters
|
||||||
public double inPerTick = INCHES_PER_TICK_VALUE;
|
//public double inPerTick = 37619.0/112;
|
||||||
public double lateralInPerTick = LATERAL_INCHES_PER_TICK_VALUE;
|
public double inPerTick = 18760.5/56;
|
||||||
public double trackWidthTicks = TRACK_WIDTH_IN_TICKS_VALUE;
|
public double lateralInPerTick = 293.2046574609792;
|
||||||
|
public double trackWidthTicks = 3968.437903995162;
|
||||||
|
|
||||||
// feedforward parameters (in tick units)
|
// feedforward parameters (in tick units)
|
||||||
public double kS = KS_VALUE;
|
public double kS = 0.7748584778215575;
|
||||||
public double kV = KV_VALUE;
|
public double kV = 0.0005849868585467051;
|
||||||
public double kA = KA_VALUE;
|
public double kA = 0;
|
||||||
|
|
||||||
// path profile parameters (in inches)
|
// path profile parameters (in inches)
|
||||||
public double maxWheelVel = 50;
|
public double maxWheelVel = 50;
|
||||||
@ -96,18 +95,15 @@ public final class MecanumDrive {
|
|||||||
public static Params PARAMS = new Params();
|
public static Params PARAMS = new Params();
|
||||||
|
|
||||||
public final MecanumKinematics kinematics = new MecanumKinematics(
|
public final MecanumKinematics kinematics = new MecanumKinematics(
|
||||||
PARAMS.inPerTick * PARAMS.trackWidthTicks,
|
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
||||||
PARAMS.inPerTick / PARAMS.lateralInPerTick);
|
|
||||||
|
|
||||||
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
|
||||||
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
|
||||||
|
|
||||||
public final VelConstraint defaultVelConstraint =
|
public final VelConstraint defaultVelConstraint =
|
||||||
new MinVelConstraint(Arrays.asList(
|
new MinVelConstraint(Arrays.asList(
|
||||||
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
|
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
|
||||||
new AngularVelConstraint(PARAMS.maxAngVel)
|
new AngularVelConstraint(PARAMS.maxAngVel)
|
||||||
));
|
));
|
||||||
|
|
||||||
public final AccelConstraint defaultAccelConstraint =
|
public final AccelConstraint defaultAccelConstraint =
|
||||||
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
|
||||||
|
|
||||||
@ -140,7 +136,9 @@ public final class MecanumDrive {
|
|||||||
leftBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftBack));
|
leftBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.leftBack));
|
||||||
rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack));
|
rightBack = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightBack));
|
||||||
rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront));
|
rightFront = new OverflowEncoder(new RawEncoder(MecanumDrive.this.rightFront));
|
||||||
|
|
||||||
imu = lazyImu.get();
|
imu = lazyImu.get();
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
@ -216,34 +214,34 @@ public final class MecanumDrive {
|
|||||||
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
// TODO: make sure your config has motors with these names (or change them)
|
||||||
Configure motors definitions
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
*/
|
leftFront = hardwareMap.get(DcMotorEx.class, "Drive front lt");
|
||||||
leftFront = hardwareMap.get(DcMotorEx.class, FRONT_LEFT_MOTOR);
|
leftBack = hardwareMap.get(DcMotorEx.class, "Drive back lt");
|
||||||
leftBack = hardwareMap.get(DcMotorEx.class, BACK_LEFT_MOTOR);
|
rightBack = hardwareMap.get(DcMotorEx.class, "Drive back rt");
|
||||||
rightFront = hardwareMap.get(DcMotorEx.class, FRONT_RIGHT_MOTOR);
|
rightFront = hardwareMap.get(DcMotorEx.class, "Drive front rt");
|
||||||
rightBack = hardwareMap.get(DcMotorEx.class, BACK_RIGHT_MOTOR);
|
|
||||||
|
|
||||||
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||||
|
|
||||||
/*
|
// TODO: reverse motor directions if needed
|
||||||
Configure motors direction
|
// leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
*/
|
rightFront.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||||
//leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
rightBack.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||||
|
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
|
||||||
/*
|
|
||||||
IMU Orientation Application
|
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
|
||||||
See https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
|
||||||
*/
|
|
||||||
lazyImu = new LazyImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
lazyImu = new LazyImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
|
||||||
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
|
||||||
|
|
||||||
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
voltageSensor = hardwareMap.voltageSensor.iterator().next();
|
||||||
|
|
||||||
localizer = new DriveLocalizer();
|
localizer = new ThreeDeadWheelLocalizer(hardwareMap, PARAMS.inPerTick);
|
||||||
|
|
||||||
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
|
||||||
}
|
}
|
||||||
|
@ -1,22 +0,0 @@
|
|||||||
package org.firstinspires.ftc.teamcode;
|
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
|
||||||
|
|
||||||
public class MecanumDriveParameters {
|
|
||||||
|
|
||||||
// Roadrunner tuning parameters
|
|
||||||
public static final double INCHES_PER_TICK_VALUE = 125.5/42126.8333333;
|
|
||||||
public static final double LATERAL_INCHES_PER_TICK_VALUE = 0.0026542073080477006;
|
|
||||||
public static final double TRACK_WIDTH_IN_TICKS_VALUE = 4012.7667474312616;
|
|
||||||
|
|
||||||
// FeedForward parameters (in tick units)
|
|
||||||
public static final double KS_VALUE = 0.7579547290234911;
|
|
||||||
public static final double KV_VALUE = 0.0005724562271687877;
|
|
||||||
public static final double KA_VALUE = 0;
|
|
||||||
|
|
||||||
// Robot motor configurations
|
|
||||||
public static final String FRONT_LEFT_MOTOR = "Drive front lt";
|
|
||||||
public static final String BACK_LEFT_MOTOR = "Drive back lt";
|
|
||||||
public static final String FRONT_RIGHT_MOTOR = "Drive front rt";
|
|
||||||
public static final String BACK_RIGHT_MOTOR = "Drive back rt";
|
|
||||||
}
|
|
@ -1,144 +0,0 @@
|
|||||||
/* Copyright (c) 2022 FIRST. All rights reserved.
|
|
||||||
*
|
|
||||||
* Redistribution and use in source and binary forms, with or without modification,
|
|
||||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
|
||||||
* the following conditions are met:
|
|
||||||
*
|
|
||||||
* Redistributions of source code must retain the above copyright notice, this list
|
|
||||||
* of conditions and the following disclaimer.
|
|
||||||
*
|
|
||||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
|
||||||
* list of conditions and the following disclaimer in the documentation and/or
|
|
||||||
* other materials provided with the distribution.
|
|
||||||
*
|
|
||||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
|
||||||
* promote products derived from this software without specific prior written permission.
|
|
||||||
*
|
|
||||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
|
||||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
|
||||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
|
||||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
|
||||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
|
||||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
|
||||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
|
||||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
|
||||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
|
||||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
|
||||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
|
||||||
*/
|
|
||||||
|
|
||||||
package org.firstinspires.ftc.teamcode;
|
|
||||||
|
|
||||||
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
|
||||||
import com.qualcomm.robotcore.hardware.IMU;
|
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.AngularVelocity;
|
|
||||||
import org.firstinspires.ftc.robotcore.external.navigation.YawPitchRollAngles;
|
|
||||||
|
|
||||||
/*
|
|
||||||
* This OpMode shows how to use the new universal IMU interface. This
|
|
||||||
* interface may be used with the BNO055 IMU or the BHI260 IMU. It assumes that an IMU is configured
|
|
||||||
* on the robot with the name "imu".
|
|
||||||
*
|
|
||||||
* The sample will display the current Yaw, Pitch and Roll of the robot.<br>
|
|
||||||
* With the correct orientation parameters selected, pitch/roll/yaw should act as follows:
|
|
||||||
* Pitch value should INCREASE as the robot is tipped UP at the front. (Rotation about X) <br>
|
|
||||||
* Roll value should INCREASE as the robot is tipped UP at the left side. (Rotation about Y) <br>
|
|
||||||
* Yaw value should INCREASE as the robot is rotated Counter Clockwise. (Rotation about Z) <br>
|
|
||||||
*
|
|
||||||
* The yaw can be reset (to zero) by pressing the Y button on the gamepad (Triangle on a PS4 controller)
|
|
||||||
*
|
|
||||||
* This specific sample assumes that the Hub is mounted on one of the three orthogonal planes
|
|
||||||
* (X/Y, X/Z or Y/Z) and that the Hub has only been rotated in a range of 90 degree increments.
|
|
||||||
*
|
|
||||||
* Note: if your Hub is mounted on a surface angled at some non-90 Degree multiple (like 30) look at
|
|
||||||
* the alternative SensorImuNonOrthogonal sample in this folder.
|
|
||||||
*
|
|
||||||
* This "Orthogonal" requirement means that:
|
|
||||||
*
|
|
||||||
* 1) The Logo printed on the top of the Hub can ONLY be pointing in one of six directions:
|
|
||||||
* FORWARD, BACKWARD, UP, DOWN, LEFT and RIGHT.
|
|
||||||
*
|
|
||||||
* 2) The USB ports can only be pointing in one of the same six directions:<br>
|
|
||||||
* FORWARD, BACKWARD, UP, DOWN, LEFT and RIGHT.
|
|
||||||
*
|
|
||||||
* So, To fully define how your Hub is mounted to the robot, you must simply specify:<br>
|
|
||||||
* logoFacingDirection<br>
|
|
||||||
* usbFacingDirection
|
|
||||||
*
|
|
||||||
* Use Android Studio to Copy this Class, and Paste it into your team's code folder with a new name.
|
|
||||||
* Remove or comment out the @Disabled line to add this OpMode to the Driver Station OpMode list.
|
|
||||||
*
|
|
||||||
* Finally, choose the two correct parameters to define how your Hub is mounted and edit this OpMode
|
|
||||||
* to use those parameters.
|
|
||||||
*/
|
|
||||||
@TeleOp(name = "Sensor: IMU Orthogonal", group = "Sensor")
|
|
||||||
@Disabled // Comment this out to add to the OpMode list
|
|
||||||
public class SensorIMUOrthogonal extends LinearOpMode
|
|
||||||
{
|
|
||||||
// The IMU sensor object
|
|
||||||
IMU imu;
|
|
||||||
|
|
||||||
//----------------------------------------------------------------------------------------------
|
|
||||||
// Main logic
|
|
||||||
//----------------------------------------------------------------------------------------------
|
|
||||||
|
|
||||||
@Override public void runOpMode() throws InterruptedException {
|
|
||||||
|
|
||||||
// Retrieve and initialize the IMU.
|
|
||||||
// This sample expects the IMU to be in a REV Hub and named "imu".
|
|
||||||
imu = hardwareMap.get(IMU.class, "imu");
|
|
||||||
|
|
||||||
/* Define how the hub is mounted on the robot to get the correct Yaw, Pitch and Roll values.
|
|
||||||
*
|
|
||||||
* Two input parameters are required to fully specify the Orientation.
|
|
||||||
* The first parameter specifies the direction the printed logo on the Hub is pointing.
|
|
||||||
* The second parameter specifies the direction the USB connector on the Hub is pointing.
|
|
||||||
* All directions are relative to the robot, and left/right is as-viewed from behind the robot.
|
|
||||||
*/
|
|
||||||
|
|
||||||
/* The next two lines define Hub orientation.
|
|
||||||
* The Default Orientation (shown) is when a hub is mounted horizontally with the printed logo pointing UP and the USB port pointing FORWARD.
|
|
||||||
*
|
|
||||||
* To Do: EDIT these two lines to match YOUR mounting configuration.
|
|
||||||
*/
|
|
||||||
RevHubOrientationOnRobot.LogoFacingDirection logoDirection = RevHubOrientationOnRobot.LogoFacingDirection.UP;
|
|
||||||
RevHubOrientationOnRobot.UsbFacingDirection usbDirection = RevHubOrientationOnRobot.UsbFacingDirection.FORWARD;
|
|
||||||
|
|
||||||
RevHubOrientationOnRobot orientationOnRobot = new RevHubOrientationOnRobot(logoDirection, usbDirection);
|
|
||||||
|
|
||||||
// Now initialize the IMU with this mounting orientation
|
|
||||||
// Note: if you choose two conflicting directions, this initialization will cause a code exception.
|
|
||||||
imu.initialize(new IMU.Parameters(orientationOnRobot));
|
|
||||||
|
|
||||||
// Loop and update the dashboard
|
|
||||||
while (!isStopRequested()) {
|
|
||||||
|
|
||||||
telemetry.addData("Hub orientation", "Logo=%s USB=%s\n ", logoDirection, usbDirection);
|
|
||||||
|
|
||||||
// Check to see if heading reset is requested
|
|
||||||
if (gamepad1.y) {
|
|
||||||
telemetry.addData("Yaw", "Resetting\n");
|
|
||||||
imu.resetYaw();
|
|
||||||
} else {
|
|
||||||
telemetry.addData("Yaw", "Press Y (triangle) on Gamepad to reset\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
// Retrieve Rotational Angles and Velocities
|
|
||||||
YawPitchRollAngles orientation = imu.getRobotYawPitchRollAngles();
|
|
||||||
AngularVelocity angularVelocity = imu.getRobotAngularVelocity(AngleUnit.DEGREES);
|
|
||||||
|
|
||||||
telemetry.addData("Yaw (Z)", "%.2f Deg. (Heading)", orientation.getYaw(AngleUnit.DEGREES));
|
|
||||||
telemetry.addData("Pitch (X)", "%.2f Deg.", orientation.getPitch(AngleUnit.DEGREES));
|
|
||||||
telemetry.addData("Roll (Y)", "%.2f Deg.\n", orientation.getRoll(AngleUnit.DEGREES));
|
|
||||||
telemetry.addData("Yaw (Z) velocity", "%.2f Deg/Sec", angularVelocity.zRotationRate);
|
|
||||||
telemetry.addData("Pitch (X) velocity", "%.2f Deg/Sec", angularVelocity.xRotationRate);
|
|
||||||
telemetry.addData("Roll (Y) velocity", "%.2f Deg/Sec", angularVelocity.yRotationRate);
|
|
||||||
telemetry.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
Reference in New Issue
Block a user