|
58 | 58 | import edu.wpi.first.wpilibj.Joystick; |
59 | 59 | import edu.wpi.first.wpilibj.PowerDistributionPanel; |
60 | 60 | import edu.wpi.first.wpilibj.SPI; |
| 61 | +import edu.wpi.first.wpilibj.Spark; |
61 | 62 | import edu.wpi.first.wpilibj.Talon; |
62 | 63 | import edu.wpi.first.wpilibj.Ultrasonic; |
63 | 64 | import edu.wpi.first.wpilibj.Victor; |
@@ -692,6 +693,29 @@ public static TalonSRX talonSRX(int deviceNumber, TalonSRX leader, boolean rever |
692 | 693 | talon.reverseOutput(reverse); |
693 | 694 | return talonSRX(talon, 0.0d, 0.0d); |
694 | 695 | } |
| 696 | + |
| 697 | + /** |
| 698 | + * Create a motor driven by a <a href="http://www.revrobotics.com/SPARK">RevRobotics Spark Motor Controller</a> on the |
| 699 | + * specified channel. The speed output is limited to [-1.0,1.0] inclusive. |
| 700 | + * |
| 701 | + * @param channel the channel the controller is connected to |
| 702 | + * @return a motor on the specified channel |
| 703 | + */ |
| 704 | + public static Motor spark(int channel) { |
| 705 | + return spark(channel, SPEED_LIMITER); |
| 706 | + } |
| 707 | + |
| 708 | + /** |
| 709 | + * Create a motor driven by a <a href="http://www.revrobotics.com/SPARK">RevRobotics Spark Motor Controller</a> on the |
| 710 | + * specified channel, with a custom speed limiting function. |
| 711 | + * |
| 712 | + * @param channel the channel the controller is connected to |
| 713 | + * @param speedLimiter function that will be used to limit the speed (input voltage); may not be null |
| 714 | + * @return a motor on the specified channel |
| 715 | + */ |
| 716 | + public static Motor spark(int channel, DoubleToDoubleFunction speedLimiter) { |
| 717 | + return new HardwareSpark(new Spark(channel), SPEED_LIMITER); |
| 718 | + } |
695 | 719 | } |
696 | 720 |
|
697 | 721 | /** |
|
0 commit comments