Custom actuators in LiveWindow?

I am trying to devise a shim between a SparkMAX and test mode, but it doesn’t show up in LiveWindow. Yes, I did enableLiveWindowInTest(true);

This works (we’ve used it for several years):

package org.usfirst.frc3620.misc;

import com.revrobotics.CANSparkMax;
import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;

public class CANSparkMaxSendable extends CANSparkMax implements Sendable  {
    public CANSparkMaxSendable(int deviceId, MotorType motorType) {
        super(deviceId, motorType);

        SendableRegistry.addLW(this, "SparkMax", deviceId);
    }

    @Override
    public void initSendable(SendableBuilder builder) {
        builder.setSmartDashboardType("Motor Controller");
        builder.setActuator(true);
        builder.setSafeState(this::stopMotor);
        builder.addDoubleProperty("Value", this::get, this::set);
    }
}

This does not show up in the network tables:

package org.usfirst.frc3620.misc;

import org.apache.logging.log4j.Logger;
import org.usfirst.frc3620.logger.EventLogging;

import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.util.sendable.SendableRegistry;
import edu.wpi.first.wpilibj.motorcontrol.MotorController;

/** Add your docs here. */
public class FakeMotor implements Sendable, MotorController {
    Logger logger = EventLogging.getLogger(this.getClass());
    int deviceId;
    double speed;
    boolean inverted;

    public FakeMotor(int deviceId) {
        this.deviceId = deviceId;
        speed = 0;
        inverted = false;
        SendableRegistry.addLW(this, "FakeMotor", deviceId);
    }

    @Override
    public void set(double speed) {
        this.speed = speed;
        logger.info ("FakeMotor[{}].set({})", deviceId, speed);
    }

    @Override
    public double get() {
        return speed;
    }

    @Override
    public void setInverted(boolean isInverted) {
        this.inverted = isInverted;
        logger.info ("FakeMotor[{}].setInverted({})", deviceId, isInverted);
    }

    @Override
    public boolean getInverted() {
        return this.inverted;
    }

    @Override
    public void disable() {
        logger.info ("FakeMotor[{}].disable()", deviceId);
    }

    @Override
    public void stopMotor() {
        logger.info ("FakeMotor[{}].stopMotor()", deviceId);
        this.speed = 0;
    }

    @Override
    public void initSendable(SendableBuilder builder) {
        builder.setSmartDashboardType("Motor Controller");
        builder.setActuator(true);
        builder.setSafeState(this::stopMotor);
        builder.addDoubleProperty("Value", this::get, this::set);
    }

}

My example subsystem:

package frc.robot.subsystems;

import org.usfirst.frc3620.misc.CANSparkMaxSendable;
import org.usfirst.frc3620.misc.FakeMotor;

import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class ExampleSubsystem extends SubsystemBase {
  FakeMotor motor;
  CANSparkMaxSendable max;
  public ExampleSubsystem() {
    motor = new FakeMotor(99);
    max = new CANSparkMaxSendable(11, MotorType.kBrushless);
    addChild("motor", motor);
    addChild("max", motor);
  }
}

What is the FakeMotor missing?

Your second addChild adds motor again instead of max but that might not be the problem.

I suspect what’s happening is OP did get the FakeMotor registered (twice) but it’s called max (last one wins).

yeah, that was a dumb mistake that I introduced in my example.

did some more testing (simulation, shuffleboard, added another motor):

  public ExampleSubsystem() {
    motor = new FakeMotor(99);
    max = new CANSparkMaxSendable(11, MotorType.kBrushless);
    max2 = new CANSparkMax(12, MotorType.kBrushless);
    CANSparkMaxSendableWrapper maxW = new CANSparkMaxSendableWrapper(max2);
    addChild("max", max);
    addChild("max3", motor);
    addChild("zmax2", maxW);
  }

max and zmax2 show up.


    addChild("ymax3", motor);
    addChild("max", max);
    addChild("zmax2", maxW);

all 3 show up.


    addChild("max3", motor);
    addChild("max", max);
    addChild("max2", maxW);

max and max2 show up.


Go back to:

    addChild("max", max);
    addChild("max3", motor);
    addChild("zmax2", maxW);

and we are back to max and zmax2 show up.


    addChild("max", max);
    addChild("ymax3", motor);
    addChild("zmax2", maxW);

All three show up.


Something funky having to do with initial part of names and ordering?

Did some more test. Shuffleboard is not always showing the same entries that OutlineViewer does; some of the LiveWindow/ stuff seems to be missing. I don’t think the problem was my Sendable, I think Shuffleboard may not be picking up stuff from test mode. I need to do more investigation, but right now, I have to go spin motors in test mode.