001// Copyright (c) FIRST and other WPILib contributors. 002// Open Source Software; you can modify and/or share it under the terms of 003// the WPILib BSD license file in the root directory of this project. 004 005package edu.wpi.first.wpilibj; 006 007import edu.wpi.first.util.sendable.Sendable; 008import edu.wpi.first.util.sendable.SendableBuilder; 009import edu.wpi.first.util.sendable.SendableRegistry; 010import edu.wpi.first.wpilibj.motorcontrol.MotorController; 011import java.util.Arrays; 012 013/** 014 * Allows multiple {@link SpeedController} objects to be linked together. 015 * 016 * @deprecated Use {@link edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup}. 017 */ 018@Deprecated(since = "2022", forRemoval = true) 019@SuppressWarnings("removal") 020public class SpeedControllerGroup implements MotorController, Sendable, AutoCloseable { 021 private boolean m_isInverted; 022 private final SpeedController[] m_speedControllers; 023 private static int instances; 024 025 /** 026 * Create a new SpeedControllerGroup with the provided SpeedControllers. 027 * 028 * @param speedController The first SpeedController to add. 029 * @param speedControllers The SpeedControllers to add 030 */ 031 public SpeedControllerGroup( 032 SpeedController speedController, SpeedController... speedControllers) { 033 m_speedControllers = new SpeedController[speedControllers.length + 1]; 034 m_speedControllers[0] = speedController; 035 System.arraycopy(speedControllers, 0, m_speedControllers, 1, speedControllers.length); 036 init(); 037 } 038 039 public SpeedControllerGroup(SpeedController[] speedControllers) { 040 m_speedControllers = Arrays.copyOf(speedControllers, speedControllers.length); 041 init(); 042 } 043 044 private void init() { 045 for (SpeedController controller : m_speedControllers) { 046 SendableRegistry.addChild(this, controller); 047 } 048 instances++; 049 SendableRegistry.addLW(this, "MotorControllerGroup", instances); 050 } 051 052 @Override 053 public void close() { 054 SendableRegistry.remove(this); 055 } 056 057 @Override 058 public void set(double speed) { 059 for (SpeedController speedController : m_speedControllers) { 060 speedController.set(m_isInverted ? -speed : speed); 061 } 062 } 063 064 @Override 065 public double get() { 066 if (m_speedControllers.length > 0) { 067 return m_speedControllers[0].get() * (m_isInverted ? -1 : 1); 068 } 069 return 0.0; 070 } 071 072 @Override 073 public void setInverted(boolean isInverted) { 074 m_isInverted = isInverted; 075 } 076 077 @Override 078 public boolean getInverted() { 079 return m_isInverted; 080 } 081 082 @Override 083 public void disable() { 084 for (SpeedController speedController : m_speedControllers) { 085 speedController.disable(); 086 } 087 } 088 089 @Override 090 public void stopMotor() { 091 for (SpeedController speedController : m_speedControllers) { 092 speedController.stopMotor(); 093 } 094 } 095 096 @Override 097 public void initSendable(SendableBuilder builder) { 098 builder.setSmartDashboardType("Motor Controller"); 099 builder.setActuator(true); 100 builder.setSafeState(this::stopMotor); 101 builder.addDoubleProperty("Value", this::get, this::set); 102 } 103}