Skip to content

Commit

Permalink
Merge pull request #30 from WHS-FRC-3467/LasercanImpl
Browse files Browse the repository at this point in the history
Lasercan impl
  • Loading branch information
CJendantix authored Feb 3, 2025
2 parents b4c9fab + 207ecb1 commit 01bfef4
Show file tree
Hide file tree
Showing 4 changed files with 93 additions and 88 deletions.
72 changes: 0 additions & 72 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,6 @@

package frc.robot;

import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.RobotBase;

public class Constants {
Expand Down Expand Up @@ -36,73 +31,6 @@ public static enum Mode {
REPLAY
}

public static final class ExampleSimpleSubsystemConstants {
public static final int ID_Motor = 10;

public static TalonFXConfiguration motorConfig()
{
TalonFXConfiguration m_configuration = new TalonFXConfiguration();

m_configuration.MotorOutput.NeutralMode = NeutralModeValue.Brake;
m_configuration.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
m_configuration.Voltage.PeakForwardVoltage = 12.0;
m_configuration.Voltage.PeakReverseVoltage = -12.0;

m_configuration.CurrentLimits.SupplyCurrentLimit = 20;
m_configuration.CurrentLimits.SupplyCurrentLimitEnable = true;
m_configuration.CurrentLimits.StatorCurrentLimit = 70;
m_configuration.CurrentLimits.StatorCurrentLimitEnable = true;

return m_configuration;
}
}

public static final class ExampleComplexSubsystemConstants {
public static final int ID_Motor = 11;
public static final double upperLimit = Units.degreesToRadians(180);
public static final double lowerLimit = Units.degreesToRadians(0);
public static final double tolerance = Units.degreesToRadians(1);

public static TalonFXConfiguration motorConfig()
{
TalonFXConfiguration m_configuration = new TalonFXConfiguration();

m_configuration.MotorOutput.NeutralMode = NeutralModeValue.Brake;
m_configuration.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
m_configuration.Voltage.PeakForwardVoltage = 12.0;
m_configuration.Voltage.PeakReverseVoltage = -12.0;

m_configuration.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.RotorSensor;
m_configuration.Feedback.SensorToMechanismRatio = 1;

m_configuration.Slot0.kP = 1; // output per unit of error in position (output/rotation)
m_configuration.Slot0.kI = 0; // output per unit of integrated error in position
// (output/(rotation*s))
m_configuration.Slot0.kD = 0; // output per unit of error derivative in position
// (output/rps)

m_configuration.Slot1.kG = 0; // output to overcome gravity (output)
m_configuration.Slot1.kS = 0; // output to overcome static friction (output)
m_configuration.Slot1.kV = 0; // output per unit of requested velocity (output/rps)
m_configuration.Slot1.kA = 0; // unused, as there is no target acceleration
m_configuration.Slot1.kP = 1; // output per unit of error in position (output/rotation)
m_configuration.Slot1.kI = 0; // output per unit of integrated error in position
// (output/(rotation*s))
m_configuration.Slot1.kD = 0; // output per unit of error derivative in position
// (output/rps)

m_configuration.MotionMagic.MotionMagicCruiseVelocity = 10;
m_configuration.MotionMagic.MotionMagicAcceleration = 10;
m_configuration.MotionMagic.MotionMagicJerk = 10;

m_configuration.CurrentLimits.SupplyCurrentLimit = 20;
m_configuration.CurrentLimits.SupplyCurrentLimitEnable = true;
m_configuration.CurrentLimits.StatorCurrentLimit = 70;
m_configuration.CurrentLimits.StatorCurrentLimitEnable = true;

return m_configuration;
}
}
}


