Added Pinpoint Localization!
This commit is contained in:
@ -4,7 +4,7 @@ the pose exponential method of localization. It's basically a way of turning mov
|
||||
robot's coordinate frame to the global coordinate frame. If you're interested in reading more about
|
||||
it, then check out pages 177 - 183 of [Controls Engineering in the FIRST Robotics Competition](https://file.tavsys.net/control/controls-engineering-in-frc.pdf)
|
||||
by Tyler Veness. However, the OTOS localizer uses its own onboard system for calculating localization,
|
||||
which I do not know about.
|
||||
which we do not know about.
|
||||
|
||||
## Setting Your Localizer
|
||||
Go to line `70` in the `PoseUpdater` class, and replace the `new ThreeWheelLocalizer(hardwareMap)`
|
||||
@ -15,6 +15,7 @@ with the localizer that applies to you:
|
||||
don't change it from the default
|
||||
* If you're using three wheel odometry with the IMU, put `new ThreeWheelIMULocalizer(hardwareMap)`
|
||||
* If you're using OTOS, put `new OTOSLocalizer(hardwareMap)`
|
||||
* If you're using Pinpoint, put `new PinpointLocalizer(hardwareMap)`
|
||||
|
||||
## Tuning
|
||||
To start, you'll want to select your localizer of choice. Below, I'll have instructions for the drive
|
||||
@ -241,6 +242,23 @@ that applies to you and follow the directions there.
|
||||
robot around and see if the movements look accurate on FTC Dashboard. If they don't, then you'll
|
||||
want to re-run some of the previous steps. Otherwise, congrats on tuning your localizer!
|
||||
|
||||
## Pinpoint Localizer
|
||||
* First you will need to plug in the pinpoint to the i2c port. Ensure that the dead wheel encoder wires are
|
||||
plugged into the proper ports on the pinpoint to ensure no error within the tuning steps.
|
||||
* Then, go to the `PinpointLocalier.java` file and go to where it tells you to replace
|
||||
the current statement with your pinpoint port in the constructor. Replace the `deviceName` parameter
|
||||
with the name of the port that the pinpoint is connected to.
|
||||
* Next, follow the instructions left by the TODO: comment and enter in the odometry measurements either in
|
||||
mms or inches (We have the conversion rates listed).
|
||||
* First, to ensure that your pinpoint is properly connected, please run the `SensorGoBildaPinpointExample.java`
|
||||
file left in the `tuning` folder located within `localization`.
|
||||
* Once completed, the localizer should be properly tuned. To test it out, you can go to
|
||||
`Localization Test` and push around or drive around your robot. Go to [FTC Dashboard](http://192.168.43.1:8080/dash)
|
||||
and on the top right, switch the drop down from the default view to the field view. Then, on the bottom
|
||||
left corner, you should see a field and the robot being drawn on the field. You can then move your
|
||||
robot around and see if the movements look accurate on FTC Dashboard. If they don't, then you'll
|
||||
want to re-run some of the previous steps. Otherwise, congrats on tuning your localizer!
|
||||
|
||||
## Using Road Runner's Localizer
|
||||
Of course, many teams have experience using Road Runner in the past and so have localizers from Road
|
||||
Runner that are tuned. There is an adapter for the Road Runner three wheel localizer to the Pedro
|
||||
|
@ -105,4 +105,5 @@ of the curvature formula, we can estimate a centripetal force correction and app
|
||||
control.
|
||||
|
||||
## Questions?
|
||||
If you still have more questions, feel free to contact us at `scottsbots10158@gmail.com`
|
||||
If you still have more questions, feel free to contact us at `scottsbots10158@gmail.com` or
|
||||
within our discord linked here(https://discord.gg/2GfC4qBP5s)
|
@ -0,0 +1,513 @@
|
||||
|
||||
/* MIT License
|
||||
* Copyright (c) [2024] [Base 10 Assets, LLC]
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
|
||||
* The above copyright notice and this permission notice shall be included in all
|
||||
* copies or substantial portions of the Software.
|
||||
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.teamcode.pedroPathing.localization;
|
||||
|
||||
import static com.qualcomm.robotcore.util.TypeConversion.byteArrayToInt;
|
||||
|
||||
import com.qualcomm.hardware.lynx.LynxI2cDeviceSynch;
|
||||
import com.qualcomm.robotcore.hardware.I2cAddr;
|
||||
import com.qualcomm.robotcore.hardware.I2cDeviceSynchDevice;
|
||||
import com.qualcomm.robotcore.hardware.I2cDeviceSynchSimple;
|
||||
import com.qualcomm.robotcore.hardware.configuration.annotations.DeviceProperties;
|
||||
import com.qualcomm.robotcore.hardware.configuration.annotations.I2cDeviceType;
|
||||
import com.qualcomm.robotcore.util.TypeConversion;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose2D;
|
||||
|
||||
import java.nio.ByteBuffer;
|
||||
import java.nio.ByteOrder;
|
||||
import java.util.Arrays;
|
||||
|
||||
|
||||
@I2cDeviceType
|
||||
@DeviceProperties(
|
||||
name = "goBILDA® Pinpoint Odometry Computer",
|
||||
xmlTag = "goBILDAPinpoint",
|
||||
description ="goBILDA® Pinpoint Odometry Computer (IMU Sensor Fusion for 2 Wheel Odometry)"
|
||||
)
|
||||
|
||||
public class GoBildaPinpointDriver extends I2cDeviceSynchDevice<I2cDeviceSynchSimple> {
|
||||
|
||||
private int deviceStatus = 0;
|
||||
private int loopTime = 0;
|
||||
private int xEncoderValue = 0;
|
||||
private int yEncoderValue = 0;
|
||||
private float xPosition = 0;
|
||||
private float yPosition = 0;
|
||||
private float hOrientation = 0;
|
||||
private float xVelocity = 0;
|
||||
private float yVelocity = 0;
|
||||
private float hVelocity = 0;
|
||||
|
||||
private static final float goBILDA_SWINGARM_POD = 13.26291192f; //ticks-per-mm for the goBILDA Swingarm Pod
|
||||
private static final float goBILDA_4_BAR_POD = 19.89436789f; //ticks-per-mm for the goBILDA 4-Bar Pod
|
||||
|
||||
//i2c address of the device
|
||||
public static final byte DEFAULT_ADDRESS = 0x31;
|
||||
|
||||
public GoBildaPinpointDriver(I2cDeviceSynchSimple deviceClient, boolean deviceClientIsOwned) {
|
||||
super(deviceClient, deviceClientIsOwned);
|
||||
|
||||
this.deviceClient.setI2cAddress(I2cAddr.create7bit(DEFAULT_ADDRESS));
|
||||
super.registerArmingStateCallback(false);
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
public Manufacturer getManufacturer() {
|
||||
return Manufacturer.Other;
|
||||
}
|
||||
|
||||
@Override
|
||||
protected synchronized boolean doInitialize() {
|
||||
((LynxI2cDeviceSynch)(deviceClient)).setBusSpeed(LynxI2cDeviceSynch.BusSpeed.FAST_400K);
|
||||
return true;
|
||||
}
|
||||
|
||||
@Override
|
||||
public String getDeviceName() {
|
||||
return "goBILDA® Pinpoint Odometry Computer";
|
||||
}
|
||||
|
||||
|
||||
//Register map of the i2c device
|
||||
private enum Register {
|
||||
DEVICE_ID (1),
|
||||
DEVICE_VERSION (2),
|
||||
DEVICE_STATUS (3),
|
||||
DEVICE_CONTROL (4),
|
||||
LOOP_TIME (5),
|
||||
X_ENCODER_VALUE (6),
|
||||
Y_ENCODER_VALUE (7),
|
||||
X_POSITION (8),
|
||||
Y_POSITION (9),
|
||||
H_ORIENTATION (10),
|
||||
X_VELOCITY (11),
|
||||
Y_VELOCITY (12),
|
||||
H_VELOCITY (13),
|
||||
MM_PER_TICK (14),
|
||||
X_POD_OFFSET (15),
|
||||
Y_POD_OFFSET (16),
|
||||
YAW_SCALAR (17),
|
||||
BULK_READ (18);
|
||||
|
||||
private final int bVal;
|
||||
|
||||
Register(int bVal){
|
||||
this.bVal = bVal;
|
||||
}
|
||||
}
|
||||
|
||||
//Device Status enum that captures the current fault condition of the device
|
||||
public enum DeviceStatus{
|
||||
NOT_READY (0),
|
||||
READY (1),
|
||||
CALIBRATING (1 << 1),
|
||||
FAULT_X_POD_NOT_DETECTED (1 << 2),
|
||||
FAULT_Y_POD_NOT_DETECTED (1 << 3),
|
||||
FAULT_NO_PODS_DETECTED (1 << 2 | 1 << 3),
|
||||
FAULT_IMU_RUNAWAY (1 << 4);
|
||||
|
||||
private final int status;
|
||||
|
||||
DeviceStatus(int status){
|
||||
this.status = status;
|
||||
}
|
||||
}
|
||||
|
||||
//enum that captures the direction the encoders are set to
|
||||
public enum EncoderDirection{
|
||||
FORWARD,
|
||||
REVERSED;
|
||||
}
|
||||
|
||||
//enum that captures the kind of goBILDA odometry pods, if goBILDA pods are used
|
||||
public enum GoBildaOdometryPods {
|
||||
goBILDA_SWINGARM_POD,
|
||||
goBILDA_4_BAR_POD;
|
||||
}
|
||||
//enum that captures a limited scope of read data. More options may be added in future update
|
||||
public enum readData {
|
||||
ONLY_UPDATE_HEADING,
|
||||
}
|
||||
|
||||
|
||||
/** Writes an int to the i2c device
|
||||
@param reg the register to write the int to
|
||||
@param i the integer to write to the register
|
||||
*/
|
||||
private void writeInt(final Register reg, int i){
|
||||
deviceClient.write(reg.bVal, TypeConversion.intToByteArray(i,ByteOrder.LITTLE_ENDIAN));
|
||||
}
|
||||
|
||||
/**
|
||||
* Reads an int from a register of the i2c device
|
||||
* @param reg the register to read from
|
||||
* @return returns an int that contains the value stored in the read register
|
||||
*/
|
||||
private int readInt(Register reg){
|
||||
return byteArrayToInt(deviceClient.read(reg.bVal,4), ByteOrder.LITTLE_ENDIAN);
|
||||
}
|
||||
|
||||
/**
|
||||
* Converts a byte array to a float value
|
||||
* @param byteArray byte array to transform
|
||||
* @param byteOrder order of byte array to convert
|
||||
* @return the float value stored by the byte array
|
||||
*/
|
||||
private float byteArrayToFloat(byte[] byteArray, ByteOrder byteOrder){
|
||||
return ByteBuffer.wrap(byteArray).order(byteOrder).getFloat();
|
||||
}
|
||||
/**
|
||||
* Reads a float from a register
|
||||
* @param reg the register to read
|
||||
* @return the float value stored in that register
|
||||
*/
|
||||
|
||||
private float readFloat(Register reg){
|
||||
return byteArrayToFloat(deviceClient.read(reg.bVal,4),ByteOrder.LITTLE_ENDIAN);
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Converts a float to a byte array
|
||||
* @param value the float array to convert
|
||||
* @return the byte array converted from the float
|
||||
*/
|
||||
private byte [] floatToByteArray (float value, ByteOrder byteOrder) {
|
||||
return ByteBuffer.allocate(4).order(byteOrder).putFloat(value).array();
|
||||
}
|
||||
|
||||
/**
|
||||
* Writes a byte array to a register on the i2c device
|
||||
* @param reg the register to write to
|
||||
* @param bytes the byte array to write
|
||||
*/
|
||||
private void writeByteArray (Register reg, byte[] bytes){
|
||||
deviceClient.write(reg.bVal,bytes);
|
||||
}
|
||||
|
||||
/**
|
||||
* Writes a float to a register on the i2c device
|
||||
* @param reg the register to write to
|
||||
* @param f the float to write
|
||||
*/
|
||||
private void writeFloat (Register reg, float f){
|
||||
byte[] bytes = ByteBuffer.allocate(4).order(ByteOrder.LITTLE_ENDIAN).putFloat(f).array();
|
||||
deviceClient.write(reg.bVal,bytes);
|
||||
}
|
||||
|
||||
/**
|
||||
* Looks up the DeviceStatus enum corresponding with an int value
|
||||
* @param s int to lookup
|
||||
* @return the Odometry Computer state
|
||||
*/
|
||||
private DeviceStatus lookupStatus (int s){
|
||||
if ((s & DeviceStatus.CALIBRATING.status) != 0){
|
||||
return DeviceStatus.CALIBRATING;
|
||||
}
|
||||
boolean xPodDetected = (s & DeviceStatus.FAULT_X_POD_NOT_DETECTED.status) == 0;
|
||||
boolean yPodDetected = (s & DeviceStatus.FAULT_Y_POD_NOT_DETECTED.status) == 0;
|
||||
|
||||
if(!xPodDetected && !yPodDetected){
|
||||
return DeviceStatus.FAULT_NO_PODS_DETECTED;
|
||||
}
|
||||
if (!xPodDetected){
|
||||
return DeviceStatus.FAULT_X_POD_NOT_DETECTED;
|
||||
}
|
||||
if (!yPodDetected){
|
||||
return DeviceStatus.FAULT_Y_POD_NOT_DETECTED;
|
||||
}
|
||||
if ((s & DeviceStatus.FAULT_IMU_RUNAWAY.status) != 0){
|
||||
return DeviceStatus.FAULT_IMU_RUNAWAY;
|
||||
}
|
||||
if ((s & DeviceStatus.READY.status) != 0){
|
||||
return DeviceStatus.READY;
|
||||
}
|
||||
else {
|
||||
return DeviceStatus.NOT_READY;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Call this once per loop to read new data from the Odometry Computer. Data will only update once this is called.
|
||||
*/
|
||||
public void update(){
|
||||
byte[] bArr = deviceClient.read(Register.BULK_READ.bVal, 40);
|
||||
deviceStatus = byteArrayToInt(Arrays.copyOfRange (bArr, 0, 4), ByteOrder.LITTLE_ENDIAN);
|
||||
loopTime = byteArrayToInt(Arrays.copyOfRange (bArr, 4, 8), ByteOrder.LITTLE_ENDIAN);
|
||||
xEncoderValue = byteArrayToInt(Arrays.copyOfRange (bArr, 8, 12), ByteOrder.LITTLE_ENDIAN);
|
||||
yEncoderValue = byteArrayToInt(Arrays.copyOfRange (bArr, 12,16), ByteOrder.LITTLE_ENDIAN);
|
||||
xPosition = byteArrayToFloat(Arrays.copyOfRange(bArr, 16,20), ByteOrder.LITTLE_ENDIAN);
|
||||
yPosition = byteArrayToFloat(Arrays.copyOfRange(bArr, 20,24), ByteOrder.LITTLE_ENDIAN);
|
||||
hOrientation = byteArrayToFloat(Arrays.copyOfRange(bArr, 24,28), ByteOrder.LITTLE_ENDIAN);
|
||||
xVelocity = byteArrayToFloat(Arrays.copyOfRange(bArr, 28,32), ByteOrder.LITTLE_ENDIAN);
|
||||
yVelocity = byteArrayToFloat(Arrays.copyOfRange(bArr, 32,36), ByteOrder.LITTLE_ENDIAN);
|
||||
hVelocity = byteArrayToFloat(Arrays.copyOfRange(bArr, 36,40), ByteOrder.LITTLE_ENDIAN);
|
||||
}
|
||||
|
||||
/**
|
||||
* Call this once per loop to read new data from the Odometry Computer. This is an override of the update() function
|
||||
* which allows a narrower range of data to be read from the device for faster read times. Currently ONLY_UPDATE_HEADING
|
||||
* is supported.
|
||||
* @param data GoBildaPinpointDriver.readData.ONLY_UPDATE_HEADING
|
||||
*/
|
||||
public void update(readData data) {
|
||||
if (data == readData.ONLY_UPDATE_HEADING) {
|
||||
hOrientation = byteArrayToFloat(deviceClient.read(Register.H_ORIENTATION.bVal, 4), ByteOrder.LITTLE_ENDIAN);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the odometry pod positions relative to the point that the odometry computer tracks around.<br><br>
|
||||
* The most common tracking position is the center of the robot. <br> <br>
|
||||
* The X pod offset refers to how far sideways (in mm) from the tracking point the X (forward) odometry pod is. Left of the center is a positive number, right of center is a negative number. <br>
|
||||
* the Y pod offset refers to how far forwards (in mm) from the tracking point the Y (strafe) odometry pod is. forward of center is a positive number, backwards is a negative number.<br>
|
||||
* @param xOffset how sideways from the center of the robot is the X (forward) pod? Left increases
|
||||
* @param yOffset how far forward from the center of the robot is the Y (Strafe) pod? forward increases
|
||||
*/
|
||||
public void setOffsets(double xOffset, double yOffset){
|
||||
writeFloat(Register.X_POD_OFFSET, (float) xOffset);
|
||||
writeFloat(Register.Y_POD_OFFSET, (float) yOffset);
|
||||
}
|
||||
|
||||
/**
|
||||
* Recalibrates the Odometry Computer's internal IMU. <br><br>
|
||||
* <strong> Robot MUST be stationary </strong> <br><br>
|
||||
* Device takes a large number of samples, and uses those as the gyroscope zero-offset. This takes approximately 0.25 seconds.
|
||||
*/
|
||||
public void recalibrateIMU(){writeInt(Register.DEVICE_CONTROL,1<<0);}
|
||||
|
||||
/**
|
||||
* Resets the current position to 0,0,0 and recalibrates the Odometry Computer's internal IMU. <br><br>
|
||||
* <strong> Robot MUST be stationary </strong> <br><br>
|
||||
* Device takes a large number of samples, and uses those as the gyroscope zero-offset. This takes approximately 0.25 seconds.
|
||||
*/
|
||||
public void resetPosAndIMU(){writeInt(Register.DEVICE_CONTROL,1<<1);}
|
||||
|
||||
/**
|
||||
* Can reverse the direction of each encoder.
|
||||
* @param xEncoder FORWARD or REVERSED, X (forward) pod should increase when the robot is moving forward
|
||||
* @param yEncoder FORWARD or REVERSED, Y (strafe) pod should increase when the robot is moving left
|
||||
*/
|
||||
public void setEncoderDirections(EncoderDirection xEncoder, EncoderDirection yEncoder){
|
||||
if (xEncoder == EncoderDirection.REVERSED) {
|
||||
writeInt(Register.DEVICE_CONTROL,1<<4);
|
||||
}
|
||||
if (yEncoder == EncoderDirection.REVERSED){
|
||||
writeInt(Register.DEVICE_CONTROL,1<<2);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* If you're using goBILDA odometry pods, the ticks-per-mm values are stored here for easy access.<br><br>
|
||||
* @param pods goBILDA_SWINGARM_POD or goBILDA_4_BAR_POD
|
||||
*/
|
||||
public void setEncoderResolution(GoBildaOdometryPods pods){
|
||||
if (pods == GoBildaOdometryPods.goBILDA_SWINGARM_POD) {
|
||||
writeByteArray(Register.MM_PER_TICK, (floatToByteArray(goBILDA_SWINGARM_POD, ByteOrder.LITTLE_ENDIAN)));
|
||||
}
|
||||
if (pods == GoBildaOdometryPods.goBILDA_4_BAR_POD){
|
||||
writeByteArray(Register.MM_PER_TICK,(floatToByteArray(goBILDA_4_BAR_POD, ByteOrder.LITTLE_ENDIAN)));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the encoder resolution in ticks per mm of the odometry pods. <br>
|
||||
* You can find this number by dividing the counts-per-revolution of your encoder by the circumference of the wheel.
|
||||
* @param ticks_per_mm should be somewhere between 10 ticks/mm and 100 ticks/mm a goBILDA Swingarm pod is ~13.26291192
|
||||
*/
|
||||
public void setEncoderResolution(double ticks_per_mm){
|
||||
writeByteArray(Register.MM_PER_TICK,(floatToByteArray((float) ticks_per_mm,ByteOrder.LITTLE_ENDIAN)));
|
||||
}
|
||||
|
||||
/**
|
||||
* Tuning this value should be unnecessary.<br>
|
||||
* The goBILDA Odometry Computer has a per-device tuned yaw offset already applied when you receive it.<br><br>
|
||||
* This is a scalar that is applied to the gyro's yaw value. Increasing it will mean it will report more than one degree for every degree the sensor fusion algorithm measures. <br><br>
|
||||
* You can tune this variable by rotating the robot a large amount (10 full turns is a good starting place) and comparing the amount that the robot rotated to the amount measured.
|
||||
* Rotating the robot exactly 10 times should measure 3600°. If it measures more or less, divide moved amount by the measured amount and apply that value to the Yaw Offset.<br><br>
|
||||
* If you find that to get an accurate heading number you need to apply a scalar of more than 1.05, or less than 0.95, your device may be bad. Please reach out to tech@gobilda.com
|
||||
* @param yawOffset A scalar for the robot's heading.
|
||||
*/
|
||||
public void setYawScalar(double yawOffset){
|
||||
writeByteArray(Register.YAW_SCALAR,(floatToByteArray((float) yawOffset, ByteOrder.LITTLE_ENDIAN)));
|
||||
}
|
||||
|
||||
/**
|
||||
* Send a position that the Pinpoint should use to track your robot relative to. You can use this to
|
||||
* update the estimated position of your robot with new external sensor data, or to run a robot
|
||||
* in field coordinates. <br><br>
|
||||
* This overrides the current position. <br><br>
|
||||
* <strong>Using this feature to track your robot's position in field coordinates:</strong> <br>
|
||||
* When you start your code, send a Pose2D that describes the starting position on the field of your robot. <br>
|
||||
* Say you're on the red alliance, your robot is against the wall and closer to the audience side,
|
||||
* and the front of your robot is pointing towards the center of the field.
|
||||
* You can send a setPosition with something like -600mm x, -1200mm Y, and 90 degrees. The pinpoint would then always
|
||||
* keep track of how far away from the center of the field you are. <br><br>
|
||||
* <strong>Using this feature to update your position with additional sensors: </strong><br>
|
||||
* Some robots have a secondary way to locate their robot on the field. This is commonly
|
||||
* Apriltag localization in FTC, but it can also be something like a distance sensor.
|
||||
* Often these external sensors are absolute (meaning they measure something about the field)
|
||||
* so their data is very accurate. But they can be slower to read, or you may need to be in a very specific
|
||||
* position on the field to use them. In that case, spend most of your time relying on the Pinpoint
|
||||
* to determine your location. Then when you pull a new position from your secondary sensor,
|
||||
* send a setPosition command with the new position. The Pinpoint will then track your movement
|
||||
* relative to that new, more accurate position.
|
||||
* @param pos a Pose2D describing the robot's new position.
|
||||
*/
|
||||
public Pose2D setPosition(Pose2D pos){
|
||||
writeByteArray(Register.X_POSITION,(floatToByteArray((float) pos.getX(DistanceUnit.MM), ByteOrder.LITTLE_ENDIAN)));
|
||||
writeByteArray(Register.Y_POSITION,(floatToByteArray((float) pos.getY(DistanceUnit.MM),ByteOrder.LITTLE_ENDIAN)));
|
||||
writeByteArray(Register.H_ORIENTATION,(floatToByteArray((float) pos.getHeading(AngleUnit.RADIANS),ByteOrder.LITTLE_ENDIAN)));
|
||||
return pos;
|
||||
}
|
||||
|
||||
/**
|
||||
* Checks the deviceID of the Odometry Computer. Should return 1.
|
||||
* @return 1 if device is functional.
|
||||
*/
|
||||
public int getDeviceID(){return readInt(Register.DEVICE_ID);}
|
||||
|
||||
/**
|
||||
* @return the firmware version of the Odometry Computer
|
||||
*/
|
||||
public int getDeviceVersion(){return readInt(Register.DEVICE_VERSION); }
|
||||
|
||||
public float getYawScalar(){return readFloat(Register.YAW_SCALAR); }
|
||||
|
||||
/**
|
||||
* Device Status stores any faults the Odometry Computer may be experiencing. These faults include:
|
||||
* @return one of the following states:<br>
|
||||
* NOT_READY - The device is currently powering up. And has not initialized yet. RED LED<br>
|
||||
* READY - The device is currently functioning as normal. GREEN LED<br>
|
||||
* CALIBRATING - The device is currently recalibrating the gyro. RED LED<br>
|
||||
* FAULT_NO_PODS_DETECTED - the device does not detect any pods plugged in. PURPLE LED <br>
|
||||
* FAULT_X_POD_NOT_DETECTED - The device does not detect an X pod plugged in. BLUE LED <br>
|
||||
* FAULT_Y_POD_NOT_DETECTED - The device does not detect a Y pod plugged in. ORANGE LED <br>
|
||||
*/
|
||||
public DeviceStatus getDeviceStatus(){return lookupStatus(deviceStatus); }
|
||||
|
||||
/**
|
||||
* Checks the Odometry Computer's most recent loop time.<br><br>
|
||||
* If values less than 500, or more than 1100 are commonly seen here, there may be something wrong with your device. Please reach out to tech@gobilda.com
|
||||
* @return loop time in microseconds (1/1,000,000 seconds)
|
||||
*/
|
||||
public int getLoopTime(){return loopTime; }
|
||||
|
||||
/**
|
||||
* Checks the Odometry Computer's most recent loop frequency.<br><br>
|
||||
* If values less than 900, or more than 2000 are commonly seen here, there may be something wrong with your device. Please reach out to tech@gobilda.com
|
||||
* @return Pinpoint Frequency in Hz (loops per second),
|
||||
*/
|
||||
public double getFrequency(){
|
||||
if (loopTime != 0){
|
||||
return 1000000.0/loopTime;
|
||||
}
|
||||
else {
|
||||
return 0;
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* @return the raw value of the X (forward) encoder in ticks
|
||||
*/
|
||||
public int getEncoderX(){return xEncoderValue; }
|
||||
|
||||
/**
|
||||
* @return the raw value of the Y (strafe) encoder in ticks
|
||||
*/
|
||||
public int getEncoderY(){return yEncoderValue; }
|
||||
|
||||
/**
|
||||
* @return the estimated X (forward) position of the robot in mm
|
||||
*/
|
||||
public double getPosX(){return xPosition; }
|
||||
|
||||
/**
|
||||
* @return the estimated Y (Strafe) position of the robot in mm
|
||||
*/
|
||||
public double getPosY(){return yPosition; }
|
||||
|
||||
/**
|
||||
* @return the estimated H (heading) position of the robot in Radians
|
||||
*/
|
||||
public double getHeading(){return hOrientation;}
|
||||
|
||||
/**
|
||||
* @return the estimated X (forward) velocity of the robot in mm/sec
|
||||
*/
|
||||
public double getVelX(){return xVelocity; }
|
||||
|
||||
/**
|
||||
* @return the estimated Y (strafe) velocity of the robot in mm/sec
|
||||
*/
|
||||
public double getVelY(){return yVelocity; }
|
||||
|
||||
/**
|
||||
* @return the estimated H (heading) velocity of the robot in radians/sec
|
||||
*/
|
||||
public double getHeadingVelocity(){return hVelocity; }
|
||||
|
||||
/**
|
||||
* <strong> This uses its own I2C read, avoid calling this every loop. </strong>
|
||||
* @return the user-set offset for the X (forward) pod
|
||||
*/
|
||||
public float getXOffset(){return readFloat(Register.X_POD_OFFSET);}
|
||||
|
||||
/**
|
||||
* <strong> This uses its own I2C read, avoid calling this every loop. </strong>
|
||||
* @return the user-set offset for the Y (strafe) pod
|
||||
*/
|
||||
public float getYOffset(){return readFloat(Register.Y_POD_OFFSET);}
|
||||
|
||||
/**
|
||||
* @return a Pose2D containing the estimated position of the robot
|
||||
*/
|
||||
public Pose2D getPosition(){
|
||||
return new Pose2D(DistanceUnit.MM,
|
||||
xPosition,
|
||||
yPosition,
|
||||
AngleUnit.RADIANS,
|
||||
hOrientation);
|
||||
}
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* @return a Pose2D containing the estimated velocity of the robot, velocity is unit per second
|
||||
*/
|
||||
public Pose2D getVelocity(){
|
||||
return new Pose2D(DistanceUnit.MM,
|
||||
xVelocity,
|
||||
yVelocity,
|
||||
AngleUnit.RADIANS,
|
||||
hVelocity);
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
@ -0,0 +1,211 @@
|
||||
package org.firstinspires.ftc.teamcode.pedroPathing.localization.localizers;
|
||||
|
||||
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose2D;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.GoBildaPinpointDriver;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Localizer;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.MathFunctions;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Vector;
|
||||
|
||||
/**
|
||||
* This is the Pinpoint class. This class extends the Localizer superclass and is a
|
||||
* localizer that uses the two wheel odometry set up with the IMU to have more accurate heading
|
||||
* readings. The diagram below, which is modified from Road Runner, shows a typical set up.
|
||||
*
|
||||
* The view is from the top of the robot looking downwards.
|
||||
*
|
||||
* left on robot is the y positive direction
|
||||
*
|
||||
* forward on robot is the x positive direction
|
||||
*
|
||||
* /--------------\
|
||||
* | ____ |
|
||||
* | ---- |
|
||||
* | || |
|
||||
* | || | ----> left (y positive)
|
||||
* | |
|
||||
* | |
|
||||
* \--------------/
|
||||
* |
|
||||
* |
|
||||
* V
|
||||
* forward (x positive)
|
||||
* With the pinpoint your readings will be used in mm
|
||||
* to use inches ensure to divide your mm value by 25.4
|
||||
* @author Logan Nash
|
||||
* @author Havish Sripada 12808 - RevAmped Robotics
|
||||
* @author Ethan Doak - Gobilda
|
||||
* @version 1.0, 10/2/2024
|
||||
*/
|
||||
public class PinpointLocalizer extends Localizer {
|
||||
private HardwareMap hardwareMap;
|
||||
private Pose startPose;
|
||||
private GoBildaPinpointDriver odo;
|
||||
private double previousHeading;
|
||||
private double totalHeading;
|
||||
|
||||
/**
|
||||
* This creates a new PinpointLocalizer from a HardwareMap, with a starting Pose at (0,0)
|
||||
* facing 0 heading.
|
||||
*
|
||||
* @param map the HardwareMap
|
||||
*/
|
||||
public PinpointLocalizer(HardwareMap map){ this(map, new Pose());}
|
||||
|
||||
/**
|
||||
* This creates a new PinpointLocalizer from a HardwareMap and a Pose, with the Pose
|
||||
* specifying the starting pose of the localizer.
|
||||
*
|
||||
* @param map the HardwareMap
|
||||
* @param setStartPose the Pose to start from
|
||||
*/
|
||||
public PinpointLocalizer(HardwareMap map, Pose setStartPose){
|
||||
hardwareMap = map;
|
||||
// TODO: replace this with your Pinpoint port
|
||||
odo = hardwareMap.get(GoBildaPinpointDriver.class,"odo");
|
||||
|
||||
//This uses mm, to use inches divide these numbers by 25.4
|
||||
odo.setOffsets(-84.0, -168.0); //these are tuned for 3110-0002-0001 Product Insight #1
|
||||
//TODO: If you find that the gobilda Yaw Scaling is incorrect you can edit this here
|
||||
// odo.setYawScalar(1.0);
|
||||
//TODO: Set your encoder resolution here, I have the Gobilda Odometry products already included.
|
||||
//TODO: If you would like to use your own odometry pods input the ticks per mm in the commented part below
|
||||
odo.setEncoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD);
|
||||
//odo.setEncoderResolution(13.26291192);
|
||||
//TODO: Set encoder directions
|
||||
odo.setEncoderDirections(GoBildaPinpointDriver.EncoderDirection.FORWARD, GoBildaPinpointDriver.EncoderDirection.FORWARD);
|
||||
|
||||
odo.resetPosAndIMU();
|
||||
|
||||
setStartPose(setStartPose);
|
||||
totalHeading = 0;
|
||||
previousHeading = startPose.getHeading();
|
||||
|
||||
resetPinpoint();
|
||||
}
|
||||
|
||||
/**
|
||||
* This returns the current pose estimate.
|
||||
*
|
||||
* @return returns the current pose estimate as a Pose
|
||||
*/
|
||||
@Override
|
||||
public Pose getPose() {
|
||||
Pose2D pose = odo.getPosition();
|
||||
return new Pose(pose.getX(DistanceUnit.INCH), pose.getY(DistanceUnit.INCH), pose.getHeading(AngleUnit.RADIANS));
|
||||
}
|
||||
|
||||
/**
|
||||
* This returns the current velocity estimate.
|
||||
*
|
||||
* @return returns the current velocity estimate as a Pose
|
||||
*/
|
||||
@Override
|
||||
public Pose getVelocity() {
|
||||
Pose2D pose = odo.getVelocity();
|
||||
return new Pose(pose.getX(DistanceUnit.INCH), pose.getY(DistanceUnit.INCH), pose.getHeading(AngleUnit.RADIANS));
|
||||
}
|
||||
|
||||
/**
|
||||
* This returns the current velocity estimate.
|
||||
*
|
||||
* @return returns the current velocity estimate as a Vector
|
||||
*/
|
||||
@Override
|
||||
public Vector getVelocityVector() {
|
||||
Pose2D pose = odo.getVelocity();
|
||||
Vector returnVector = new Vector();
|
||||
returnVector.setOrthogonalComponents(pose.getX(DistanceUnit.INCH), pose.getY(DistanceUnit.INCH));
|
||||
return returnVector;
|
||||
}
|
||||
|
||||
/**
|
||||
* This sets the start pose. Changing the start pose should move the robot as if all its
|
||||
* previous movements were displacing it from its new start pose.
|
||||
*
|
||||
* @param setStart the new start pose
|
||||
*/
|
||||
@Override
|
||||
public void setStartPose(Pose setStart) {startPose = setStart;}
|
||||
|
||||
/**
|
||||
* This sets the current pose estimate. Changing this should just change the robot's current
|
||||
* pose estimate, not anything to do with the start pose.
|
||||
*
|
||||
* @param setPose the new current pose estimate
|
||||
*/
|
||||
@Override
|
||||
public void setPose(Pose setPose) {
|
||||
resetPinpoint();
|
||||
Pose setPinpointPose = MathFunctions.subtractPoses(setPose, startPose);
|
||||
odo.setPosition(new Pose2D(DistanceUnit.INCH, setPinpointPose.getY(), setPinpointPose.getX(), AngleUnit.RADIANS, setPinpointPose.getHeading()));
|
||||
}
|
||||
|
||||
/**
|
||||
* This updates the total heading of the robot. The Pinpoint handles all other updates itself.
|
||||
*/
|
||||
@Override
|
||||
public void update() {
|
||||
odo.update();
|
||||
totalHeading += MathFunctions.getSmallestAngleDifference(odo.getHeading(),previousHeading);
|
||||
previousHeading = odo.getHeading();
|
||||
}
|
||||
|
||||
/**
|
||||
* This returns how far the robot has turned in radians, in a number not clamped between 0 and
|
||||
* 2 * pi radians. This is used for some tuning things and nothing actually within the following.
|
||||
*
|
||||
* @return returns how far the robot has turned in total, in radians.
|
||||
*/
|
||||
@Override
|
||||
public double getTotalHeading() {
|
||||
return totalHeading;
|
||||
}
|
||||
|
||||
/**
|
||||
* This returns the Y encoder value as none of the odometry tuners are required for this localizer
|
||||
* @return returns the Y encoder value
|
||||
*/
|
||||
@Override
|
||||
public double getForwardMultiplier() {
|
||||
return odo.getEncoderY();
|
||||
}
|
||||
|
||||
/**
|
||||
* This returns the X encoder value as none of the odometry tuners are required for this localizer
|
||||
* @return returns the X encoder value
|
||||
*/
|
||||
@Override
|
||||
public double getLateralMultiplier() {
|
||||
return odo.getEncoderX();
|
||||
}
|
||||
|
||||
/**
|
||||
* This returns either the factory tuned yaw scalar or the yaw scalar tuned by yourself.
|
||||
* @return returns the yaw scalar
|
||||
*/
|
||||
@Override
|
||||
public double getTurningMultiplier() {
|
||||
return odo.getYawScalar();
|
||||
}
|
||||
|
||||
/**
|
||||
* This resets the IMU.
|
||||
*/
|
||||
@Override
|
||||
public void resetIMU() {
|
||||
odo.recalibrateIMU();
|
||||
}
|
||||
|
||||
/**
|
||||
* This resets the OTOS.
|
||||
*/
|
||||
public void resetPinpoint(){
|
||||
odo.resetPosAndIMU();
|
||||
}
|
||||
}
|
@ -0,0 +1,200 @@
|
||||
/* MIT License
|
||||
* Copyright (c) [2024] [Base 10 Assets, LLC]
|
||||
*
|
||||
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
* of this software and associated documentation files (the "Software"), to deal
|
||||
* in the Software without restriction, including without limitation the rights
|
||||
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
* copies of the Software, and to permit persons to whom the Software is
|
||||
* furnished to do so, subject to the following conditions:
|
||||
|
||||
* The above copyright notice and this permission notice shall be included in all
|
||||
* copies or substantial portions of the Software.
|
||||
|
||||
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
* SOFTWARE.
|
||||
*/
|
||||
|
||||
package org.firstinspires.ftc.teamcode.pedroPathing.localization.tuning;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose2D;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.GoBildaPinpointDriver;
|
||||
|
||||
import java.util.Locale;
|
||||
|
||||
/*
|
||||
This opmode shows how to use the goBILDA® Pinpoint Odometry Computer.
|
||||
The goBILDA Odometry Computer is a device designed to solve the Pose Exponential calculation
|
||||
commonly associated with Dead Wheel Odometry systems. It reads two encoders, and an integrated
|
||||
system of senors to determine the robot's current heading, X position, and Y position.
|
||||
|
||||
it uses an ESP32-S3 as a main cpu, with an STM LSM6DSV16X IMU.
|
||||
It is validated with goBILDA "Dead Wheel" Odometry pods, but should be compatible with any
|
||||
quadrature rotary encoder. The ESP32 PCNT peripheral is speced to decode quadrature encoder signals
|
||||
at a maximum of 40mhz per channel. Though the maximum in-application tested number is 130khz.
|
||||
|
||||
The device expects two perpendicularly mounted Dead Wheel pods. The encoder pulses are translated
|
||||
into mm and their readings are transformed by an "offset", this offset describes how far away
|
||||
the pods are from the "tracking point", usually the center of rotation of the robot.
|
||||
|
||||
Dead Wheel pods should both increase in count when moved forwards and to the left.
|
||||
The gyro will report an increase in heading when rotated counterclockwise.
|
||||
|
||||
The Pose Exponential algorithm used is described on pg 181 of this book:
|
||||
https://github.com/calcmogul/controls-engineering-in-frc
|
||||
|
||||
For support, contact tech@gobilda.com
|
||||
|
||||
-Ethan Doak
|
||||
*/
|
||||
|
||||
//TODO: If tuning comment out the @Disabled
|
||||
@TeleOp(name="goBILDA® PinPoint Odometry Example", group="Linear OpMode")
|
||||
@Disabled
|
||||
|
||||
public class SensorGoBildaPinpointExample extends LinearOpMode {
|
||||
|
||||
GoBildaPinpointDriver odo; // Declare OpMode member for the Odometry Computer
|
||||
|
||||
double oldTime = 0;
|
||||
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
// Initialize the hardware variables. Note that the strings used here must correspond
|
||||
// to the names assigned during the robot configuration step on the DS or RC devices.
|
||||
|
||||
odo = hardwareMap.get(GoBildaPinpointDriver.class,"odo");
|
||||
|
||||
/*
|
||||
Set the odometry pod positions relative to the point that the odometry computer tracks around.
|
||||
The X pod offset refers to how far sideways from the tracking point the
|
||||
X (forward) odometry pod is. Left of the center is a positive number,
|
||||
right of center is a negative number. the Y pod offset refers to how far forwards from
|
||||
the tracking point the Y (strafe) odometry pod is. forward of center is a positive number,
|
||||
backwards is a negative number.
|
||||
*/
|
||||
odo.setOffsets(-84.0, -168.0); //these are tuned for 3110-0002-0001 Product Insight #1
|
||||
|
||||
/*
|
||||
Set the kind of pods used by your robot. If you're using goBILDA odometry pods, select either
|
||||
the goBILDA_SWINGARM_POD, or the goBILDA_4_BAR_POD.
|
||||
If you're using another kind of odometry pod, uncomment setEncoderResolution and input the
|
||||
number of ticks per mm of your odometry pod.
|
||||
*/
|
||||
odo.setEncoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD);
|
||||
//odo.setEncoderResolution(13.26291192);
|
||||
|
||||
|
||||
/*
|
||||
Set the direction that each of the two odometry pods count. The X (forward) pod should
|
||||
increase when you move the robot forward. And the Y (strafe) pod should increase when
|
||||
you move the robot to the left.
|
||||
*/
|
||||
odo.setEncoderDirections(GoBildaPinpointDriver.EncoderDirection.FORWARD, GoBildaPinpointDriver.EncoderDirection.FORWARD);
|
||||
|
||||
|
||||
/*
|
||||
Before running the robot, recalibrate the IMU. This needs to happen when the robot is stationary
|
||||
The IMU will automatically calibrate when first powered on, but recalibrating before running
|
||||
the robot is a good idea to ensure that the calibration is "good".
|
||||
resetPosAndIMU will reset the position to 0,0,0 and also recalibrate the IMU.
|
||||
This is recommended before you run your autonomous, as a bad initial calibration can cause
|
||||
an incorrect starting value for x, y, and heading.
|
||||
*/
|
||||
//odo.recalibrateIMU();
|
||||
odo.resetPosAndIMU();
|
||||
|
||||
telemetry.addData("Status", "Initialized");
|
||||
telemetry.addData("X offset", odo.getXOffset());
|
||||
telemetry.addData("Y offset", odo.getYOffset());
|
||||
telemetry.addData("Device Version Number:", odo.getDeviceVersion());
|
||||
telemetry.addData("Device Scalar", odo.getYawScalar());
|
||||
telemetry.update();
|
||||
|
||||
// Wait for the game to start (driver presses START)
|
||||
waitForStart();
|
||||
resetRuntime();
|
||||
|
||||
|
||||
// run until the end of the match (driver presses STOP)
|
||||
while (opModeIsActive()) {
|
||||
|
||||
/*
|
||||
Request an update from the Pinpoint odometry computer. This checks almost all outputs
|
||||
from the device in a single I2C read.
|
||||
*/
|
||||
odo.update();
|
||||
|
||||
/*
|
||||
Optionally, you can update only the heading of the device. This takes less time to read, but will not
|
||||
pull any other data. Only the heading (which you can pull with getHeading() or in getPosition().
|
||||
*/
|
||||
//odo.update(GoBildaPinpointDriver.readData.ONLY_UPDATE_HEADING);
|
||||
|
||||
|
||||
if (gamepad1.a){
|
||||
odo.resetPosAndIMU(); //resets the position to 0 and recalibrates the IMU
|
||||
}
|
||||
|
||||
if (gamepad1.b){
|
||||
odo.recalibrateIMU(); //recalibrates the IMU without resetting position
|
||||
}
|
||||
|
||||
/*
|
||||
This code prints the loop frequency of the REV Control Hub. This frequency is effected
|
||||
by I²C reads/writes. So it's good to keep an eye on. This code calculates the amount
|
||||
of time each cycle takes and finds the frequency (number of updates per second) from
|
||||
that cycle time.
|
||||
*/
|
||||
double newTime = getRuntime();
|
||||
double loopTime = newTime-oldTime;
|
||||
double frequency = 1/loopTime;
|
||||
oldTime = newTime;
|
||||
|
||||
|
||||
/*
|
||||
gets the current Position (x & y in mm, and heading in degrees) of the robot, and prints it.
|
||||
*/
|
||||
Pose2D pos = odo.getPosition();
|
||||
String data = String.format(Locale.US, "{X: %.3f, Y: %.3f, H: %.3f}", pos.getX(DistanceUnit.MM), pos.getY(DistanceUnit.MM), pos.getHeading(AngleUnit.DEGREES));
|
||||
telemetry.addData("Position", data);
|
||||
|
||||
/*
|
||||
gets the current Velocity (x & y in mm/sec and heading in degrees/sec) and prints it.
|
||||
*/
|
||||
Pose2D vel = odo.getVelocity();
|
||||
String velocity = String.format(Locale.US,"{XVel: %.3f, YVel: %.3f, HVel: %.3f}", vel.getX(DistanceUnit.MM), vel.getY(DistanceUnit.MM), vel.getHeading(AngleUnit.DEGREES));
|
||||
telemetry.addData("Velocity", velocity);
|
||||
|
||||
|
||||
/*
|
||||
Gets the Pinpoint device status. Pinpoint can reflect a few states. But we'll primarily see
|
||||
READY: the device is working as normal
|
||||
CALIBRATING: the device is calibrating and outputs are put on hold
|
||||
NOT_READY: the device is resetting from scratch. This should only happen after a power-cycle
|
||||
FAULT_NO_PODS_DETECTED - the device does not detect any pods plugged in
|
||||
FAULT_X_POD_NOT_DETECTED - The device does not detect an X pod plugged in
|
||||
FAULT_Y_POD_NOT_DETECTED - The device does not detect a Y pod plugged in
|
||||
*/
|
||||
telemetry.addData("Status", odo.getDeviceStatus());
|
||||
|
||||
telemetry.addData("Pinpoint Frequency", odo.getFrequency()); //prints/gets the current refresh rate of the Pinpoint
|
||||
|
||||
telemetry.addData("REV Hub Frequency: ", frequency); //prints the control system refresh rate
|
||||
telemetry.update();
|
||||
|
||||
}
|
||||
}}
|
Reference in New Issue
Block a user