Skip to content

Commit

Permalink
Merge pull request chopshop-166#186 from chopshop-166/mac-address
Browse files Browse the repository at this point in the history
feat: Add MAC address detection
  • Loading branch information
bot190 authored Jan 20, 2024
2 parents 47717cd + 86b6c3b commit 610960b
Show file tree
Hide file tree
Showing 2 changed files with 57 additions and 27 deletions.
50 changes: 40 additions & 10 deletions core/src/main/java/com/chopshop166/chopshoplib/RobotUtils.java
Original file line number Diff line number Diff line change
@@ -1,22 +1,27 @@
package com.chopshop166.chopshoplib;

import java.net.NetworkInterface;
import java.net.SocketException;
import java.util.StringJoiner;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import java.util.function.DoubleUnaryOperator;
import java.util.stream.DoubleStream;

import edu.wpi.first.wpilibj.Preferences;

/**
* Utilities that are related to overall robot functionality.
*/
public final class RobotUtils {
private RobotUtils() {}
private RobotUtils() {
}

/**
* Get a value if it exists, or a default value if it's null.
*
* @param <T> The type to get.
* @param value The value to test.
* @param <T> The type to get.
* @param value The value to test.
* @param defaultValue The default value for if value is null.
* @return A null safe value
*/
Expand Down Expand Up @@ -50,7 +55,7 @@ public static Double[] toBoxed(final double... args) {
*
* @param minBound The lowest possible value.
* @param maxBound The highest possible value.
* @param value The value to clamp.
* @param value The value to clamp.
* @return The provided value, clamped between minBound and maxBound.
*/
public static double clamp(final double minBound, final double maxBound, final double value) {
Expand All @@ -62,7 +67,7 @@ public static double clamp(final double minBound, final double maxBound, final d
*
* @param minBound The lowest possible value.
* @param maxBound The highest possible value.
* @param value The value to clamp.
* @param value The value to clamp.
* @return The provided value, clamped between minBound and maxBound.
*/
public static float clamp(final float minBound, final float maxBound, final float value) {
Expand All @@ -74,7 +79,7 @@ public static float clamp(final float minBound, final float maxBound, final floa
*
* @param minBound The lowest possible value.
* @param maxBound The highest possible value.
* @param value The value to clamp.
* @param value The value to clamp.
* @return The provided value, clamped between minBound and maxBound.
*/
public static int clamp(final int minBound, final int maxBound, final int value) {
Expand All @@ -86,7 +91,7 @@ public static int clamp(final int minBound, final int maxBound, final int value)
*
* @param minBound The lowest possible value.
* @param maxBound The highest possible value.
* @param value The value to clamp.
* @param value The value to clamp.
* @return The provided value, clamped between minBound and maxBound.
*/
public static long clamp(final long minBound, final long maxBound, final long value) {
Expand All @@ -107,7 +112,7 @@ public static double sps(final double value) {
* Sign Preserving Power
*
* @param value The value to multiply.
* @param exp The value to exponentiate by.
* @param exp The value to exponentiate by.
* @return The square of the given value, preserving sign.
*/
public static double sppow(final double value, final double exp) {
Expand Down Expand Up @@ -136,7 +141,7 @@ public static DoubleUnaryOperator scalingDeadband(final double range) {
* Apply a deadband to an axis, elongating the remaining space.
*
* @param range The range to deaden.
* @param axis The axis to pull from.
* @param axis The axis to pull from.
* @return The new axis to use.
*/
public static DoubleSupplier deadbandAxis(final double range, final DoubleSupplier axis) {
Expand All @@ -147,10 +152,35 @@ public static DoubleSupplier deadbandAxis(final double range, final DoubleSuppli
/**
* Negate a boolean supplier.
*
* @param func The base function
* @param func The base function.
* @return A function that returns true when func returns false, and vice versa.
*/
public static BooleanSupplier not(final BooleanSupplier func) {
return () -> !func.getAsBoolean();
}

/**
* Get the MAC address for a robot.
*
* @return The MAC address as a standardized string.
*/
public static String getMACAddress() {
try {
final NetworkInterface iface = NetworkInterface.getByName("eth0");
if (iface == null) {
return "NotFound";
}
final byte[] mac = iface.getHardwareAddress();
if (mac == null) {
throw new SocketException();
}
final StringJoiner sb = new StringJoiner(":");
for (final byte octet : mac) {
sb.add(String.format("%02X", octet));
}
return sb.toString();
} catch (SocketException ex) {
return "SocketException";
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
import java.util.stream.Stream;
import org.littletonrobotics.junction.LoggedRobot;
import com.chopshop166.chopshoplib.Autonomous;
import com.chopshop166.chopshoplib.RobotUtils;
import com.chopshop166.chopshoplib.maps.RobotMapFor;
import com.google.common.io.Resources;
import com.google.common.reflect.ClassPath;
Expand All @@ -26,7 +27,7 @@
*
* Contains convenient wrappers for the commands that are often used in groups.
*/
@SuppressWarnings({"PMD.ExcessiveImports", "PMD.GodClass"})
@SuppressWarnings({ "PMD.ExcessiveImports", "PMD.GodClass" })
public abstract class CommandRobot extends LoggedRobot {

/** The value to display on Shuffleboard if Git data isn't found. */
Expand Down Expand Up @@ -167,15 +168,15 @@ public Command resetSubsystems(final SmartSubsystem... subsystems) {
public Command safeStateSubsystems(final SmartSubsystem... subsystems) {
return parallel(
Stream.of(subsystems).map(SmartSubsystem::safeStateCmd).toArray(Command[]::new))
.withName("Reset Subsystems");
.withName("Reset Subsystems");
}

/**
* Get a RobotMap for the given name.
*
* @param <T> The type to return.
* @param <T> The type to return.
* @param rootClass The root class object that the map derives from.
* @param pkg The package to look in.
* @param pkg The package to look in.
* @return An instance of the given type, or null.
*/
public static <T> T getRobotMap(final Class<T> rootClass, final String pkg) {
Expand Down Expand Up @@ -205,19 +206,17 @@ public <T> T getRobotMap(final Class<T> rootClass, final T defaultValue) {
* @param defaultValue The object to return if no match is found.
* @return An instance of the given type, or the default value.
*/
public static <T> T getRobotMap(final Class<T> rootClass, final String pkg,
final T defaultValue) {
return CommandRobot.getMapForName(RobotController.getSerialNumber(), rootClass, pkg,
defaultValue);
public static <T> T getRobotMap(final Class<T> rootClass, final String pkg, final T defaultValue) {
return CommandRobot.getMapForName(RobotUtils.getMACAddress(), rootClass, pkg, defaultValue);
}

/**
* Get a RobotMap for the given name.
*
* @param <T> The type to return.
* @param name The name to match against in annotations.
* @param <T> The type to return.
* @param name The name to match against in annotations.
* @param rootClass The root class object that the map derives from.
* @param pkg The package to look in.
* @param pkg The package to look in.
* @return An instance of the given type, or null.
*/
public static <T> T getMapForName(final String name, final Class<T> rootClass,
Expand All @@ -228,10 +227,10 @@ public static <T> T getMapForName(final String name, final Class<T> rootClass,
/**
* Get a RobotMap for the given name.
*
* @param <T> The type to return.
* @param name The name to match against in annotations.
* @param rootClass The root class object that the map derives from.
* @param pkg The package to look in.
* @param <T> The type to return.
* @param name The name to match against in annotations.
* @param rootClass The root class object that the map derives from.
* @param pkg The package to look in.
* @param defaultValue The object to return if no match is found.
* @return An instance of the given type, or the default value.
*/
Expand Down Expand Up @@ -267,7 +266,8 @@ public static <T> T getMapForName(final String name, final Class<T> rootClass, f
/**
* Put robot code build information onto the dashboard.
* <p>
* This will fail without a Gradle task to generate build information. See this ChopShopLib
* This will fail without a Gradle task to generate build information. See this
* ChopShopLib
* README for more information.
*/
@SuppressWarnings("PMD.EmptyCatchBlock")
Expand Down Expand Up @@ -308,7 +308,7 @@ public static void logBuildData() {
* Get an attribute, safely
*
* @param attrs Attributes to load from
* @param key Key to load
* @param key Key to load
* @return An attribute, or UNKNOWN_VALUE.
*/
private static String getAttr(final Attributes attrs, final String key) {
Expand Down

0 comments on commit 610960b

Please sign in to comment.