6 changes: 6 additions & 0 deletions src/main/java/frc/robot/Ports.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,12 @@ public class Ports {
public static final CanDeviceId ARM_FOLLOWER = new CanDeviceId(22, "rio");
public static final CanDeviceId ARM_CANCODER = new CanDeviceId(23, "rio");

public static final CanDeviceId PROFROLLER_MAIN = new CanDeviceId(24, "rio");
public static final CanDeviceId PROFROLLER_FOLLOWER = new CanDeviceId(25, "rio");

public static final CanDeviceId CLAW_LASERCAN = new CanDeviceId(33, "rio");
public static final CanDeviceId RAMP_LASERCAN = new CanDeviceId(34, "rio");

public static final CanDeviceId CLIMBER = new CanDeviceId(26, "rio");

/*
Expand Down
25 changes: 9 additions & 16 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,26 +20,15 @@
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.commands.DriveCommands;
import frc.robot.generated.TunerConstants;
import frc.robot.subsystems.Arm.Arm;
import frc.robot.subsystems.Arm.ArmIO;
import frc.robot.subsystems.Arm.ArmIOSim;
import frc.robot.subsystems.Arm.ArmIOTalonFX;
import frc.robot.subsystems.Arm.*;
import frc.robot.subsystems.Climber.Climber;
import frc.robot.subsystems.Climber.ClimberIO;
import frc.robot.subsystems.Climber.ClimberIOSim;
import frc.robot.subsystems.Climber.ClimberIOTalonFX;
import frc.robot.subsystems.Elevator.*;
import frc.robot.subsystems.Vision.Vision;
import frc.robot.subsystems.Vision.VisionIO;
import frc.robot.subsystems.Vision.VisionIOPhotonVision;
import frc.robot.subsystems.Vision.VisionIOPhotonVisionSim;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.drive.GyroIO;
import frc.robot.subsystems.drive.GyroIOPigeon2;
import frc.robot.subsystems.drive.GyroIOSim;
import frc.robot.subsystems.drive.ModuleIO;
import frc.robot.subsystems.drive.ModuleIOTalonFXReal;
import frc.robot.subsystems.drive.ModuleIOTalonFXSim;
import frc.robot.subsystems.Vision.*;
import frc.robot.subsystems.drive.*;
import frc.robot.util.drivers.LaserCANSensor;
import org.ironmaple.simulation.SimulatedArena;
import org.ironmaple.simulation.drivesims.SwerveDriveSimulation;
import org.ironmaple.simulation.seasonspecific.reefscape2025.ReefscapeAlgaeOnField;
Expand All @@ -59,7 +48,6 @@ public class RobotContainer {

// Controllers
private final CommandXboxController m_driver = new CommandXboxController(0);
// private final CommandXboxController m_operator = new CommandXboxController(1);

// Dashboard inputs
private final LoggedDashboardChooser<Command> m_autoChooser;
Expand All @@ -75,6 +63,11 @@ public class RobotContainer {

public final Vision m_vision;

private final LaserCANSensor m_clawLaserCAN =
new LaserCANSensor(Ports.CLAW_LASERCAN.getDeviceNumber(), Inches.of(6));
private final LaserCANSensor m_rampLaserCAN =
new LaserCANSensor(Ports.RAMP_LASERCAN.getDeviceNumber(), Inches.of(6));

/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer()
{
Expand Down
78 changes: 78 additions & 0 deletions src/main/java/frc/robot/util/drivers/LaserCANSensor.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.util.drivers;

import au.grapplerobotics.ConfigurationFailedException;
import au.grapplerobotics.LaserCan;
import au.grapplerobotics.interfaces.LaserCanInterface.Measurement;
import edu.wpi.first.units.measure.Distance;
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import lombok.Getter;
import edu.wpi.first.wpilibj.Alert;
import static edu.wpi.first.units.Units.*;


public class LaserCANSensor {
private LaserCan lc;
private int CAN_ID;
private Distance triggerDistance = Inches.zero();

@Getter
public Trigger nearTrigger = new Trigger(() -> getMeasurement().lte(triggerDistance));

private final Alert failedConfig =
new Alert("Failed to configure LaserCAN!", AlertType.kError);
private final Alert sensorAlert =
new Alert("Failed to get LaserCAN measurement", Alert.AlertType.kWarning);

/**
* Constructs a new LaserCAN sensor
*
* @param ID CAN ID assigned to the sensor
* @param triggerDistance distance at which to trigger the sensor
*/
public LaserCANSensor(int ID, Distance distance)
{
CAN_ID = ID;
lc = new LaserCan(CAN_ID);
triggerDistance = distance;
try {
lc.setRangingMode(LaserCan.RangingMode.SHORT);
lc.setRegionOfInterest(new LaserCan.RegionOfInterest(8, 8, 6, 6));
lc.setTimingBudget(LaserCan.TimingBudget.TIMING_BUDGET_20MS);
failedConfig.set(false);
} catch (ConfigurationFailedException e) {
System.out.println("Configuration failed! " + e);
failedConfig.setText("Failed to configure LaserCAN ID: " + ID + "!");
failedConfig.set(true);
}

}

/**
* Returns distance reading from LaserCAN sensor
*/
public Distance getMeasurement()
{
Measurement measurement = lc.getMeasurement();
if (measurement != null
&& measurement.status == LaserCan.LASERCAN_STATUS_VALID_MEASUREMENT) {
sensorAlert.set(false);
return Millimeters.of(measurement.distance_mm);
} else if (measurement != null
&& measurement.status != LaserCan.LASERCAN_STATUS_VALID_MEASUREMENT) {
sensorAlert
.setText("Failed to get LaserCAN ID: " + this.CAN_ID + ", no valid measurement");
sensorAlert.set(true);
return Millimeters.of(Double.POSITIVE_INFINITY);
} else {
sensorAlert.setText("Failed to get LaserCAN ID: " + this.CAN_ID + ", measurement null");
sensorAlert.set(true);
return Millimeters.of(Double.POSITIVE_INFINITY);
}
}

}

0 comments on commit 01bfef4

Please sign in to comment.