001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ 003/* Open Source Software - may be modified and shared by FRC teams. The code */ 004/* must be accompanied by the FIRST BSD license file in the root directory of */ 005/* the project. */ 006/*----------------------------------------------------------------------------*/ 007 008package edu.wpi.first.wpilibj; 009 010import edu.wpi.first.wpilibj.hal.FRCNetComm.tResourceType; 011import edu.wpi.first.wpilibj.hal.HAL; 012 013/** 014 * REV Robotics SPARK Speed Controller. 015 */ 016public class Spark extends PWMSpeedController { 017 /** 018 * Common initialization code called by all constructors. 019 * 020 * <p>Note that the SPARK uses the following bounds for PWM values. These values should work 021 * reasonably well for most controllers, but if users experience issues such as asymmetric 022 * behavior around the deadband or inability to saturate the controller in either direction, 023 * calibration is recommended. The calibration procedure can be found in the Spark User Manual 024 * available from REV Robotics. 025 * 026 * <p>- 2.003ms = full "forward" - 1.55ms = the "high end" of the deadband range - 1.50ms = 027 * center of the deadband range (off) - 1.46ms = the "low end" of the deadband range - .999ms = 028 * full "reverse" 029 */ 030 protected void initSpark() { 031 setBounds(2.003, 1.55, 1.50, 1.46, .999); 032 setPeriodMultiplier(PeriodMultiplier.k1X); 033 setSpeed(0.0); 034 setZeroLatch(); 035 036 HAL.report(tResourceType.kResourceType_RevSPARK, getChannel()); 037 setName("Spark", getChannel()); 038 } 039 040 /** 041 * Constructor. 042 * 043 * @param channel The PWM channel that the SPARK is attached to. 0-9 are on-board, 10-19 are on 044 * the MXP port 045 */ 046 public Spark(final int channel) { 047 super(channel); 048 initSpark(); 049 } 050}