001/*
002 * Copyright (c) 2018-2021 REV Robotics
003 *
004 * Redistribution and use in source and binary forms, with or without
005 * modification, are permitted provided that the following conditions are met:
006 *
007 * 1. Redistributions of source code must retain the above copyright notice,
008 *    this list of conditions and the following disclaimer.
009 * 2. Redistributions in binary form must reproduce the above copyright
010 *    notice, this list of conditions and the following disclaimer in the
011 *    documentation and/or other materials provided with the distribution.
012 * 3. Neither the name of REV Robotics nor the names of its
013 *    contributors may be used to endorse or promote products derived from
014 *    this software without specific prior written permission.
015 *
016 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
017 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
018 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
019 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
020 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
021 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
022 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
023 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
024 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
025 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
026 * POSSIBILITY OF SUCH DAMAGE.
027 */
028
029package com.revrobotics;
030
031/**
032 * Get an instance of this interface by using {@link CANSparkMax#getEncoder()}, {@link
033 * CANSparkMax#getEncoder(SparkMaxRelativeEncoder.Type, int)}, {@link
034 * CANSparkMax#getAlternateEncoder(int)}, or {@link
035 * CANSparkMax#getAlternateEncoder(SparkMaxAlternateEncoder.Type, int)}.
036 */
037public interface RelativeEncoder extends CANEncoder {
038  /**
039   * Get the position of the motor. This returns the native units of 'rotations' by default, and can
040   * be changed by a scale factor using setPositionConversionFactor().
041   *
042   * @return Number of rotations of the motor
043   */
044  double getPosition();
045
046  /**
047   * Get the velocity of the motor. This returns the native units of 'RPM' by default, and can be
048   * changed by a scale factor using setVelocityConversionFactor().
049   *
050   * @return Number the RPM of the motor
051   */
052  double getVelocity();
053
054  /**
055   * Set the position of the encoder. By default the units are 'rotations' and can be changed by a
056   * scale factor using setPositionConversionFactor().
057   *
058   * @param position Number of rotations of the motor
059   * @return {@link REVLibError#kOk} if successful
060   */
061  REVLibError setPosition(double position);
062
063  /**
064   * Set the conversion factor for position of the encoder. Multiplied by the native output units to
065   * give you position.
066   *
067   * @param factor The conversion factor to multiply the native units by
068   * @return {@link REVLibError#kOk} if successful
069   */
070  REVLibError setPositionConversionFactor(double factor);
071
072  /**
073   * Set the conversion factor for velocity of the encoder. Multiplied by the native output units to
074   * give you velocity
075   *
076   * @param factor The conversion factor to multiply the native units by
077   * @return {@link REVLibError#kOk} if successful
078   */
079  REVLibError setVelocityConversionFactor(double factor);
080
081  /**
082   * Get the conversion factor for position of the encoder. Multiplied by the native output units to
083   * give you position
084   *
085   * @return The conversion factor for position
086   */
087  double getPositionConversionFactor();
088
089  /**
090   * Get the conversion factor for velocity of the encoder. Multiplied by the native output units to
091   * give you velocity
092   *
093   * @return The conversion factor for velocity
094   */
095  double getVelocityConversionFactor();
096
097  /**
098   * Set the average sampling depth for a quadrature encoder. This value sets the number of samples
099   * in the average for velocity readings. This can be any value from 1 to 64.
100   *
101   * <p>When the SparkMax controller is in Brushless mode, this will not change any behavior.
102   *
103   * @param depth The average sampling depth between 1 and 64 (default)
104   * @return {@link REVLibError#kOk} if successful
105   */
106  REVLibError setAverageDepth(int depth);
107
108  /**
109   * Get the average sampling depth for a quadrature encoder.
110   *
111   * @return The average sampling depth
112   */
113  int getAverageDepth();
114
115  /**
116   * Set the measurement period for velocity measurements of a quadrature encoder. When the SparkMax
117   * controller is in Brushless mode, this will not change any behavior.
118   *
119   * <p>The basic formula to calculate velocity is change in position / change in time. This
120   * parameter sets the change in time for measurement.
121   *
122   * @param period_us Measurement period in milliseconds. This number may be between 1 and 100
123   *     (default).
124   * @return {@link REVLibError#kOk} if successful
125   */
126  REVLibError setMeasurementPeriod(int period_us);
127
128  /**
129   * Get the number of samples for reading from a quadrature encoder.
130   *
131   * @return Number of samples
132   */
133  int getMeasurementPeriod();
134
135  /**
136   * Get the counts per revolution of the quadrature encoder.
137   *
138   * <p>For a description on the difference between CPR, PPR, etc. go to
139   * https://www.cuidevices.com/blog/what-is-encoder-ppr-cpr-and-lpr
140   *
141   * @return Counts per revolution
142   */
143  int getCountsPerRevolution();
144
145  // TODO(Noah): Add Javadocs here
146  REVLibError setInverted(boolean inverted);
147
148  boolean getInverted();
149}