001package com.ctre.phoenix.motorcontrol;
002
003import com.ctre.phoenix.ErrorCode;
004import com.ctre.phoenix.sensors.SensorVelocityMeasPeriod;
005
006/**
007 * Interface for enhanced motor controllers
008 */
009public interface IMotorControllerEnhanced extends IMotorController {
010         //------ Set output routines. ----------//
011    /* in parent */
012
013    //------ Invert behavior ----------//
014    /* in parent */
015
016    //----- general output shaping ------------------//
017    /* in parent */
018
019    //------ Voltage Compensation ----------//
020    /* in parent */
021
022    //------ General Status ----------//
023    /* in parent */
024
025    //------ sensor selection ----------//
026    /* expand the options */
027        /**
028         * Select the feedback device for the motor controller.
029         *
030         * @param feedbackDevice
031         *            Feedback Device to select.
032         * @param pidIdx
033         *            0 for Primary closed-loop. 1 for auxiliary closed-loop.
034         * @param timeoutMs
035         *            Timeout value in ms. If nonzero, function will wait for
036         *            config success and report an error if it times out.
037         *            If zero, no blocking or checking is performed.
038         * @return Error Code generated by function. 0 indicates no error.
039         */
040        public ErrorCode configSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx, int timeoutMs );
041
042        //------ Current Lim ----------//
043        /**
044         * Configures the supply (input) current limit.
045
046         * @param currLimitCfg  Current limit configuration
047         * @param timeoutMs
048         *            Timeout value in ms. If nonzero, function will wait for
049         *            config success and report an error if it times out.
050         *            If zero, no blocking or checking is performed.
051         * @return Error Code generated by function. 0 indicates no error.
052         */
053        public ErrorCode configSupplyCurrentLimit(SupplyCurrentLimitConfiguration currLimitCfg, int timeoutMs );
054
055    //------- sensor status --------- //
056    /* in parent */
057
058    //------ status frame period changes ----------//
059        /**
060         * Sets the period of the given status frame.
061         *
062         * User ensure CAN Bus utilization is not high.
063         *
064         * This setting is not persistent and is lost when device is reset. If this
065         * is a concern, calling application can use hasResetOccurred() to determine if the
066         * status frame needs to be reconfigured.
067         *
068         * @param frame
069         *            Frame whose period is to be changed.
070         * @param periodMs
071         *            Period in ms for the given frame.
072         * @param timeoutMs
073         *            Timeout value in ms. If nonzero, function will wait for
074         *            config success and report an error if it times out.
075         *            If zero, no blocking or checking is performed.
076         * @return Error Code generated by function. 0 indicates no error.
077         */
078    public ErrorCode setStatusFramePeriod(StatusFrameEnhanced frame, int periodMs, int timeoutMs );
079    /**
080         * Gets the period of the given status frame.
081         *
082         * @param frame
083         *            Frame to get the period of.
084         * @param timeoutMs
085         *            Timeout value in ms. If nonzero, function will wait for
086         *            config success and report an error if it times out.
087         *            If zero, no blocking or checking is performed.
088         * @return Period of the given status frame.
089         */
090    public int getStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs );
091
092        // ------ General Status ----------//
093        /**
094         * Gets the output current of the motor controller.
095         * In the case of TalonSRX class, this routine returns supply current for legacy reasons.  In order to get the "true" output current, call GetStatorCurrent().
096         * In the case of TalonFX class, this routine returns the true output stator current.
097         *
098         * @deprecated Use getStatorCurrent/getSupplyCurrent instead.
099         *
100         * @return The output current (in amps).
101         */
102        @Deprecated
103        public double getOutputCurrent() ;
104
105    //----- velocity signal conditionaing ------//
106        /**
107         * Sets the period over which velocity measurements are taken.
108         *
109         * @param period
110         *            Desired period for the velocity measurement. @see
111         *            com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
112         * @param timeoutMs
113         *            Timeout value in ms. If nonzero, function will wait for
114         *            config success and report an error if it times out.
115         *            If zero, no blocking or checking is performed.
116         * @return Error Code generated by function. 0 indicates no error.
117         */
118    public ErrorCode configVelocityMeasurementPeriod(SensorVelocityMeasPeriod period, int timeoutMs );
119        /**
120         * Sets the period over which velocity measurements are taken.
121         * 
122         * @deprecated Use the overload with SensorVelocityMeasPeriod instead.
123         *
124         * @param period
125         *            Desired period for the velocity measurement. @see
126         *            com.ctre.phoenix.sensors.SensorVelocityMeasPeriod
127         * @param timeoutMs
128         *            Timeout value in ms. If nonzero, function will wait for
129         *            config success and report an error if it times out.
130         *            If zero, no blocking or checking is performed.
131         * @return Error Code generated by function. 0 indicates no error.
132         */
133        @Deprecated
134    public ErrorCode configVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs );
135    /**
136         * Sets the number of velocity samples used in the rolling average velocity
137         * measurement.
138         *
139         * @param windowSize
140         *            Number of samples in the rolling average of velocity
141         *            measurement. Valid values are 1,2,4,8,16,32. If another value
142         *            is specified, it will truncate to nearest support value.
143         * @param timeoutMs
144         *            Timeout value in ms. If nonzero, function will wait for config
145         *            success and report an error if it times out. If zero, no
146         *            blocking or checking is performed.
147         * @return Error Code generated by function. 0 indicates no error.
148         */
149        public ErrorCode configVelocityMeasurementWindow(int windowSize, int timeoutMs );
150
151    //------ remote limit switch ----------//
152    /* in parent */
153
154    //------ local limit switch ----------//
155        /**
156         * Configures the forward limit switch for a remote source. For example, a
157         * CAN motor controller may need to monitor the Limit-F pin of another Talon
158         * or CANifier.
159         *
160         * @param type
161         *            Remote limit switch source. User can choose between a remote
162         *            Talon SRX, CANifier, or deactivate the feature.
163         * @param normalOpenOrClose
164         *            Setting for normally open, normally closed, or disabled. This
165         *            setting matches the Phoenix Tuner drop down.
166         * @param timeoutMs
167         *            Timeout value in ms. If nonzero, function will wait for config
168         *            success and report an error if it times out. If zero, no
169         *            blocking or checking is performed.
170         * @return Error Code generated by function. 0 indicates no error.
171         */
172    public ErrorCode configForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs );
173    /**
174         * Configures the reverse limit switch for a remote source. For example, a
175         * CAN motor controller may need to monitor the Limit-R pin of another Talon
176         * or CANifier.
177         *
178         * @param type
179         *            Remote limit switch source. User can choose between a remote
180         *            Talon SRX, CANifier, or deactivate the feature.
181         * @param normalOpenOrClose
182         *            Setting for normally open, normally closed, or disabled. This
183         *            setting matches the Phoenix Tuner drop down.
184         * @param timeoutMs
185         *            Timeout value in ms. If nonzero, function will wait for config
186         *            success and report an error if it times out. If zero, no
187         *            blocking or checking is performed.
188         * @return Error Code generated by function. 0 indicates no error.
189         */
190        public ErrorCode configReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs );
191
192    //------ soft limit ----------//
193    /* in parent */
194
195    //------ General Close loop ----------//
196    /* in parent */
197
198    //------ Motion Profile Settings used in Motion Magic and Motion Profile ----------//
199    /* in parent */
200
201    //------ Motion Profile Buffer ----------//
202    /* in parent */
203
204    //------ error ----------//
205    /* in parent */
206
207    //------ Faults ----------//
208    /* in parent */
209
210    //------ Firmware ----------//
211    /* in parent */
212
213    //------ Custom Persistent Params ----------//
214    /* in parent */
215
216    //------ Generic Param API, typically not used ----------//
217    /* in parent */
218
219    //------ Misc. ----------//
220    /* in parent */
221}