mirror of
https://github.com/trc492/FtcTemplate.git
synced 2025-07-04 06:21:23 -07:00
Sync'd latest changes.
Updated ftclib, trclib. Reorganized params.
This commit is contained in:
@ -31,7 +31,7 @@ import ftclib.robotcore.FtcOpMode;
|
||||
import ftclib.sensor.FtcRobotBattery;
|
||||
import teamcode.subsystems.LEDIndicator;
|
||||
import teamcode.subsystems.RobotBase;
|
||||
import teamcode.vision.Vision;
|
||||
import teamcode.subsystems.Vision;
|
||||
import trclib.motor.TrcMotor;
|
||||
import trclib.motor.TrcServo;
|
||||
import trclib.pathdrive.TrcPose2D;
|
||||
@ -62,6 +62,7 @@ public class Robot
|
||||
public LEDIndicator ledIndicator;
|
||||
public FtcRobotBattery battery;
|
||||
// Subsystems.
|
||||
// Autotasks.
|
||||
|
||||
/**
|
||||
* Constructor: Create an instance of the object.
|
||||
@ -92,7 +93,7 @@ public class Robot
|
||||
}
|
||||
// If robotType is VisionOnly, the robot controller is disconnected from the robot for testing vision.
|
||||
// In this case, we should not instantiate any robot hardware.
|
||||
if (RobotParams.Preferences.robotType != RobotParams.RobotType.VisionOnly)
|
||||
if (RobotParams.Preferences.robotType != RobotBase.RobotType.VisionOnly)
|
||||
{
|
||||
// Create and initialize sensors and indicators.
|
||||
if (robotInfo.indicatorName != null)
|
||||
@ -109,6 +110,10 @@ public class Robot
|
||||
//
|
||||
if (RobotParams.Preferences.useSubsystems)
|
||||
{
|
||||
// Create subsystems.
|
||||
// Zero calibrate all subsystems only at init time.
|
||||
zeroCalibrate();
|
||||
// Create autotasks.
|
||||
}
|
||||
}
|
||||
|
||||
@ -283,11 +288,7 @@ public class Robot
|
||||
{
|
||||
globalTracer.traceInfo(moduleName, "Cancel all operations.");
|
||||
|
||||
if (robotDrive != null)
|
||||
{
|
||||
// Cancel all auto-assist driving.
|
||||
robotDrive.cancel();
|
||||
}
|
||||
if (robotDrive != null) robotDrive.cancel();
|
||||
} //cancelAll
|
||||
|
||||
/**
|
||||
@ -316,6 +317,88 @@ public class Robot
|
||||
{
|
||||
} //setRobotStartPosition
|
||||
|
||||
/**
|
||||
* This method adjusts the given pose in the red alliance to be the specified alliance.
|
||||
*
|
||||
* @param x specifies x position in the red alliance in the specified unit.
|
||||
* @param y specifies y position in the red alliance in the specified unit.
|
||||
* @param heading specifies heading in the red alliance in degrees.
|
||||
* @param alliance specifies the alliance to be converted to.
|
||||
* @param isTileUnit specifies true if x and y are in tile unit, false if in inches.
|
||||
* @return pose adjusted to be in the specified alliance in inches.
|
||||
*/
|
||||
public TrcPose2D adjustPoseByAlliance(
|
||||
double x, double y, double heading, FtcAuto.Alliance alliance, boolean isTileUnit)
|
||||
{
|
||||
TrcPose2D newPose = new TrcPose2D(x, y, heading);
|
||||
|
||||
if (alliance == FtcAuto.Alliance.BLUE_ALLIANCE)
|
||||
{
|
||||
// Translate blue alliance pose to red alliance pose.
|
||||
if (RobotParams.Game.fieldIsMirrored)
|
||||
{
|
||||
// Mirrored field.
|
||||
double angleDelta = (newPose.angle - 90.0)*2.0;
|
||||
newPose.angle -= angleDelta;
|
||||
newPose.y = -newPose.y;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Symmetrical field.
|
||||
newPose.x = -newPose.x;
|
||||
newPose.y = -newPose.y;
|
||||
newPose.angle = (newPose.angle + 180.0) % 360.0;
|
||||
}
|
||||
}
|
||||
|
||||
if (isTileUnit)
|
||||
{
|
||||
newPose.x *= RobotParams.Field.FULL_TILE_INCHES;
|
||||
newPose.y *= RobotParams.Field.FULL_TILE_INCHES;
|
||||
}
|
||||
|
||||
return newPose;
|
||||
} //adjustPoseByAlliance
|
||||
|
||||
/**
|
||||
* This method adjusts the given pose in the red alliance to be the specified alliance.
|
||||
*
|
||||
* @param x specifies x position in the red alliance in tile unit.
|
||||
* @param y specifies y position in the red alliance in tile unit.
|
||||
* @param heading specifies heading in the red alliance in degrees.
|
||||
* @param alliance specifies the alliance to be converted to.
|
||||
* @return pose adjusted to be in the specified alliance in inches.
|
||||
*/
|
||||
public TrcPose2D adjustPoseByAlliance(double x, double y, double heading, FtcAuto.Alliance alliance)
|
||||
{
|
||||
return adjustPoseByAlliance(x, y, heading, alliance, true);
|
||||
} //adjustPoseByAlliance
|
||||
|
||||
/**
|
||||
* This method adjusts the given pose in the red alliance to be the specified alliance.
|
||||
*
|
||||
* @param pose specifies pose in the red alliance in the specified unit.
|
||||
* @param alliance specifies the alliance to be converted to.
|
||||
* @param isTileUnit specifies true if pose is in tile units, false in inches.
|
||||
* @return pose adjusted to be in the specified alliance in inches.
|
||||
*/
|
||||
public TrcPose2D adjustPoseByAlliance(TrcPose2D pose, FtcAuto.Alliance alliance, boolean isTileUnit)
|
||||
{
|
||||
return adjustPoseByAlliance(pose.x, pose.y, pose.angle, alliance, isTileUnit);
|
||||
} //adjustPoseByAlliance
|
||||
|
||||
/**
|
||||
* This method adjusts the given pose in the red alliance to be the specified alliance.
|
||||
*
|
||||
* @param pose specifies pose in the blue alliance in tile unit.
|
||||
* @param alliance specifies the alliance to be converted to.
|
||||
* @return pose adjusted to be in the specified alliance in inches.
|
||||
*/
|
||||
public TrcPose2D adjustPoseByAlliance(TrcPose2D pose, FtcAuto.Alliance alliance)
|
||||
{
|
||||
return adjustPoseByAlliance(pose, alliance, true);
|
||||
} //adjustPoseByAlliance
|
||||
|
||||
/**
|
||||
* This method sends the text string to the Driver Station to be spoken using text to speech.
|
||||
*
|
||||
|
Reference in New Issue
Block a user