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