diff --git a/eclipse-plugins/edu.wpi.first.wpilib.plugins.java/resources/templates/examples/CANTalon/src/org/usfirst/frc/team190/robot/Robot.java b/eclipse-plugins/edu.wpi.first.wpilib.plugins.java/resources/templates/examples/CANTalon/src/org/usfirst/frc/team190/robot/Robot.java index 55ae01955b..48af9802d1 100755 --- a/eclipse-plugins/edu.wpi.first.wpilib.plugins.java/resources/templates/examples/CANTalon/src/org/usfirst/frc/team190/robot/Robot.java +++ b/eclipse-plugins/edu.wpi.first.wpilib.plugins.java/resources/templates/examples/CANTalon/src/org/usfirst/frc/team190/robot/Robot.java @@ -2,7 +2,7 @@ package $package; import edu.wpi.first.wpilibj.SpeedController; -import edu.wpi.first.wpilibj.hal.CanTalonSRX; +import edu.wpi.first.wpilibj.CANTalon; import edu.wpi.first.wpilibj.SampleRobot; import edu.wpi.first.wpilibj.Timer; @@ -13,27 +13,27 @@ import edu.wpi.first.wpilibj.Timer; */ public class Robot extends SampleRobot { - CanTalonSRX motor; + CANTalon motor; private final double k_updatePeriod = 0.005; // update every 0.005 seconds/5 milliseconds (200Hz) public Robot() { - motor = new CanTalonSRX(1); // Initialize the CanTalonSRX on device 1. + motor = new CANTalon(1); // Initialize the CanTalonSRX on device 1. } /** * Runs the motor from a joystick. */ public void operatorControl() { - motor.SetModeSelect(0); + motor.enableControl(); while (isOperatorControl() && isEnabled()) { - // Set the motor's output. + // Set the motor's output to half power. // This takes a number from -1 (100% speed in reverse) to +1 (100% speed // going forward) - motor.Set(0.5); + motor.set(0.5); Timer.delay(k_updatePeriod); // wait 5ms to the next update } - motor.Set(0.0); + motor.disable(); } } diff --git a/hal/lib/Athena/ctre/CanTalonSRX.cpp b/hal/lib/Athena/ctre/CanTalonSRX.cpp index 715befcf51..8c8f9a038d 100644 --- a/hal/lib/Athena/ctre/CanTalonSRX.cpp +++ b/hal/lib/Athena/ctre/CanTalonSRX.cpp @@ -1,4 +1,72 @@ /** + * @brief CAN TALON SRX driver. + * + * The TALON SRX is designed to instrument all runtime signals periodically. The default periods are chosen to support 16 TALONs + * with 10ms update rate for control (throttle or setpoint). However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate + * The getters for these unsolicited signals are auto generated at the bottom of this module. + * + * Likewise most control signals are sent periodically using the fire-and-forget CAN API. + * The setters for these unsolicited signals are auto generated at the bottom of this module. + * + * Signals that are not available in an unsolicited fashion are the Close Loop gains. + * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once + * or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application. These parameters are saved to flash so once they are + * loaded in the TALON, they will persist through power cycles and mode changes. + * + * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from + * and the ProfileSlotSelect is periodically sent in the 10 ms control frame. + * + * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters. Most likely + * they will only need to set them in a periodic fashion as a function of what motion the application is attempting. + * If this API is used, be mindful of the CAN utilization reported in the driver station. + * + * Encoder position is measured in encoder edges. Every edge is counted (similar to roboRIO 4X mode). + * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V). + * Use SetFeedbackDeviceSelect to select which sensor type you need. Once you do that you can use GetSensorPosition() + * and GetSensorVelocity(). These signals are updated on CANBus every 20ms (by default). + * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition. + * + * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel. + * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms. This allows easy instrumentation + * for "in the pits" checking of all sensors regardless of modeselect. The 100ms rate is overridable for teams who want to acquire sensor + * data for processing, not just instrumentation. Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms. + * + * Velocity is in position ticks / 100ms. + * + * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward). + * This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 1ms (if nonzero). + * + * Pos and velocity close loops are calc'd as + * err = target - posOrVel. + * iErr += err; + * if( (IZone!=0) and abs(err) > IZone) + * ClearIaccum() + * output = P X err + I X iErr + D X dErr + F X target + * dErr = err - lastErr + * P, I,and D gains are always positive. F can be negative. + * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase. + * Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted. + * + * P gain is specified in throttle per error tick. For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1 + * ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor. + * + * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023) + * for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor. + * Close loop and integral accumulator runs every 1ms. + * + * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023) + * per change of 1 unit (ADC or encoder) per ms. + * + * I Zone is specified in the same units as sensor position (ADC units or quadrature edges). If pos/vel error is outside of + * this value, the integrated error will auto-clear... + * if( (IZone!=0) and abs(err) > IZone) + * ClearIaccum() + * ...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low. + * + * CloseLoopRampRate ramps the target of the close loop. The units are in position per 1ms. Set to zero to disable ramping. + * So a value of 10 means allow the target input of the close loop to approach the user's demand by 10 units (ADC or encoder edges) + * per 1ms. + * * auto generated using spreadsheet and WpiClassGen.csproj * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967 */ @@ -16,6 +84,8 @@ #define STATUS_7 0x02041580 #define CONTROL_1 0x02040000 +#define CONTROL_2 0x02040040 +#define CONTROL_3 0x02040080 #define EXPECTED_RESPONSE_TIMEOUT_MS (200) #define GET_STATUS1() CtreCanNode::recMsg rx = GetRx(STATUS_1 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS) @@ -26,20 +96,30 @@ #define GET_STATUS6() CtreCanNode::recMsg rx = GetRx(STATUS_6 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS) #define GET_STATUS7() CtreCanNode::recMsg rx = GetRx(STATUS_7 | GetDeviceNumber(), EXPECTED_RESPONSE_TIMEOUT_MS) +#define PARAM_REQUEST 0x02041800 +#define PARAM_RESPONSE 0x02041840 +#define PARAM_SET 0x02041880 + +const int kParamArbIdValue = PARAM_RESPONSE; +const int kParamArbIdMask = 0xFFFFFFFF; + +const double FLOAT_TO_FXP = (double)0x400000; +const double FXP_TO_FLOAT = 0.0000002384185791015625; + /* encoder/decoders */ /** control */ typedef struct _TALON_Control_1_General_10ms_t { unsigned TokenH:8; unsigned TokenL:8; - unsigned Demand24H:8; - unsigned Demand24M:8; - unsigned Demand24L:8; - unsigned CloseLoopCellSelect:1; - unsigned SelectlFeedbackDevice:4; - unsigned LimitSwitchEn:3; - unsigned RevEncoderPosAndVel:1; + unsigned DemandH:8; + unsigned DemandM:8; + unsigned DemandL:8; + unsigned ProfileSlotSelect:1; + unsigned FeedbackDeviceSelect:4; + unsigned OverrideLimitSwitchEn:3; + unsigned RevFeedbackSensor:1; unsigned RevMotDuringCloseLoopEn:1; - unsigned BrakeType:2; + unsigned OverrideBrakeType:2; unsigned ModeSelect:4; unsigned RampThrottle:8; } TALON_Control_1_General_10ms_t ; @@ -59,15 +139,15 @@ typedef struct _TALON_Status_1_General_10ms_t { unsigned CloseLoopErrH:8; unsigned CloseLoopErrM:8; unsigned CloseLoopErrL:8; - unsigned Throttle_h3:3; + unsigned AppliedThrottle_h3:3; unsigned Fault_RevSoftLim:1; unsigned Fault_ForSoftLim:1; unsigned TokLocked:1; unsigned LimitSwitchClosedRev:1; unsigned LimitSwitchClosedFor:1; - unsigned Throttle_l8:8; + unsigned AppliedThrottle_l8:8; unsigned ModeSelect_h1:1; - unsigned SelectlFeedbackDevice:4; + unsigned FeedbackDeviceSelect:4; unsigned LimitSwitchEn:3; unsigned Fault_HardwareFailure:1; unsigned Fault_RevLim:1; @@ -92,7 +172,7 @@ typedef struct _TALON_Status_2_Feedback_20ms_t { unsigned StckyFault_OverTemp:1; unsigned Current_l2:2; unsigned reserved:6; - unsigned CloseLoopCellSelect:1; + unsigned ProfileSlotSelect:1; unsigned BrakeIsEnabled:1; } TALON_Status_2_Feedback_20ms_t ; typedef struct _TALON_Status_3_Enc_100ms_t { @@ -149,84 +229,93 @@ typedef struct _TALON_Status_7_Debug_200ms_t { unsigned TokenizationSucceses_h8:8; unsigned TokenizationSucceses_l8:8; } TALON_Status_7_Debug_200ms_t ; -typedef struct _TALON_Config_SetGains0_1_t { - unsigned PH:8; - unsigned PM:8; - unsigned PL:8; - unsigned IH:8; - unsigned IM:8; - unsigned IL:8; - unsigned IZoneH:8; - unsigned IZoneL:8; -} TALON_Config_SetGains0_1_t ; -typedef struct _TALON_Config_SetGains0_2_t { - unsigned DH:8; - unsigned DM:8; - unsigned DL:8; - unsigned FH:8; - unsigned FM:8; - unsigned FL:8; - unsigned RampRateH:8; - unsigned RampRateL:8; -} TALON_Config_SetGains0_2_t ; -typedef struct _TALON_Config_SetGains1_1_t { - unsigned PH:8; - unsigned PM:8; - unsigned PL:8; - unsigned IH:8; - unsigned IM:8; - unsigned IL:8; - unsigned IZoneH:8; - unsigned IZoneL:8; -} TALON_Config_SetGains1_1_t ; -typedef struct _TALON_Config_SetGains1_2_t { - unsigned DH:8; - unsigned DM:8; - unsigned DL:8; - unsigned FH:8; - unsigned FM:8; - unsigned FL:8; - unsigned RampRateH:8; - unsigned RampRateL:8; -} TALON_Config_SetGains1_2_t ; -typedef struct _TALON_Config_SetSoftLimits_t { - unsigned LimitFH:8; - unsigned LimitFMH:8; - unsigned LimitFML:8; - unsigned LimitFL:8; - unsigned LimitRH:8; - unsigned LimitRMH:8; - unsigned LimitRML:8; - unsigned LimitRL:8; -} TALON_Config_SetSoftLimits_t ; typedef struct _TALON_Param_Request_t { unsigned ParamEnum:8; } TALON_Param_Request_t ; typedef struct _TALON_Param_Response_t { unsigned ParamEnum:8; - unsigned ParamValueH:8; - unsigned ParamValueMH:8; - unsigned ParamValueML:8; unsigned ParamValueL:8; + unsigned ParamValueML:8; + unsigned ParamValueMH:8; + unsigned ParamValueH:8; } TALON_Param_Response_t ; -CanTalonSRX::CanTalonSRX(int deviceNumber): CtreCanNode((UINT8)deviceNumber) +CanTalonSRX::CanTalonSRX(int deviceNumber): CtreCanNode((UINT8)deviceNumber), _can_h(0), _can_stat(0) { - UINT8 device = deviceNumber; - RegisterRx(STATUS_1 | device ); - RegisterRx(STATUS_2 | device ); - RegisterRx(STATUS_3 | device ); - RegisterRx(STATUS_4 | device ); - RegisterRx(STATUS_5 | device ); - RegisterRx(STATUS_6 | device ); - RegisterRx(STATUS_7 | device ); - RegisterTx(CONTROL_1 | device, 10); + RegisterRx(STATUS_1 | (UINT8)deviceNumber ); + RegisterRx(STATUS_2 | (UINT8)deviceNumber ); + RegisterRx(STATUS_3 | (UINT8)deviceNumber ); + RegisterRx(STATUS_4 | (UINT8)deviceNumber ); + RegisterRx(STATUS_5 | (UINT8)deviceNumber ); + RegisterRx(STATUS_6 | (UINT8)deviceNumber ); + RegisterRx(STATUS_7 | (UINT8)deviceNumber ); + RegisterTx(CONTROL_1 | (UINT8)deviceNumber, 10); + /* default our frame rate table to what firmware defaults to. */ + _statusRateMs[0] = 10; /* TALON_Status_1_General_10ms_t */ + _statusRateMs[1] = 20; /* TALON_Status_2_Feedback_20ms_t */ + _statusRateMs[2] = 100; /* TALON_Status_3_Enc_100ms_t */ + _statusRateMs[3] = 100; /* TALON_Status_4_AinTempVbat_100ms_t */ + /* the only default param that is nonzero is limit switch. + * Default to using the flash settings. */ + SetOverrideLimitSwitchEn(kLimitSwitchOverride_UseDefaultsFromFlash); } /* CanTalonSRX D'tor */ CanTalonSRX::~CanTalonSRX() { + if(_can_h){ + FRC_NetworkCommunication_CANSessionMux_closeStreamSession(_can_h); + _can_h = 0; + } +} +void CanTalonSRX::OpenSessionIfNeedBe() +{ + _can_stat = 0; + if (_can_h == 0) { + /* bit30 - bit8 must match $000002XX. Top bit is not masked to get remote frames */ + FRC_NetworkCommunication_CANSessionMux_openStreamSession(&_can_h,kParamArbIdValue | GetDeviceNumber(), kParamArbIdMask, kMsgCapacity, &_can_stat); + if (_can_stat == 0) { + /* success */ + } else { + /* something went wrong, try again later */ + _can_h = 0; + } + } +} +void CanTalonSRX::ProcessStreamMessages() +{ + if(0 == _can_h) + OpenSessionIfNeedBe(); + /* process receive messages */ + uint32_t i; + uint32_t messagesToRead = sizeof(_msgBuff) / sizeof(_msgBuff[0]); + uint32_t messagesRead = 0; + /* read out latest bunch of messages */ + _can_stat = 0; + if (_can_h){ + FRC_NetworkCommunication_CANSessionMux_readStreamSession(_can_h,_msgBuff, messagesToRead, &messagesRead, &_can_stat); + } + /* loop thru each message of interest */ + for (i = 0; i < messagesRead; ++i) { + tCANStreamMessage * msg = _msgBuff + i; + if(msg->messageID == (PARAM_RESPONSE | GetDeviceNumber()) ){ + TALON_Param_Response_t * paramResp = (TALON_Param_Response_t*)msg->data; + /* decode value */ + int32_t val = paramResp->ParamValueH; + val <<= 8; + val |= paramResp->ParamValueMH; + val <<= 8; + val |= paramResp->ParamValueML; + val <<= 8; + val |= paramResp->ParamValueL; + /* save latest signal */ + _sigs[paramResp->ParamEnum] = val; + }else{ + int brkpthere = 42; + ++brkpthere; + } + } } void CanTalonSRX::Set(double value) { @@ -234,11 +323,288 @@ void CanTalonSRX::Set(double value) value = 1; else if(value < -1) value = -1; - value *= 1023; - SetDemand24(value); /* must be within [-1023,1023] */ + SetDemand(1023*value); /* must be within [-1023,1023] */ +} +/*---------------------setters and getters that use the param request/response-------------*/ +/** + * Send a one shot frame to set an arbitrary signal. + * Most signals are in the control frame so avoid using this API unless you have to. + * Use this api for... + * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically. + * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame. + * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms. + */ +CTR_Code CanTalonSRX::SetParamRaw(uint32_t paramEnum, int32_t rawBits) +{ + /* caller is using param API. Open session if it hasn'T been done. */ + if(0 == _can_h) + OpenSessionIfNeedBe(); + TALON_Param_Response_t frame; + memset(&frame,0,sizeof(frame)); + frame.ParamEnum = paramEnum; + frame.ParamValueH = rawBits >> 0x18; + frame.ParamValueMH = rawBits >> 0x10; + frame.ParamValueML = rawBits >> 0x08; + frame.ParamValueL = rawBits; + int32_t status = 0; + FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_SET | GetDeviceNumber(), (const uint8_t*)&frame, 5, 0, &status); + if(status) + return CTR_TxFailed; + return CTR_OKAY; +} +/** + * Checks cached CAN frames and updating solicited signals. + */ +CTR_Code CanTalonSRX::GetParamResponseRaw(uint32_t paramEnum, int32_t & rawBits) +{ + CTR_Code retval = CTR_OKAY; + /* process received param events. We don't expect many since this API is not used often. */ + ProcessStreamMessages(); + /* grab the solicited signal value */ + sigs_t::iterator i = _sigs.find(paramEnum); + if(i == _sigs.end()){ + retval = CTR_SigNotUpdated; + }else{ + rawBits = i->second; + } + return retval; +} +/** + * Asks TALON to immedietely respond with signal value. This API is only used for signals that are not sent periodically. + * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values. + * @param param to request. + */ +CTR_Code CanTalonSRX::RequestParam(param_t paramEnum) +{ + /* process received param events. We don't expect many since this API is not used often. */ + ProcessStreamMessages(); + TALON_Param_Request_t frame; + memset(&frame,0,sizeof(frame)); + frame.ParamEnum = paramEnum; + int32_t status = 0; + FRC_NetworkCommunication_CANSessionMux_sendMessage(PARAM_REQUEST | GetDeviceNumber(), (const uint8_t*)&frame, 1, 0, &status); + if(status) + return CTR_TxFailed; + return CTR_OKAY; } -/*------------------------ auto generated ----------------------*/ +CTR_Code CanTalonSRX::SetParam(param_t paramEnum, double value) +{ + int32_t rawbits = 0; + switch(paramEnum){ + case eProfileParamSlot0_P:/* 10.22 fixed pt value */ + case eProfileParamSlot0_I: + case eProfileParamSlot0_D: + case eProfileParamSlot0_F: + case eProfileParamSlot1_P: + case eProfileParamSlot1_I: + case eProfileParamSlot1_D: + case eProfileParamSlot1_F: + case eCurrent: + case eTemp: + case eBatteryV: + rawbits = value * FLOAT_TO_FXP; + break; + default: /* everything else is integral */ + rawbits = (int32_t)value; + break; + } + return SetParamRaw(paramEnum,rawbits); +} +CTR_Code CanTalonSRX::GetParamResponse(param_t paramEnum, double & value) +{ + int32_t rawbits = 0; + CTR_Code retval = GetParamResponseRaw(paramEnum,rawbits); + switch(paramEnum){ + case eProfileParamSlot0_P:/* 10.22 fixed pt value */ + case eProfileParamSlot0_I: + case eProfileParamSlot0_D: + case eProfileParamSlot0_F: + case eProfileParamSlot1_P: + case eProfileParamSlot1_I: + case eProfileParamSlot1_D: + case eProfileParamSlot1_F: + case eCurrent: + case eTemp: + case eBatteryV: + value = ((double)rawbits) * FXP_TO_FLOAT; + break; + default: /* everything else is integral */ + value = (double)rawbits; + break; + } + return retval; +} +CTR_Code CanTalonSRX::GetParamResponseInt32(param_t paramEnum, int32_t & value) +{ + double dvalue = 0; + CTR_Code retval = GetParamResponse(paramEnum, dvalue); + value = (int32_t)dvalue; + return retval; +} +/*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/ +/*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/ +/*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/ +/*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/ +CTR_Code CanTalonSRX::SetPgain(uint32_t slotIdx,double gain) +{ + if(slotIdx == 0) + return SetParam(eProfileParamSlot0_P, gain); + return SetParam(eProfileParamSlot1_P, gain); +} +CTR_Code CanTalonSRX::SetIgain(uint32_t slotIdx,double gain) +{ + if(slotIdx == 0) + return SetParam(eProfileParamSlot0_I, gain); + return SetParam(eProfileParamSlot1_I, gain); +} +CTR_Code CanTalonSRX::SetDgain(uint32_t slotIdx,double gain) +{ + if(slotIdx == 0) + return SetParam(eProfileParamSlot0_D, gain); + return SetParam(eProfileParamSlot1_D, gain); +} +CTR_Code CanTalonSRX::SetFgain(uint32_t slotIdx,double gain) +{ + if(slotIdx == 0) + return SetParam(eProfileParamSlot0_F, gain); + return SetParam(eProfileParamSlot1_F, gain); +} +CTR_Code CanTalonSRX::SetIzone(uint32_t slotIdx,int32_t zone) +{ + if(slotIdx == 0) + return SetParam(eProfileParamSlot0_IZone, zone); + return SetParam(eProfileParamSlot1_IZone, zone); +} +CTR_Code CanTalonSRX::SetCloseLoopRampRate(uint32_t slotIdx,int32_t closeLoopRampRate) +{ + if(slotIdx == 0) + return SetParam(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate); + return SetParam(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate); +} +CTR_Code CanTalonSRX::GetPgain(uint32_t slotIdx,double & gain) +{ + if(slotIdx == 0) + return GetParamResponse(eProfileParamSlot0_P, gain); + return GetParamResponse(eProfileParamSlot1_P, gain); +} +CTR_Code CanTalonSRX::GetIgain(uint32_t slotIdx,double & gain) +{ + if(slotIdx == 0) + return GetParamResponse(eProfileParamSlot0_I, gain); + return GetParamResponse(eProfileParamSlot1_I, gain); +} +CTR_Code CanTalonSRX::GetDgain(uint32_t slotIdx,double & gain) +{ + if(slotIdx == 0) + return GetParamResponse(eProfileParamSlot0_D, gain); + return GetParamResponse(eProfileParamSlot1_D, gain); +} +CTR_Code CanTalonSRX::GetFgain(uint32_t slotIdx,double & gain) +{ + if(slotIdx == 0) + return GetParamResponse(eProfileParamSlot0_F, gain); + return GetParamResponse(eProfileParamSlot1_F, gain); +} +CTR_Code CanTalonSRX::GetIzone(uint32_t slotIdx,int32_t & zone) +{ + if(slotIdx == 0) + return GetParamResponseInt32(eProfileParamSlot0_IZone, zone); + return GetParamResponseInt32(eProfileParamSlot1_IZone, zone); +} +CTR_Code CanTalonSRX::GetCloseLoopRampRate(uint32_t slotIdx,int32_t & closeLoopRampRate) +{ + if(slotIdx == 0) + return GetParamResponseInt32(eProfileParamSlot0_CloseLoopRampRate, closeLoopRampRate); + return GetParamResponseInt32(eProfileParamSlot1_CloseLoopRampRate, closeLoopRampRate); +} + +CTR_Code CanTalonSRX::SetSensorPosition(int32_t pos) +{ + return SetParam(eSensorPosition, pos); +} +CTR_Code CanTalonSRX::SetForwardSoftLimit(int32_t forwardLimit) +{ + return SetParam(eProfileParamSoftLimitForThreshold, forwardLimit); +} +CTR_Code CanTalonSRX::SetReverseSoftLimit(int32_t reverseLimit) +{ + return SetParam(eProfileParamSoftLimitRevThreshold, reverseLimit); +} +CTR_Code CanTalonSRX::SetForwardSoftEnable(int32_t enable) +{ + return SetParam(eProfileParamSoftLimitForEnable, enable); +} +CTR_Code CanTalonSRX::SetReverseSoftEnable(int32_t enable) +{ + return SetParam(eProfileParamSoftLimitRevEnable, enable); +} +CTR_Code CanTalonSRX::GetForwardSoftLimit(int32_t & forwardLimit) +{ + return GetParamResponseInt32(eProfileParamSoftLimitForThreshold, forwardLimit); +} +CTR_Code CanTalonSRX::GetReverseSoftLimit(int32_t & reverseLimit) +{ + return GetParamResponseInt32(eProfileParamSoftLimitRevThreshold, reverseLimit); +} +CTR_Code CanTalonSRX::GetForwardSoftEnable(int32_t & enable) +{ + return GetParamResponseInt32(eProfileParamSoftLimitForEnable, enable); +} +CTR_Code CanTalonSRX::GetReverseSoftEnable(int32_t & enable) +{ + return GetParamResponseInt32(eProfileParamSoftLimitRevEnable, enable); +} +/** + * Change the periodMs of a TALON's status frame. See kStatusFrame_* enums for what's available. + */ +CTR_Code CanTalonSRX::SetStatusFrameRate(uint32_t frameEnum, uint8_t periodMs) +{ + int32_t status = 0; + /* tweak just the status messsage rate the caller cares about */ + switch(frameEnum){ + case kStatusFrame_General: + _statusRateMs[0] = periodMs; + break; + case kStatusFrame_Feedback: + _statusRateMs[1] = periodMs; + break; + case kStatusFrame_Encoder: + _statusRateMs[2] = periodMs; + break; + case kStatusFrame_AnalogTempVbat: + _statusRateMs[3] = periodMs; + break; + } + /* build our request frame */ + TALON_Control_2_Rates_OneShot_t frame; + memset(&frame,0,sizeof(frame)); + frame.Status1Ms = _statusRateMs[0]; + frame.Status2Ms = _statusRateMs[1]; + frame.Status3Ms = _statusRateMs[2]; + frame.Status4Ms = _statusRateMs[3]; + FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_2 | GetDeviceNumber(), (const uint8_t*)&frame, sizeof(frame), 0, &status); + if(status) + return CTR_TxFailed; + return CTR_OKAY; +} +/** + * Clear all sticky faults in TALON. + */ +CTR_Code CanTalonSRX::ClearStickyFaults() +{ + int32_t status = 0; + /* build request frame */ + TALON_Control_3_ClearFlags_OneShot_t frame; + memset(&frame,0,sizeof(frame)); + frame.ClearStickyFaults = 1; + FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_3 | GetDeviceNumber(), (const uint8_t*)&frame, sizeof(frame), 0, &status); + if(status) + return CTR_TxFailed; + return CTR_OKAY; +} +/*------------------------ auto generated. This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/ +/*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/ CTR_Code CanTalonSRX::GetFault_OverTemp(int ¶m) { GET_STATUS1(); @@ -317,13 +683,13 @@ CTR_Code CanTalonSRX::GetStckyFault_RevSoftLim(int ¶m) param = rx->StckyFault_RevSoftLim; return rx.err; } -CTR_Code CanTalonSRX::GetAppliedThrottle11(int ¶m) +CTR_Code CanTalonSRX::GetAppliedThrottle(int ¶m) { GET_STATUS1(); uint32_t raw = 0; - raw |= rx->Throttle_h3; + raw |= rx->AppliedThrottle_h3; raw <<= 8; - raw |= rx->Throttle_l8; + raw |= rx->AppliedThrottle_l8; param = (int)raw; return rx.err; } @@ -339,10 +705,10 @@ CTR_Code CanTalonSRX::GetCloseLoopErr(int ¶m) param = (int)raw; return rx.err; } -CTR_Code CanTalonSRX::GetSelectlFeedbackDevice(int ¶m) +CTR_Code CanTalonSRX::GetFeedbackDeviceSelect(int ¶m) { GET_STATUS1(); - param = rx->SelectlFeedbackDevice; + param = rx->FeedbackDeviceSelect; return rx.err; } CTR_Code CanTalonSRX::GetModeSelect(int ¶m) @@ -373,12 +739,6 @@ CTR_Code CanTalonSRX::GetLimitSwitchClosedRev(int ¶m) param = rx->LimitSwitchClosedRev; return rx.err; } -CTR_Code CanTalonSRX::GetCloseLoopCellSelect(int ¶m) -{ - GET_STATUS2(); - param = rx->CloseLoopCellSelect; - return rx.err; -} CTR_Code CanTalonSRX::GetSensorPosition(int ¶m) { GET_STATUS2(); @@ -533,29 +893,29 @@ CTR_Code CanTalonSRX::GetFirmVers(int ¶m) param = (int)raw; return rx.err; } -CTR_Code CanTalonSRX::SetDemand24(int param) +CTR_Code CanTalonSRX::SetDemand(int param) { CtreCanNode::txTask toFill = GetTx(CONTROL_1 | GetDeviceNumber()); if (toFill.IsEmpty()) return CTR_UnexpectedArbId; - toFill->Demand24H = param>>16; - toFill->Demand24M = param>>8; - toFill->Demand24L = param>>0; + toFill->DemandH = param>>16; + toFill->DemandM = param>>8; + toFill->DemandL = param>>0; FlushTx(toFill); return CTR_OKAY; } -CTR_Code CanTalonSRX::SetLimitSwitchEn(int param) +CTR_Code CanTalonSRX::SetOverrideLimitSwitchEn(int param) { CtreCanNode::txTask toFill = GetTx(CONTROL_1 | GetDeviceNumber()); if (toFill.IsEmpty()) return CTR_UnexpectedArbId; - toFill->LimitSwitchEn = param; + toFill->OverrideLimitSwitchEn = param; FlushTx(toFill); return CTR_OKAY; } -CTR_Code CanTalonSRX::SetSelectlFeedbackDevice(int param) +CTR_Code CanTalonSRX::SetFeedbackDeviceSelect(int param) { CtreCanNode::txTask toFill = GetTx(CONTROL_1 | GetDeviceNumber()); if (toFill.IsEmpty()) return CTR_UnexpectedArbId; - toFill->SelectlFeedbackDevice = param; + toFill->FeedbackDeviceSelect = param; FlushTx(toFill); return CTR_OKAY; } @@ -567,11 +927,11 @@ CTR_Code CanTalonSRX::SetRevMotDuringCloseLoopEn(int param) FlushTx(toFill); return CTR_OKAY; } -CTR_Code CanTalonSRX::SetBrakeType(int param) +CTR_Code CanTalonSRX::SetOverrideBrakeType(int param) { CtreCanNode::txTask toFill = GetTx(CONTROL_1 | GetDeviceNumber()); if (toFill.IsEmpty()) return CTR_UnexpectedArbId; - toFill->BrakeType = param; + toFill->OverrideBrakeType = param; FlushTx(toFill); return CTR_OKAY; } @@ -583,11 +943,11 @@ CTR_Code CanTalonSRX::SetModeSelect(int param) FlushTx(toFill); return CTR_OKAY; } -CTR_Code CanTalonSRX::SetCloseLoopCellSelect(int param) +CTR_Code CanTalonSRX::SetProfileSlotSelect(int param) { CtreCanNode::txTask toFill = GetTx(CONTROL_1 | GetDeviceNumber()); if (toFill.IsEmpty()) return CTR_UnexpectedArbId; - toFill->CloseLoopCellSelect = param; + toFill->ProfileSlotSelect = param; FlushTx(toFill); return CTR_OKAY; } @@ -599,11 +959,11 @@ CTR_Code CanTalonSRX::SetRampThrottle(int param) FlushTx(toFill); return CTR_OKAY; } -CTR_Code CanTalonSRX::SetRevEncoderPosAndVel(int param) +CTR_Code CanTalonSRX::SetRevFeedbackSensor(int param) { CtreCanNode::txTask toFill = GetTx(CONTROL_1 | GetDeviceNumber()); if (toFill.IsEmpty()) return CTR_UnexpectedArbId; - toFill->RevEncoderPosAndVel = param; + toFill->RevFeedbackSensor = param; FlushTx(toFill); return CTR_OKAY; } diff --git a/hal/lib/Athena/ctre/CanTalonSRX.h b/hal/lib/Athena/ctre/CanTalonSRX.h index 4a9bfe0c58..3c1a7378e0 100644 --- a/hal/lib/Athena/ctre/CanTalonSRX.h +++ b/hal/lib/Athena/ctre/CanTalonSRX.h @@ -1,4 +1,72 @@ /** + * @brief CAN TALON SRX driver. + * + * The TALON SRX is designed to instrument all runtime signals periodically. The default periods are chosen to support 16 TALONs + * with 10ms update rate for control (throttle or setpoint). However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate + * The getters for these unsolicited signals are auto generated at the bottom of this module. + * + * Likewise most control signals are sent periodically using the fire-and-forget CAN API. + * The setters for these unsolicited signals are auto generated at the bottom of this module. + * + * Signals that are not available in an unsolicited fashion are the Close Loop gains. + * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once + * or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application. These parameters are saved to flash so once they are + * loaded in the TALON, they will persist through power cycles and mode changes. + * + * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from + * and the ProfileSlotSelect is periodically sent in the 10 ms control frame. + * + * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters. Most likely + * they will only need to set them in a periodic fashion as a function of what motion the application is attempting. + * If this API is used, be mindful of the CAN utilization reported in the driver station. + * + * Encoder position is measured in encoder edges. Every edge is counted (similar to roboRIO 4X mode). + * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V). + * Use SetFeedbackDeviceSelect to select which sensor type you need. Once you do that you can use GetSensorPosition() + * and GetSensorVelocity(). These signals are updated on CANBus every 20ms (by default). + * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition. + * + * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel. + * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms. This allows easy instrumentation + * for "in the pits" checking of all sensors regardless of modeselect. The 100ms rate is overridable for teams who want to acquire sensor + * data for processing, not just instrumentation. Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms. + * + * Velocity is in position ticks / 100ms. + * + * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward). + * This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 1ms (if nonzero). + * + * Pos and velocity close loops are calc'd as + * err = target - posOrVel. + * iErr += err; + * if( (IZone!=0) and abs(err) > IZone) + * ClearIaccum() + * output = P X err + I X iErr + D X dErr + F X target + * dErr = err - lastErr + * P, I,and D gains are always positive. F can be negative. + * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase. + * Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted. + * + * P gain is specified in throttle per error tick. For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1 + * ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor. + * + * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023) + * for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor. + * Close loop and integral accumulator runs every 1ms. + * + * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023) + * per change of 1 unit (ADC or encoder) per ms. + * + * I Zone is specified in the same units as sensor position (ADC units or quadrature edges). If pos/vel error is outside of + * this value, the integrated error will auto-clear... + * if( (IZone!=0) and abs(err) > IZone) + * ClearIaccum() + * ...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low. + * + * CloseLoopRampRate ramps the target of the close loop. The units are in position per 1ms. Set to zero to disable ramping. + * So a value of 10 means allow the target input of the close loop to approach the user's demand by 10 units (ADC or encoder edges) + * per 1ms. + * * auto generated using spreadsheet and WpiClassGen.csproj * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967 */ @@ -7,14 +75,195 @@ #include "ctre.h" //BIT Defines + Typedefs #include "CtreCanNode.h" #include //CAN Comm +#include class CanTalonSRX : public CtreCanNode { +private: + + /** just in case user wants to modify periods of certain status frames. + * Default the vars to match the firmware default. */ + uint32_t _statusRateMs[4]; + //---------------------- Vars for opening a CAN stream if caller needs signals that require soliciting */ + uint32_t _can_h; //!< Session handle for catching response params. + int32_t _can_stat; //!< Session handle status. + struct tCANStreamMessage _msgBuff[20]; + static int const kMsgCapacity = 20; + typedef std::map sigs_t; + sigs_t _sigs; //!< Catches signal updates that are solicited. Expect this to be very few. + void OpenSessionIfNeedBe(); + void ProcessStreamMessages(); + /** + * Send a one shot frame to set an arbitrary signal. + * Most signals are in the control frame so avoid using this API unless you have to. + * Use this api for... + * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically. + * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame. + * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms. + */ + CTR_Code SetParamRaw(uint32_t paramEnum, int32_t rawBits); + /** + * Checks cached CAN frames and updating solicited signals. + */ + CTR_Code GetParamResponseRaw(uint32_t paramEnum, int32_t & rawBits); public: CanTalonSRX(int deviceNumber=0); ~CanTalonSRX(); void Set(double value); - - /*------------------------ auto generated ----------------------*/ + /* mode select enumerations */ + static const int kMode_DutyCycle = 0; //!< Demand is 11bit signed duty cycle [-1023,1023]. + static const int kMode_PositionCloseLoop = 1; //!< Position PIDF. + static const int kMode_VelocityCloseLoop = 2; //!< Velocity PIDF. + static const int kMode_CurrentCloseLoop = 3; //!< Current close loop - not done. + static const int kMode_VoltCompen = 4; //!< Voltage Compensation Mode - not done. Demand is fixed pt target 8.8 volts. + static const int kMode_SlaveFollower = 5; //!< Demand is the 6 bit Device ID of the 'master' TALON SRX. + static const int kMode_NoDrive = 15; //!< Zero the output (honors brake/coast) regardless of demand. Might be useful if we need to change modes but can't atomically change all the signals we want in between. + /* limit switch enumerations */ + static const int kLimitSwitchOverride_UseDefaultsFromFlash = 1; + static const int kLimitSwitchOverride_DisableFwd_DisableRev = 4; + static const int kLimitSwitchOverride_DisableFwd_EnableRev = 5; + static const int kLimitSwitchOverride_EnableFwd_DisableRev = 6; + static const int kLimitSwitchOverride_EnableFwd_EnableRev = 7; + /* brake override enumerations */ + static const int kBrakeOverride_UseDefaultsFromFlash = 0; + static const int kBrakeOverride_OverrideCoast = 1; + static const int kBrakeOverride_OverrideBrake = 2; + /* feedback device enumerations */ + static const int kFeedbackDev_DigitalQuadEnc=0; + static const int kFeedbackDev_AnalogPot=2; + static const int kFeedbackDev_AnalogEncoder=3; + static const int kFeedbackDev_CountEveryRisingEdge=4; + static const int kFeedbackDev_CountEveryFallingEdge=5; + static const int kFeedbackDev_PosIsPulseWidth=8; + /* ProfileSlotSelect enumerations*/ + static const int kProfileSlotSelect_Slot0 = 0; + static const int kProfileSlotSelect_Slot1 = 1; + /* status frame rate types */ + static const int kStatusFrame_General = 0; + static const int kStatusFrame_Feedback = 1; + static const int kStatusFrame_Encoder = 2; + static const int kStatusFrame_AnalogTempVbat = 3; + /** + * Signal enumeration for generic signal access. + * Although every signal is enumerated, only use this for traffic that must be solicited. + * Use the auto generated getters/setters at bottom of this header as much as possible. + */ + typedef enum _param_t{ + eProfileParamSlot0_P=1, + eProfileParamSlot0_I=2, + eProfileParamSlot0_D=3, + eProfileParamSlot0_F=4, + eProfileParamSlot0_IZone=5, + eProfileParamSlot0_CloseLoopRampRate=6, + eProfileParamSlot1_P=11, + eProfileParamSlot1_I=12, + eProfileParamSlot1_D=13, + eProfileParamSlot1_F=14, + eProfileParamSlot1_IZone=15, + eProfileParamSlot1_CloseLoopRampRate=16, + eProfileParamSoftLimitForThreshold=21, + eProfileParamSoftLimitRevThreshold=22, + eProfileParamSoftLimitForEnable=23, + eProfileParamSoftLimitRevEnable=24, + eOnBoot_BrakeMode=31, + eOnBoot_LimitSwitch_Forward_NormallyClosed=32, + eOnBoot_LimitSwitch_Reverse_NormallyClosed=33, + eOnBoot_LimitSwitch_Forward_Disable=34, + eOnBoot_LimitSwitch_Reverse_Disable=35, + eFault_OverTemp=41, + eFault_UnderVoltage=42, + eFault_ForLim=43, + eFault_RevLim=44, + eFault_HardwareFailure=45, + eFault_ForSoftLim=46, + eFault_RevSoftLim=47, + eStckyFault_OverTemp=48, + eStckyFault_UnderVoltage=49, + eStckyFault_ForLim=50, + eStckyFault_RevLim=51, + eStckyFault_ForSoftLim=52, + eStckyFault_RevSoftLim=53, + eAppliedThrottle=61, + eCloseLoopErr=62, + eFeedbackDeviceSelect=63, + eRevMotDuringCloseLoopEn=64, + eModeSelect=65, + eProfileSlotSelect=66, + eRampThrottle=67, + eRevFeedbackSensor=68, + eLimitSwitchEn=69, + eLimitSwitchClosedFor=70, + eLimitSwitchClosedRev=71, + eSensorPosition=73, + eSensorVelocity=74, + eCurrent=75, + eBrakeIsEnabled=76, + eEncPosition=77, + eEncVel=78, + eEncIndexRiseEvents=79, + eQuadApin=80, + eQuadBpin=81, + eQuadIdxpin=82, + eAnalogInWithOv=83, + eAnalogInVel=84, + eTemp=85, + eBatteryV=86, + eResetCount=87, + eResetFlags=88, + eFirmVers=89, + eSettingsChanged=90, + }param_t; + /*---------------------setters and getters that use the solicated param request/response-------------*//** + * Send a one shot frame to set an arbitrary signal. + * Most signals are in the control frame so avoid using this API unless you have to. + * Use this api for... + * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically. + * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame. + * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms. + */ + CTR_Code SetParam(param_t paramEnum, double value); + /** + * Asks TALON to immedietely respond with signal value. This API is only used for signals that are not sent periodically. + * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values. + * @param param to request. + */ + CTR_Code RequestParam(param_t paramEnum); + CTR_Code GetParamResponse(param_t paramEnum, double & value); + CTR_Code GetParamResponseInt32(param_t paramEnum, int32_t & value); + /*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/ + /*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/ + /*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/ + /*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/ + CTR_Code SetPgain(uint32_t slotIdx,double gain); + CTR_Code SetIgain(uint32_t slotIdx,double gain); + CTR_Code SetDgain(uint32_t slotIdx,double gain); + CTR_Code SetFgain(uint32_t slotIdx,double gain); + CTR_Code SetIzone(uint32_t slotIdx,int32_t zone); + CTR_Code SetCloseLoopRampRate(uint32_t slotIdx,int32_t closeLoopRampRate); + CTR_Code SetSensorPosition(int32_t pos); + CTR_Code SetForwardSoftLimit(int32_t forwardLimit); + CTR_Code SetReverseSoftLimit(int32_t reverseLimit); + CTR_Code SetForwardSoftEnable(int32_t enable); + CTR_Code SetReverseSoftEnable(int32_t enable); + CTR_Code GetPgain(uint32_t slotIdx,double & gain); + CTR_Code GetIgain(uint32_t slotIdx,double & gain); + CTR_Code GetDgain(uint32_t slotIdx,double & gain); + CTR_Code GetFgain(uint32_t slotIdx,double & gain); + CTR_Code GetIzone(uint32_t slotIdx,int32_t & zone); + CTR_Code GetCloseLoopRampRate(uint32_t slotIdx,int32_t & closeLoopRampRate); + CTR_Code GetForwardSoftLimit(int32_t & forwardLimit); + CTR_Code GetReverseSoftLimit(int32_t & reverseLimit); + CTR_Code GetForwardSoftEnable(int32_t & enable); + CTR_Code GetReverseSoftEnable(int32_t & enable); + /** + * Change the periodMs of a TALON's status frame. See kStatusFrame_* enums for what's available. + */ + CTR_Code SetStatusFrameRate(uint32_t frameEnum, uint8_t periodMs); + /** + * Clear all sticky faults in TALON. + */ + CTR_Code ClearStickyFaults(); + /*------------------------ auto generated. This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/ + /*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/ CTR_Code GetFault_OverTemp(int ¶m); CTR_Code GetFault_UnderVoltage(int ¶m); CTR_Code GetFault_ForLim(int ¶m); @@ -28,14 +277,13 @@ public: CTR_Code GetStckyFault_RevLim(int ¶m); CTR_Code GetStckyFault_ForSoftLim(int ¶m); CTR_Code GetStckyFault_RevSoftLim(int ¶m); - CTR_Code GetAppliedThrottle11(int ¶m); + CTR_Code GetAppliedThrottle(int ¶m); CTR_Code GetCloseLoopErr(int ¶m); - CTR_Code GetSelectlFeedbackDevice(int ¶m); + CTR_Code GetFeedbackDeviceSelect(int ¶m); CTR_Code GetModeSelect(int ¶m); CTR_Code GetLimitSwitchEn(int ¶m); CTR_Code GetLimitSwitchClosedFor(int ¶m); CTR_Code GetLimitSwitchClosedRev(int ¶m); - CTR_Code GetCloseLoopCellSelect(int ¶m); CTR_Code GetSensorPosition(int ¶m); CTR_Code GetSensorVelocity(int ¶m); CTR_Code GetCurrent(double ¶m); @@ -53,15 +301,15 @@ public: CTR_Code GetResetCount(int ¶m); CTR_Code GetResetFlags(int ¶m); CTR_Code GetFirmVers(int ¶m); - CTR_Code SetDemand24(int param); - CTR_Code SetLimitSwitchEn(int param); - CTR_Code SetSelectlFeedbackDevice(int param); + CTR_Code SetDemand(int param); + CTR_Code SetOverrideLimitSwitchEn(int param); + CTR_Code SetFeedbackDeviceSelect(int param); CTR_Code SetRevMotDuringCloseLoopEn(int param); - CTR_Code SetBrakeType(int param); + CTR_Code SetOverrideBrakeType(int param); CTR_Code SetModeSelect(int param); - CTR_Code SetCloseLoopCellSelect(int param); + CTR_Code SetProfileSlotSelect(int param); CTR_Code SetRampThrottle(int param); - CTR_Code SetRevEncoderPosAndVel(int param); + CTR_Code SetRevFeedbackSensor(int param); }; #endif diff --git a/hal/lib/Athena/ctre/ctre.h b/hal/lib/Athena/ctre/ctre.h index 49dc2f6cf3..c2d3f69614 100644 --- a/hal/lib/Athena/ctre/ctre.h +++ b/hal/lib/Athena/ctre/ctre.h @@ -38,23 +38,13 @@ typedef unsigned int UINT; typedef unsigned long ULONG; typedef enum { - CTR_OKAY, //No Error - Function executed as expected - CTR_RxTimeout, /* - * Receive Timeout - * - * No module-specific CAN frames have been received in - * the last 50ms. Function returns the latest received data - * but may be STALE DATA. - */ - CTR_TxTimeout, /* - * Transmission Timeout - * - * No module-specific CAN frames were transmitted in - * the last 50ms. Parameters passed in by the user are loaded - * for next transmission but have not sent. - */ - CTR_InvalidParamValue, - CTR_UnexpectedArbId, + CTR_OKAY, //!< No Error - Function executed as expected + CTR_RxTimeout, //!< CAN frame has not been received within specified period of time. + CTR_TxTimeout, //!< Not used. + CTR_InvalidParamValue, //!< Caller passed an invalid param + CTR_UnexpectedArbId, //!< Specified CAN Id is invalid. + CTR_TxFailed, //!< Could not transmit the CAN frame. + CTR_SigNotUpdated, //!< Have not received an value response for signal. }CTR_Code; #endif diff --git a/wpilibc/wpilibC++Devices/include/CANTalon.h b/wpilibc/wpilibC++Devices/include/CANTalon.h index 623aa6cdc9..931fa552c9 100644 --- a/wpilibc/wpilibC++Devices/include/CANTalon.h +++ b/wpilibc/wpilibC++Devices/include/CANTalon.h @@ -86,6 +86,7 @@ private: int m_deviceNumber; CanTalonSRX *m_impl; MotorSafetyHelper *m_safetyHelper; + int m_profile; // Profile from CANTalon to use. Set to zero until we can actually test this. bool m_controlEnabled; ControlMode m_controlMode; diff --git a/wpilibc/wpilibC++Devices/include/ctre/CanTalonSRX.h b/wpilibc/wpilibC++Devices/include/ctre/CanTalonSRX.h index 4a9bfe0c58..3c1a7378e0 100644 --- a/wpilibc/wpilibC++Devices/include/ctre/CanTalonSRX.h +++ b/wpilibc/wpilibC++Devices/include/ctre/CanTalonSRX.h @@ -1,4 +1,72 @@ /** + * @brief CAN TALON SRX driver. + * + * The TALON SRX is designed to instrument all runtime signals periodically. The default periods are chosen to support 16 TALONs + * with 10ms update rate for control (throttle or setpoint). However these can be overridden with SetStatusFrameRate. @see SetStatusFrameRate + * The getters for these unsolicited signals are auto generated at the bottom of this module. + * + * Likewise most control signals are sent periodically using the fire-and-forget CAN API. + * The setters for these unsolicited signals are auto generated at the bottom of this module. + * + * Signals that are not available in an unsolicited fashion are the Close Loop gains. + * For teams that have a single profile for their TALON close loop they can use either the webpage to configure their TALONs once + * or set the PIDF,Izone,CloseLoopRampRate,etc... once in the robot application. These parameters are saved to flash so once they are + * loaded in the TALON, they will persist through power cycles and mode changes. + * + * For teams that have one or two profiles to switch between, they can use the same strategy since there are two slots to choose from + * and the ProfileSlotSelect is periodically sent in the 10 ms control frame. + * + * For teams that require changing gains frequently, they can use the soliciting API to get and set those parameters. Most likely + * they will only need to set them in a periodic fashion as a function of what motion the application is attempting. + * If this API is used, be mindful of the CAN utilization reported in the driver station. + * + * Encoder position is measured in encoder edges. Every edge is counted (similar to roboRIO 4X mode). + * Analog position is 10 bits, meaning 1024 ticks per rotation (0V => 3.3V). + * Use SetFeedbackDeviceSelect to select which sensor type you need. Once you do that you can use GetSensorPosition() + * and GetSensorVelocity(). These signals are updated on CANBus every 20ms (by default). + * If a relative sensor is selected, you can zero (or change the current value) using SetSensorPosition. + * + * Analog Input and quadrature position (and velocity) are also explicitly reported in GetEncPosition, GetEncVel, GetAnalogInWithOv, GetAnalogInVel. + * These signals are available all the time, regardless of what sensor is selected at a rate of 100ms. This allows easy instrumentation + * for "in the pits" checking of all sensors regardless of modeselect. The 100ms rate is overridable for teams who want to acquire sensor + * data for processing, not just instrumentation. Or just select the sensor using SetFeedbackDeviceSelect to get it at 20ms. + * + * Velocity is in position ticks / 100ms. + * + * All output units are in respect to duty cycle (throttle) which is -1023(full reverse) to +1023 (full forward). + * This includes demand (which specifies duty cycle when in duty cycle mode) and rampRamp, which is in throttle units per 1ms (if nonzero). + * + * Pos and velocity close loops are calc'd as + * err = target - posOrVel. + * iErr += err; + * if( (IZone!=0) and abs(err) > IZone) + * ClearIaccum() + * output = P X err + I X iErr + D X dErr + F X target + * dErr = err - lastErr + * P, I,and D gains are always positive. F can be negative. + * Motor direction can be reversed using SetRevMotDuringCloseLoopEn if sensor and motor are out of phase. + * Similarly feedback sensor can also be reversed (multiplied by -1) if you prefer the sensor to be inverted. + * + * P gain is specified in throttle per error tick. For example, a value of 102 is ~9.9% (which is 102/1023) throttle per 1 + * ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor. + * + * I gain is specified in throttle per integrated error. For example, a value of 10 equates to ~0.99% (which is 10/1023) + * for each accumulated ADC unit(10bit) or 1 quadrature encoder edge depending on selected sensor. + * Close loop and integral accumulator runs every 1ms. + * + * D gain is specified in throttle per derivative error. For example a value of 102 equates to ~9.9% (which is 102/1023) + * per change of 1 unit (ADC or encoder) per ms. + * + * I Zone is specified in the same units as sensor position (ADC units or quadrature edges). If pos/vel error is outside of + * this value, the integrated error will auto-clear... + * if( (IZone!=0) and abs(err) > IZone) + * ClearIaccum() + * ...this is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low. + * + * CloseLoopRampRate ramps the target of the close loop. The units are in position per 1ms. Set to zero to disable ramping. + * So a value of 10 means allow the target input of the close loop to approach the user's demand by 10 units (ADC or encoder edges) + * per 1ms. + * * auto generated using spreadsheet and WpiClassGen.csproj * @link https://docs.google.com/spreadsheets/d/1OU_ZV7fZLGYUQ-Uhc8sVAmUmWTlT8XBFYK8lfjg_tac/edit#gid=1766046967 */ @@ -7,14 +75,195 @@ #include "ctre.h" //BIT Defines + Typedefs #include "CtreCanNode.h" #include //CAN Comm +#include class CanTalonSRX : public CtreCanNode { +private: + + /** just in case user wants to modify periods of certain status frames. + * Default the vars to match the firmware default. */ + uint32_t _statusRateMs[4]; + //---------------------- Vars for opening a CAN stream if caller needs signals that require soliciting */ + uint32_t _can_h; //!< Session handle for catching response params. + int32_t _can_stat; //!< Session handle status. + struct tCANStreamMessage _msgBuff[20]; + static int const kMsgCapacity = 20; + typedef std::map sigs_t; + sigs_t _sigs; //!< Catches signal updates that are solicited. Expect this to be very few. + void OpenSessionIfNeedBe(); + void ProcessStreamMessages(); + /** + * Send a one shot frame to set an arbitrary signal. + * Most signals are in the control frame so avoid using this API unless you have to. + * Use this api for... + * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically. + * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame. + * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms. + */ + CTR_Code SetParamRaw(uint32_t paramEnum, int32_t rawBits); + /** + * Checks cached CAN frames and updating solicited signals. + */ + CTR_Code GetParamResponseRaw(uint32_t paramEnum, int32_t & rawBits); public: CanTalonSRX(int deviceNumber=0); ~CanTalonSRX(); void Set(double value); - - /*------------------------ auto generated ----------------------*/ + /* mode select enumerations */ + static const int kMode_DutyCycle = 0; //!< Demand is 11bit signed duty cycle [-1023,1023]. + static const int kMode_PositionCloseLoop = 1; //!< Position PIDF. + static const int kMode_VelocityCloseLoop = 2; //!< Velocity PIDF. + static const int kMode_CurrentCloseLoop = 3; //!< Current close loop - not done. + static const int kMode_VoltCompen = 4; //!< Voltage Compensation Mode - not done. Demand is fixed pt target 8.8 volts. + static const int kMode_SlaveFollower = 5; //!< Demand is the 6 bit Device ID of the 'master' TALON SRX. + static const int kMode_NoDrive = 15; //!< Zero the output (honors brake/coast) regardless of demand. Might be useful if we need to change modes but can't atomically change all the signals we want in between. + /* limit switch enumerations */ + static const int kLimitSwitchOverride_UseDefaultsFromFlash = 1; + static const int kLimitSwitchOverride_DisableFwd_DisableRev = 4; + static const int kLimitSwitchOverride_DisableFwd_EnableRev = 5; + static const int kLimitSwitchOverride_EnableFwd_DisableRev = 6; + static const int kLimitSwitchOverride_EnableFwd_EnableRev = 7; + /* brake override enumerations */ + static const int kBrakeOverride_UseDefaultsFromFlash = 0; + static const int kBrakeOverride_OverrideCoast = 1; + static const int kBrakeOverride_OverrideBrake = 2; + /* feedback device enumerations */ + static const int kFeedbackDev_DigitalQuadEnc=0; + static const int kFeedbackDev_AnalogPot=2; + static const int kFeedbackDev_AnalogEncoder=3; + static const int kFeedbackDev_CountEveryRisingEdge=4; + static const int kFeedbackDev_CountEveryFallingEdge=5; + static const int kFeedbackDev_PosIsPulseWidth=8; + /* ProfileSlotSelect enumerations*/ + static const int kProfileSlotSelect_Slot0 = 0; + static const int kProfileSlotSelect_Slot1 = 1; + /* status frame rate types */ + static const int kStatusFrame_General = 0; + static const int kStatusFrame_Feedback = 1; + static const int kStatusFrame_Encoder = 2; + static const int kStatusFrame_AnalogTempVbat = 3; + /** + * Signal enumeration for generic signal access. + * Although every signal is enumerated, only use this for traffic that must be solicited. + * Use the auto generated getters/setters at bottom of this header as much as possible. + */ + typedef enum _param_t{ + eProfileParamSlot0_P=1, + eProfileParamSlot0_I=2, + eProfileParamSlot0_D=3, + eProfileParamSlot0_F=4, + eProfileParamSlot0_IZone=5, + eProfileParamSlot0_CloseLoopRampRate=6, + eProfileParamSlot1_P=11, + eProfileParamSlot1_I=12, + eProfileParamSlot1_D=13, + eProfileParamSlot1_F=14, + eProfileParamSlot1_IZone=15, + eProfileParamSlot1_CloseLoopRampRate=16, + eProfileParamSoftLimitForThreshold=21, + eProfileParamSoftLimitRevThreshold=22, + eProfileParamSoftLimitForEnable=23, + eProfileParamSoftLimitRevEnable=24, + eOnBoot_BrakeMode=31, + eOnBoot_LimitSwitch_Forward_NormallyClosed=32, + eOnBoot_LimitSwitch_Reverse_NormallyClosed=33, + eOnBoot_LimitSwitch_Forward_Disable=34, + eOnBoot_LimitSwitch_Reverse_Disable=35, + eFault_OverTemp=41, + eFault_UnderVoltage=42, + eFault_ForLim=43, + eFault_RevLim=44, + eFault_HardwareFailure=45, + eFault_ForSoftLim=46, + eFault_RevSoftLim=47, + eStckyFault_OverTemp=48, + eStckyFault_UnderVoltage=49, + eStckyFault_ForLim=50, + eStckyFault_RevLim=51, + eStckyFault_ForSoftLim=52, + eStckyFault_RevSoftLim=53, + eAppliedThrottle=61, + eCloseLoopErr=62, + eFeedbackDeviceSelect=63, + eRevMotDuringCloseLoopEn=64, + eModeSelect=65, + eProfileSlotSelect=66, + eRampThrottle=67, + eRevFeedbackSensor=68, + eLimitSwitchEn=69, + eLimitSwitchClosedFor=70, + eLimitSwitchClosedRev=71, + eSensorPosition=73, + eSensorVelocity=74, + eCurrent=75, + eBrakeIsEnabled=76, + eEncPosition=77, + eEncVel=78, + eEncIndexRiseEvents=79, + eQuadApin=80, + eQuadBpin=81, + eQuadIdxpin=82, + eAnalogInWithOv=83, + eAnalogInVel=84, + eTemp=85, + eBatteryV=86, + eResetCount=87, + eResetFlags=88, + eFirmVers=89, + eSettingsChanged=90, + }param_t; + /*---------------------setters and getters that use the solicated param request/response-------------*//** + * Send a one shot frame to set an arbitrary signal. + * Most signals are in the control frame so avoid using this API unless you have to. + * Use this api for... + * -A motor controller profile signal eProfileParam_XXXs. These are backed up in flash. If you are gain-scheduling then call this periodically. + * -Default brake and limit switch signals... eOnBoot_XXXs. Avoid doing this, use the override signals in the control frame. + * Talon will automatically send a PARAM_RESPONSE after the set, so GetParamResponse will catch the latest value after a couple ms. + */ + CTR_Code SetParam(param_t paramEnum, double value); + /** + * Asks TALON to immedietely respond with signal value. This API is only used for signals that are not sent periodically. + * This can be useful for reading params that rarely change like Limit Switch settings and PIDF values. + * @param param to request. + */ + CTR_Code RequestParam(param_t paramEnum); + CTR_Code GetParamResponse(param_t paramEnum, double & value); + CTR_Code GetParamResponseInt32(param_t paramEnum, int32_t & value); + /*----- getters and setters that use param request/response. These signals are backed up in flash and will survive a power cycle. ---------*/ + /*----- If your application requires changing these values consider using both slots and switch between slot0 <=> slot1. ------------------*/ + /*----- If your application requires changing these signals frequently then it makes sense to leverage this API. --------------------------*/ + /*----- Getters don't block, so it may require several calls to get the latest value. --------------------------*/ + CTR_Code SetPgain(uint32_t slotIdx,double gain); + CTR_Code SetIgain(uint32_t slotIdx,double gain); + CTR_Code SetDgain(uint32_t slotIdx,double gain); + CTR_Code SetFgain(uint32_t slotIdx,double gain); + CTR_Code SetIzone(uint32_t slotIdx,int32_t zone); + CTR_Code SetCloseLoopRampRate(uint32_t slotIdx,int32_t closeLoopRampRate); + CTR_Code SetSensorPosition(int32_t pos); + CTR_Code SetForwardSoftLimit(int32_t forwardLimit); + CTR_Code SetReverseSoftLimit(int32_t reverseLimit); + CTR_Code SetForwardSoftEnable(int32_t enable); + CTR_Code SetReverseSoftEnable(int32_t enable); + CTR_Code GetPgain(uint32_t slotIdx,double & gain); + CTR_Code GetIgain(uint32_t slotIdx,double & gain); + CTR_Code GetDgain(uint32_t slotIdx,double & gain); + CTR_Code GetFgain(uint32_t slotIdx,double & gain); + CTR_Code GetIzone(uint32_t slotIdx,int32_t & zone); + CTR_Code GetCloseLoopRampRate(uint32_t slotIdx,int32_t & closeLoopRampRate); + CTR_Code GetForwardSoftLimit(int32_t & forwardLimit); + CTR_Code GetReverseSoftLimit(int32_t & reverseLimit); + CTR_Code GetForwardSoftEnable(int32_t & enable); + CTR_Code GetReverseSoftEnable(int32_t & enable); + /** + * Change the periodMs of a TALON's status frame. See kStatusFrame_* enums for what's available. + */ + CTR_Code SetStatusFrameRate(uint32_t frameEnum, uint8_t periodMs); + /** + * Clear all sticky faults in TALON. + */ + CTR_Code ClearStickyFaults(); + /*------------------------ auto generated. This API is optimal since it uses the fire-and-forget CAN interface ----------------------*/ + /*------------------------ These signals should cover the majority of all use cases. ----------------------------------*/ CTR_Code GetFault_OverTemp(int ¶m); CTR_Code GetFault_UnderVoltage(int ¶m); CTR_Code GetFault_ForLim(int ¶m); @@ -28,14 +277,13 @@ public: CTR_Code GetStckyFault_RevLim(int ¶m); CTR_Code GetStckyFault_ForSoftLim(int ¶m); CTR_Code GetStckyFault_RevSoftLim(int ¶m); - CTR_Code GetAppliedThrottle11(int ¶m); + CTR_Code GetAppliedThrottle(int ¶m); CTR_Code GetCloseLoopErr(int ¶m); - CTR_Code GetSelectlFeedbackDevice(int ¶m); + CTR_Code GetFeedbackDeviceSelect(int ¶m); CTR_Code GetModeSelect(int ¶m); CTR_Code GetLimitSwitchEn(int ¶m); CTR_Code GetLimitSwitchClosedFor(int ¶m); CTR_Code GetLimitSwitchClosedRev(int ¶m); - CTR_Code GetCloseLoopCellSelect(int ¶m); CTR_Code GetSensorPosition(int ¶m); CTR_Code GetSensorVelocity(int ¶m); CTR_Code GetCurrent(double ¶m); @@ -53,15 +301,15 @@ public: CTR_Code GetResetCount(int ¶m); CTR_Code GetResetFlags(int ¶m); CTR_Code GetFirmVers(int ¶m); - CTR_Code SetDemand24(int param); - CTR_Code SetLimitSwitchEn(int param); - CTR_Code SetSelectlFeedbackDevice(int param); + CTR_Code SetDemand(int param); + CTR_Code SetOverrideLimitSwitchEn(int param); + CTR_Code SetFeedbackDeviceSelect(int param); CTR_Code SetRevMotDuringCloseLoopEn(int param); - CTR_Code SetBrakeType(int param); + CTR_Code SetOverrideBrakeType(int param); CTR_Code SetModeSelect(int param); - CTR_Code SetCloseLoopCellSelect(int param); + CTR_Code SetProfileSlotSelect(int param); CTR_Code SetRampThrottle(int param); - CTR_Code SetRevEncoderPosAndVel(int param); + CTR_Code SetRevFeedbackSensor(int param); }; #endif diff --git a/wpilibc/wpilibC++Devices/include/ctre/ctre.h b/wpilibc/wpilibC++Devices/include/ctre/ctre.h index 49dc2f6cf3..c2d3f69614 100644 --- a/wpilibc/wpilibC++Devices/include/ctre/ctre.h +++ b/wpilibc/wpilibC++Devices/include/ctre/ctre.h @@ -38,23 +38,13 @@ typedef unsigned int UINT; typedef unsigned long ULONG; typedef enum { - CTR_OKAY, //No Error - Function executed as expected - CTR_RxTimeout, /* - * Receive Timeout - * - * No module-specific CAN frames have been received in - * the last 50ms. Function returns the latest received data - * but may be STALE DATA. - */ - CTR_TxTimeout, /* - * Transmission Timeout - * - * No module-specific CAN frames were transmitted in - * the last 50ms. Parameters passed in by the user are loaded - * for next transmission but have not sent. - */ - CTR_InvalidParamValue, - CTR_UnexpectedArbId, + CTR_OKAY, //!< No Error - Function executed as expected + CTR_RxTimeout, //!< CAN frame has not been received within specified period of time. + CTR_TxTimeout, //!< Not used. + CTR_InvalidParamValue, //!< Caller passed an invalid param + CTR_UnexpectedArbId, //!< Specified CAN Id is invalid. + CTR_TxFailed, //!< Could not transmit the CAN frame. + CTR_SigNotUpdated, //!< Have not received an value response for signal. }CTR_Code; #endif diff --git a/wpilibc/wpilibC++Devices/src/CANTalon.cpp b/wpilibc/wpilibC++Devices/src/CANTalon.cpp index ae002cc010..23095ed8e2 100644 --- a/wpilibc/wpilibC++Devices/src/CANTalon.cpp +++ b/wpilibc/wpilibC++Devices/src/CANTalon.cpp @@ -24,11 +24,9 @@ CANTalon::CANTalon(int deviceNumber) , m_safetyHelper(new MotorSafetyHelper(this)) , m_controlEnabled(false) { - // The control mode may already have been set. - CTR_Code status = m_impl->SetModeSelect((int)m_controlMode); - if(status != CTR_OKAY) { - wpi_setErrorWithContext(status, getHALErrorMessage(status)); - } + // The control mode may already have been set; GetControlMode will reset + // m_controlMode to match the Talon. + GetControlMode(); } CANTalon::~CANTalon() { @@ -60,6 +58,24 @@ void CANTalon::PIDWrite(float output) */ float CANTalon::Get() { + int value; + switch(m_controlMode) { + case kPercentVbus: + m_impl->GetAppliedThrottle(value); + return 1.0 - (float)value / 1023.0; + case kVoltage: + return GetOutputVoltage(); + case kCurrent: + return GetOutputCurrent(); + case kSpeed: + m_impl->GetSensorVelocity(value); + return value; + case kPosition: + m_impl->GetSensorPosition(value); + return value; + default: + break; + } return 0.0f; } @@ -79,18 +95,18 @@ void CANTalon::Set(float value, uint8_t syncGroup) break; case kFollowerMode: { - status = m_impl->SetDemand24((int)value); + status = m_impl->SetDemand((int)value); } break; case kVoltageMode: { // Voltage is an 8.8 fixed point number. int volts = int(value * 256); - status = m_impl->SetDemand24(volts); + status = m_impl->SetDemand(volts); } default: // TODO: Add support for other modes. Need to figure out what format - // SetDemand24 needs. + // SetDemand needs. break; } if (status != CTR_OKAY) { @@ -105,8 +121,8 @@ void CANTalon::Set(float value, uint8_t syncGroup) void CANTalon::Disable() { // Until Modes other than throttle work, just disable by setting throttle to 0.0. - m_impl->Set(0.0); // TODO when firmware is updated, remove this. - //m_impl->SetModeSelect(kDisabled); // TODO when firmware is updated, uncomment this. + //m_impl->Set(0.0); // TODO when firmware is updated, remove this. + m_impl->SetModeSelect(kDisabled); // TODO when firmware is updated, uncomment this. m_controlEnabled = false; } @@ -119,11 +135,14 @@ void CANTalon::EnableControl() { } /** - * TODO documentation (see CANJaguar.cpp) + * @param */ void CANTalon::SetP(double p) { - // TODO + CTR_Code status = m_impl->SetPgain(m_profile, p); + if(status != CTR_OKAY) { + wpi_setErrorWithContext(status, getHALErrorMessage(status)); + } } /** @@ -131,7 +150,10 @@ void CANTalon::SetP(double p) */ void CANTalon::SetI(double i) { - // TODO + CTR_Code status = m_impl->SetIgain(m_profile, i); + if(status != CTR_OKAY) { + wpi_setErrorWithContext(status, getHALErrorMessage(status)); + } } /** @@ -139,7 +161,10 @@ void CANTalon::SetI(double i) */ void CANTalon::SetD(double d) { - // TODO + CTR_Code status = m_impl->SetDgain(m_profile, d); + if(status != CTR_OKAY) { + wpi_setErrorWithContext(status, getHALErrorMessage(status)); + } } /** @@ -157,8 +182,12 @@ void CANTalon::SetPID(double p, double i, double d) */ double CANTalon::GetP() { - // TODO - return 0.0; + double p; + CTR_Code status = m_impl->GetPgain(m_profile, p); + if(status != CTR_OKAY) { + wpi_setErrorWithContext(status, getHALErrorMessage(status)); + } + return p; } /** @@ -166,8 +195,12 @@ double CANTalon::GetP() */ double CANTalon::GetI() { - // TODO - return 0.0; + double i; + CTR_Code status = m_impl->GetIgain(m_profile, i); + if(status != CTR_OKAY) { + wpi_setErrorWithContext(status, getHALErrorMessage(status)); + } + return i; } /** @@ -175,8 +208,12 @@ double CANTalon::GetI() */ double CANTalon::GetD() { - // TODO - return 0.0; + double d; + CTR_Code status = m_impl->GetDgain(m_profile, d); + if(status != CTR_OKAY) { + wpi_setErrorWithContext(status, getHALErrorMessage(status)); + } + return d; } /** @@ -200,8 +237,8 @@ float CANTalon::GetBusVoltage() float CANTalon::GetOutputVoltage() { int throttle11; - CTR_Code status = m_impl->GetAppliedThrottle11(throttle11); - float voltage = GetBusVoltage() * float(throttle11) / 1023.0; + CTR_Code status = m_impl->GetAppliedThrottle(throttle11); + float voltage = GetBusVoltage() * (float(throttle11) / 1023.0 - 1.0); if(status != CTR_OKAY) { wpi_setErrorWithContext(status, getHALErrorMessage(status)); } diff --git a/wpilibc/wpilibC++IntegrationTests/src/CANTalonTest.cpp b/wpilibc/wpilibC++IntegrationTests/src/CANTalonTest.cpp index 57b9054822..1513d23c73 100644 --- a/wpilibc/wpilibC++IntegrationTests/src/CANTalonTest.cpp +++ b/wpilibc/wpilibC++IntegrationTests/src/CANTalonTest.cpp @@ -8,14 +8,52 @@ #include "gtest/gtest.h" #include "TestBench.h" +const int deviceId = 0; + TEST(CANTalonTest, QuickTest) { - CANTalon talon(0); + CANTalon talon(deviceId); talon.SetControlMode(CANSpeedController::kPercentVbus); talon.EnableControl(); - talon.Set(1.0); + talon.Set(0.5); Wait(0.25); - EXPECT_GT(talon.GetOutputCurrent(), 0.0); + EXPECT_NEAR(talon.Get(), 0.5, 5e-3); + talon.Set(-0.5); + Wait(0.25); + EXPECT_NEAR(talon.Get(), -0.5, 5e-3); - talon.Set(0.0); talon.Disable(); } + +TEST(CANTalonTest, SetGetPID) { + // Tests that we can actually set and get PID values as intended. + CANTalon talon(deviceId); + double p = 0.05, i = 0.098, d = 1.23; + talon.SetPID(p, i , d); + Wait(0.1); + EXPECT_NEAR(p, talon.GetP(), 1e-5); + EXPECT_NEAR(i, talon.GetI(), 1e-5); + EXPECT_NEAR(d, talon.GetD(), 1e-5); + // Test with new values in case the talon was already set to the previous ones. + p = 0.15; + i = 0.198; + d = 1.03; + talon.SetPID(p, i , d); + Wait(0.1); + EXPECT_NEAR(p, talon.GetP(), 1e-5); + EXPECT_NEAR(i, talon.GetI(), 1e-5); + EXPECT_NEAR(d, talon.GetD(), 1e-5); +} + +TEST(CANTalonTest, DISABLED_PositionModeWorks) { + CANTalon talon(deviceId); + double p = 1; + double i = 0.05; + double d = 0.01; + talon.SetPID(p, i, d); + talon.SetControlMode(CANSpeedController::kPosition); + talon.Set(1000); + talon.EnableControl(); + Wait(10.0); + talon.Disable(); + EXPECT_NEAR(talon.Get(), 1000, 100); +} diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CANTalon.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CANTalon.java new file mode 100644 index 0000000000..3e9b037907 --- /dev/null +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CANTalon.java @@ -0,0 +1,135 @@ +/* ---------------------------------------------------------------------------- + * This file was automatically generated by SWIG (http://www.swig.org). + * Version 2.0.11 + * + * Do not make changes to this file unless you know what you are doing--modify + * the SWIG interface file instead. + * ----------------------------------------------------------------------------- */ + +package edu.wpi.first.wpilibj; + +import edu.wpi.first.wpilibj.hal.CanTalonSRX; +import edu.wpi.first.wpilibj.hal.CanTalonJNI; +import edu.wpi.first.wpilibj.hal.SWIGTYPE_p_double; + +public class CANTalon implements MotorSafety, PIDOutput, SpeedController { + private MotorSafetyHelper m_safetyHelper; + public enum ControlMode { + PercentVbus(0), Follower(1), Voltage(2), Position(3), Speed(4), Current(5), Disabled(15); + + public int value; + + public static ControlMode valueOf(int value) { + for(ControlMode mode : values()) { + if(mode.value == value) { + return mode; + } + } + + return null; + } + + private ControlMode(int value) { + this.value = value; + } + } + + private CanTalonSRX m_impl; + + int m_deviceNumber; + boolean m_controlEnabled; + + public CANTalon(int deviceNumber) { + m_deviceNumber = deviceNumber; + m_impl = new CanTalonSRX(deviceNumber); + m_safetyHelper = new MotorSafetyHelper(this); + m_controlEnabled = false; + } + + @Override + public void pidWrite(double output) { + set(output); + } + + public void set(double outputValue) { + m_impl.Set(outputValue); + } + + @Override + public void set(double outputValue, byte thisValueDoesNotDoAnything) { + set(outputValue); + } + + public double get() { + // TODO + return 0.0f; + } + + // Returns temperature of Talon, in degrees Celsius. + public double getTemp() { + long tempp = CanTalonJNI.new_doublep(); // Create a new swig pointer. + m_impl.GetTemp(new SWIGTYPE_p_double(tempp, true)); + return CanTalonJNI.doublep_value(tempp); + } + + // Only supports kPercentVbus mode for now. + public void enableControl() { + m_impl.SetModeSelect(ControlMode.PercentVbus.value); + m_controlEnabled = true; + } + + public void disableControl() { + m_impl.SetModeSelect(ControlMode.Disabled.value); + m_controlEnabled = false; + } + + /** + * Common interface for stopping a motor. + * + * @deprecated Use disableControl instead. + */ + @Override + @Deprecated + public void stopMotor() { + disableControl(); + } + + @Override + public void disable() { + disableControl(); + } + + public int getDeviceID() { + return m_deviceNumber; + } + + @Override + public void setExpiration(double timeout) { + m_safetyHelper.setExpiration(timeout); + } + + @Override + public double getExpiration() { + return m_safetyHelper.getExpiration(); + } + + @Override + public boolean isAlive() { + return m_safetyHelper.isAlive(); + } + + @Override + public boolean isSafetyEnabled() { + return m_safetyHelper.isSafetyEnabled(); + } + + @Override + public void setSafetyEnabled(boolean enabled) { + m_safetyHelper.setSafetyEnabled(enabled); + } + + @Override + public String getDescription() { + return "CANJaguar ID "+m_deviceNumber; + } +} diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CanTalonSRX.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CanTalonSRX.java index c1c81293c1..2cbb12da25 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CanTalonSRX.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CanTalonSRX.java @@ -47,6 +47,114 @@ public class CanTalonSRX extends CtreCanNode { CanTalonJNI.CanTalonSRX_Set(swigCPtr, this, value); } + public SWIGTYPE_p_CTR_Code SetParam(CanTalonSRX.param_t paramEnum, double value) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetParam(swigCPtr, this, paramEnum.swigValue(), value), true); + } + + public SWIGTYPE_p_CTR_Code RequestParam(CanTalonSRX.param_t paramEnum) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_RequestParam(swigCPtr, this, paramEnum.swigValue()), true); + } + + public SWIGTYPE_p_CTR_Code GetParamResponse(CanTalonSRX.param_t paramEnum, SWIGTYPE_p_double value) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetParamResponse(swigCPtr, this, paramEnum.swigValue(), SWIGTYPE_p_double.getCPtr(value)), true); + } + + public SWIGTYPE_p_CTR_Code GetParamResponseInt32(CanTalonSRX.param_t paramEnum, SWIGTYPE_p_int32_t value) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetParamResponseInt32(swigCPtr, this, paramEnum.swigValue(), SWIGTYPE_p_int32_t.getCPtr(value)), true); + } + + public SWIGTYPE_p_CTR_Code SetPgain(SWIGTYPE_p_uint32_t slotIdx, double gain) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetPgain(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), gain), true); + } + + public SWIGTYPE_p_CTR_Code SetIgain(SWIGTYPE_p_uint32_t slotIdx, double gain) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetIgain(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), gain), true); + } + + public SWIGTYPE_p_CTR_Code SetDgain(SWIGTYPE_p_uint32_t slotIdx, double gain) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetDgain(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), gain), true); + } + + public SWIGTYPE_p_CTR_Code SetFgain(SWIGTYPE_p_uint32_t slotIdx, double gain) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetFgain(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), gain), true); + } + + public SWIGTYPE_p_CTR_Code SetIzone(SWIGTYPE_p_uint32_t slotIdx, SWIGTYPE_p_int32_t zone) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetIzone(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), SWIGTYPE_p_int32_t.getCPtr(zone)), true); + } + + public SWIGTYPE_p_CTR_Code SetCloseLoopRampRate(SWIGTYPE_p_uint32_t slotIdx, SWIGTYPE_p_int32_t closeLoopRampRate) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetCloseLoopRampRate(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), SWIGTYPE_p_int32_t.getCPtr(closeLoopRampRate)), true); + } + + public SWIGTYPE_p_CTR_Code SetSensorPosition(SWIGTYPE_p_int32_t pos) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetSensorPosition(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(pos)), true); + } + + public SWIGTYPE_p_CTR_Code SetForwardSoftLimit(SWIGTYPE_p_int32_t forwardLimit) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetForwardSoftLimit(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(forwardLimit)), true); + } + + public SWIGTYPE_p_CTR_Code SetReverseSoftLimit(SWIGTYPE_p_int32_t reverseLimit) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetReverseSoftLimit(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(reverseLimit)), true); + } + + public SWIGTYPE_p_CTR_Code SetForwardSoftEnable(SWIGTYPE_p_int32_t enable) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetForwardSoftEnable(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(enable)), true); + } + + public SWIGTYPE_p_CTR_Code SetReverseSoftEnable(SWIGTYPE_p_int32_t enable) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetReverseSoftEnable(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(enable)), true); + } + + public SWIGTYPE_p_CTR_Code GetPgain(SWIGTYPE_p_uint32_t slotIdx, SWIGTYPE_p_double gain) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetPgain(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), SWIGTYPE_p_double.getCPtr(gain)), true); + } + + public SWIGTYPE_p_CTR_Code GetIgain(SWIGTYPE_p_uint32_t slotIdx, SWIGTYPE_p_double gain) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetIgain(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), SWIGTYPE_p_double.getCPtr(gain)), true); + } + + public SWIGTYPE_p_CTR_Code GetDgain(SWIGTYPE_p_uint32_t slotIdx, SWIGTYPE_p_double gain) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetDgain(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), SWIGTYPE_p_double.getCPtr(gain)), true); + } + + public SWIGTYPE_p_CTR_Code GetFgain(SWIGTYPE_p_uint32_t slotIdx, SWIGTYPE_p_double gain) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetFgain(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), SWIGTYPE_p_double.getCPtr(gain)), true); + } + + public SWIGTYPE_p_CTR_Code GetIzone(SWIGTYPE_p_uint32_t slotIdx, SWIGTYPE_p_int32_t zone) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetIzone(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), SWIGTYPE_p_int32_t.getCPtr(zone)), true); + } + + public SWIGTYPE_p_CTR_Code GetCloseLoopRampRate(SWIGTYPE_p_uint32_t slotIdx, SWIGTYPE_p_int32_t closeLoopRampRate) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetCloseLoopRampRate(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(slotIdx), SWIGTYPE_p_int32_t.getCPtr(closeLoopRampRate)), true); + } + + public SWIGTYPE_p_CTR_Code GetForwardSoftLimit(SWIGTYPE_p_int32_t forwardLimit) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetForwardSoftLimit(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(forwardLimit)), true); + } + + public SWIGTYPE_p_CTR_Code GetReverseSoftLimit(SWIGTYPE_p_int32_t reverseLimit) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetReverseSoftLimit(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(reverseLimit)), true); + } + + public SWIGTYPE_p_CTR_Code GetForwardSoftEnable(SWIGTYPE_p_int32_t enable) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetForwardSoftEnable(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(enable)), true); + } + + public SWIGTYPE_p_CTR_Code GetReverseSoftEnable(SWIGTYPE_p_int32_t enable) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetReverseSoftEnable(swigCPtr, this, SWIGTYPE_p_int32_t.getCPtr(enable)), true); + } + + public SWIGTYPE_p_CTR_Code SetStatusFrameRate(SWIGTYPE_p_uint32_t frameEnum, SWIGTYPE_p_uint8_t periodMs) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetStatusFrameRate(swigCPtr, this, SWIGTYPE_p_uint32_t.getCPtr(frameEnum), SWIGTYPE_p_uint8_t.getCPtr(periodMs)), true); + } + + public SWIGTYPE_p_CTR_Code ClearStickyFaults() { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_ClearStickyFaults(swigCPtr, this), true); + } + public SWIGTYPE_p_CTR_Code GetFault_OverTemp(SWIGTYPE_p_int param) { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetFault_OverTemp(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); } @@ -99,16 +207,16 @@ public class CanTalonSRX extends CtreCanNode { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetStckyFault_RevSoftLim(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); } - public SWIGTYPE_p_CTR_Code GetAppliedThrottle11(SWIGTYPE_p_int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetAppliedThrottle11(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); + public SWIGTYPE_p_CTR_Code GetAppliedThrottle(SWIGTYPE_p_int param) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetAppliedThrottle(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); } public SWIGTYPE_p_CTR_Code GetCloseLoopErr(SWIGTYPE_p_int param) { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetCloseLoopErr(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); } - public SWIGTYPE_p_CTR_Code GetSelectlFeedbackDevice(SWIGTYPE_p_int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetSelectlFeedbackDevice(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); + public SWIGTYPE_p_CTR_Code GetFeedbackDeviceSelect(SWIGTYPE_p_int param) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetFeedbackDeviceSelect(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); } public SWIGTYPE_p_CTR_Code GetModeSelect(SWIGTYPE_p_int param) { @@ -127,10 +235,6 @@ public class CanTalonSRX extends CtreCanNode { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetLimitSwitchClosedRev(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); } - public SWIGTYPE_p_CTR_Code GetCloseLoopCellSelect(SWIGTYPE_p_int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetCloseLoopCellSelect(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); - } - public SWIGTYPE_p_CTR_Code GetSensorPosition(SWIGTYPE_p_int param) { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetSensorPosition(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); } @@ -199,40 +303,172 @@ public class CanTalonSRX extends CtreCanNode { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_GetFirmVers(swigCPtr, this, SWIGTYPE_p_int.getCPtr(param)), true); } - public SWIGTYPE_p_CTR_Code SetDemand24(int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetDemand24(swigCPtr, this, param), true); + public SWIGTYPE_p_CTR_Code SetDemand(int param) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetDemand(swigCPtr, this, param), true); } - public SWIGTYPE_p_CTR_Code SetLimitSwitchEn(int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetLimitSwitchEn(swigCPtr, this, param), true); + public SWIGTYPE_p_CTR_Code SetOverrideLimitSwitchEn(int param) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetOverrideLimitSwitchEn(swigCPtr, this, param), true); } - public SWIGTYPE_p_CTR_Code SetSelectlFeedbackDevice(int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetSelectlFeedbackDevice(swigCPtr, this, param), true); + public SWIGTYPE_p_CTR_Code SetFeedbackDeviceSelect(int param) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetFeedbackDeviceSelect(swigCPtr, this, param), true); } public SWIGTYPE_p_CTR_Code SetRevMotDuringCloseLoopEn(int param) { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetRevMotDuringCloseLoopEn(swigCPtr, this, param), true); } - public SWIGTYPE_p_CTR_Code SetBrakeType(int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetBrakeType(swigCPtr, this, param), true); + public SWIGTYPE_p_CTR_Code SetOverrideBrakeType(int param) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetOverrideBrakeType(swigCPtr, this, param), true); } public SWIGTYPE_p_CTR_Code SetModeSelect(int param) { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetModeSelect(swigCPtr, this, param), true); } - public SWIGTYPE_p_CTR_Code SetCloseLoopCellSelect(int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetCloseLoopCellSelect(swigCPtr, this, param), true); + public SWIGTYPE_p_CTR_Code SetProfileSlotSelect(int param) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetProfileSlotSelect(swigCPtr, this, param), true); } public SWIGTYPE_p_CTR_Code SetRampThrottle(int param) { return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetRampThrottle(swigCPtr, this, param), true); } - public SWIGTYPE_p_CTR_Code SetRevEncoderPosAndVel(int param) { - return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetRevEncoderPosAndVel(swigCPtr, this, param), true); + public SWIGTYPE_p_CTR_Code SetRevFeedbackSensor(int param) { + return new SWIGTYPE_p_CTR_Code(CanTalonJNI.CanTalonSRX_SetRevFeedbackSensor(swigCPtr, this, param), true); + } + + public final static int kMode_DutyCycle = CanTalonJNI.CanTalonSRX_kMode_DutyCycle_get(); + public final static int kMode_PositionCloseLoop = CanTalonJNI.CanTalonSRX_kMode_PositionCloseLoop_get(); + public final static int kMode_VelocityCloseLoop = CanTalonJNI.CanTalonSRX_kMode_VelocityCloseLoop_get(); + public final static int kMode_CurrentCloseLoop = CanTalonJNI.CanTalonSRX_kMode_CurrentCloseLoop_get(); + public final static int kMode_VoltCompen = CanTalonJNI.CanTalonSRX_kMode_VoltCompen_get(); + public final static int kMode_SlaveFollower = CanTalonJNI.CanTalonSRX_kMode_SlaveFollower_get(); + public final static int kMode_NoDrive = CanTalonJNI.CanTalonSRX_kMode_NoDrive_get(); + public final static int kLimitSwitchOverride_UseDefaultsFromFlash = CanTalonJNI.CanTalonSRX_kLimitSwitchOverride_UseDefaultsFromFlash_get(); + public final static int kLimitSwitchOverride_DisableFwd_DisableRev = CanTalonJNI.CanTalonSRX_kLimitSwitchOverride_DisableFwd_DisableRev_get(); + public final static int kLimitSwitchOverride_DisableFwd_EnableRev = CanTalonJNI.CanTalonSRX_kLimitSwitchOverride_DisableFwd_EnableRev_get(); + public final static int kLimitSwitchOverride_EnableFwd_DisableRev = CanTalonJNI.CanTalonSRX_kLimitSwitchOverride_EnableFwd_DisableRev_get(); + public final static int kLimitSwitchOverride_EnableFwd_EnableRev = CanTalonJNI.CanTalonSRX_kLimitSwitchOverride_EnableFwd_EnableRev_get(); + public final static int kBrakeOverride_UseDefaultsFromFlash = CanTalonJNI.CanTalonSRX_kBrakeOverride_UseDefaultsFromFlash_get(); + public final static int kBrakeOverride_OverrideCoast = CanTalonJNI.CanTalonSRX_kBrakeOverride_OverrideCoast_get(); + public final static int kBrakeOverride_OverrideBrake = CanTalonJNI.CanTalonSRX_kBrakeOverride_OverrideBrake_get(); + public final static int kFeedbackDev_DigitalQuadEnc = CanTalonJNI.CanTalonSRX_kFeedbackDev_DigitalQuadEnc_get(); + public final static int kFeedbackDev_AnalogPot = CanTalonJNI.CanTalonSRX_kFeedbackDev_AnalogPot_get(); + public final static int kFeedbackDev_AnalogEncoder = CanTalonJNI.CanTalonSRX_kFeedbackDev_AnalogEncoder_get(); + public final static int kFeedbackDev_CountEveryRisingEdge = CanTalonJNI.CanTalonSRX_kFeedbackDev_CountEveryRisingEdge_get(); + public final static int kFeedbackDev_CountEveryFallingEdge = CanTalonJNI.CanTalonSRX_kFeedbackDev_CountEveryFallingEdge_get(); + public final static int kFeedbackDev_PosIsPulseWidth = CanTalonJNI.CanTalonSRX_kFeedbackDev_PosIsPulseWidth_get(); + public final static int kProfileSlotSelect_Slot0 = CanTalonJNI.CanTalonSRX_kProfileSlotSelect_Slot0_get(); + public final static int kProfileSlotSelect_Slot1 = CanTalonJNI.CanTalonSRX_kProfileSlotSelect_Slot1_get(); + public final static int kStatusFrame_General = CanTalonJNI.CanTalonSRX_kStatusFrame_General_get(); + public final static int kStatusFrame_Feedback = CanTalonJNI.CanTalonSRX_kStatusFrame_Feedback_get(); + public final static int kStatusFrame_Encoder = CanTalonJNI.CanTalonSRX_kStatusFrame_Encoder_get(); + public final static int kStatusFrame_AnalogTempVbat = CanTalonJNI.CanTalonSRX_kStatusFrame_AnalogTempVbat_get(); + public final static class param_t { + public final static CanTalonSRX.param_t eProfileParamSlot0_P = new CanTalonSRX.param_t("eProfileParamSlot0_P", CanTalonJNI.CanTalonSRX_eProfileParamSlot0_P_get()); + public final static CanTalonSRX.param_t eProfileParamSlot0_I = new CanTalonSRX.param_t("eProfileParamSlot0_I", CanTalonJNI.CanTalonSRX_eProfileParamSlot0_I_get()); + public final static CanTalonSRX.param_t eProfileParamSlot0_D = new CanTalonSRX.param_t("eProfileParamSlot0_D", CanTalonJNI.CanTalonSRX_eProfileParamSlot0_D_get()); + public final static CanTalonSRX.param_t eProfileParamSlot0_F = new CanTalonSRX.param_t("eProfileParamSlot0_F", CanTalonJNI.CanTalonSRX_eProfileParamSlot0_F_get()); + public final static CanTalonSRX.param_t eProfileParamSlot0_IZone = new CanTalonSRX.param_t("eProfileParamSlot0_IZone", CanTalonJNI.CanTalonSRX_eProfileParamSlot0_IZone_get()); + public final static CanTalonSRX.param_t eProfileParamSlot0_CloseLoopRampRate = new CanTalonSRX.param_t("eProfileParamSlot0_CloseLoopRampRate", CanTalonJNI.CanTalonSRX_eProfileParamSlot0_CloseLoopRampRate_get()); + public final static CanTalonSRX.param_t eProfileParamSlot1_P = new CanTalonSRX.param_t("eProfileParamSlot1_P", CanTalonJNI.CanTalonSRX_eProfileParamSlot1_P_get()); + public final static CanTalonSRX.param_t eProfileParamSlot1_I = new CanTalonSRX.param_t("eProfileParamSlot1_I", CanTalonJNI.CanTalonSRX_eProfileParamSlot1_I_get()); + public final static CanTalonSRX.param_t eProfileParamSlot1_D = new CanTalonSRX.param_t("eProfileParamSlot1_D", CanTalonJNI.CanTalonSRX_eProfileParamSlot1_D_get()); + public final static CanTalonSRX.param_t eProfileParamSlot1_F = new CanTalonSRX.param_t("eProfileParamSlot1_F", CanTalonJNI.CanTalonSRX_eProfileParamSlot1_F_get()); + public final static CanTalonSRX.param_t eProfileParamSlot1_IZone = new CanTalonSRX.param_t("eProfileParamSlot1_IZone", CanTalonJNI.CanTalonSRX_eProfileParamSlot1_IZone_get()); + public final static CanTalonSRX.param_t eProfileParamSlot1_CloseLoopRampRate = new CanTalonSRX.param_t("eProfileParamSlot1_CloseLoopRampRate", CanTalonJNI.CanTalonSRX_eProfileParamSlot1_CloseLoopRampRate_get()); + public final static CanTalonSRX.param_t eProfileParamSoftLimitForThreshold = new CanTalonSRX.param_t("eProfileParamSoftLimitForThreshold", CanTalonJNI.CanTalonSRX_eProfileParamSoftLimitForThreshold_get()); + public final static CanTalonSRX.param_t eProfileParamSoftLimitRevThreshold = new CanTalonSRX.param_t("eProfileParamSoftLimitRevThreshold", CanTalonJNI.CanTalonSRX_eProfileParamSoftLimitRevThreshold_get()); + public final static CanTalonSRX.param_t eProfileParamSoftLimitForEnable = new CanTalonSRX.param_t("eProfileParamSoftLimitForEnable", CanTalonJNI.CanTalonSRX_eProfileParamSoftLimitForEnable_get()); + public final static CanTalonSRX.param_t eProfileParamSoftLimitRevEnable = new CanTalonSRX.param_t("eProfileParamSoftLimitRevEnable", CanTalonJNI.CanTalonSRX_eProfileParamSoftLimitRevEnable_get()); + public final static CanTalonSRX.param_t eOnBoot_BrakeMode = new CanTalonSRX.param_t("eOnBoot_BrakeMode", CanTalonJNI.CanTalonSRX_eOnBoot_BrakeMode_get()); + public final static CanTalonSRX.param_t eOnBoot_LimitSwitch_Forward_NormallyClosed = new CanTalonSRX.param_t("eOnBoot_LimitSwitch_Forward_NormallyClosed", CanTalonJNI.CanTalonSRX_eOnBoot_LimitSwitch_Forward_NormallyClosed_get()); + public final static CanTalonSRX.param_t eOnBoot_LimitSwitch_Reverse_NormallyClosed = new CanTalonSRX.param_t("eOnBoot_LimitSwitch_Reverse_NormallyClosed", CanTalonJNI.CanTalonSRX_eOnBoot_LimitSwitch_Reverse_NormallyClosed_get()); + public final static CanTalonSRX.param_t eOnBoot_LimitSwitch_Forward_Disable = new CanTalonSRX.param_t("eOnBoot_LimitSwitch_Forward_Disable", CanTalonJNI.CanTalonSRX_eOnBoot_LimitSwitch_Forward_Disable_get()); + public final static CanTalonSRX.param_t eOnBoot_LimitSwitch_Reverse_Disable = new CanTalonSRX.param_t("eOnBoot_LimitSwitch_Reverse_Disable", CanTalonJNI.CanTalonSRX_eOnBoot_LimitSwitch_Reverse_Disable_get()); + public final static CanTalonSRX.param_t eFault_OverTemp = new CanTalonSRX.param_t("eFault_OverTemp", CanTalonJNI.CanTalonSRX_eFault_OverTemp_get()); + public final static CanTalonSRX.param_t eFault_UnderVoltage = new CanTalonSRX.param_t("eFault_UnderVoltage", CanTalonJNI.CanTalonSRX_eFault_UnderVoltage_get()); + public final static CanTalonSRX.param_t eFault_ForLim = new CanTalonSRX.param_t("eFault_ForLim", CanTalonJNI.CanTalonSRX_eFault_ForLim_get()); + public final static CanTalonSRX.param_t eFault_RevLim = new CanTalonSRX.param_t("eFault_RevLim", CanTalonJNI.CanTalonSRX_eFault_RevLim_get()); + public final static CanTalonSRX.param_t eFault_HardwareFailure = new CanTalonSRX.param_t("eFault_HardwareFailure", CanTalonJNI.CanTalonSRX_eFault_HardwareFailure_get()); + public final static CanTalonSRX.param_t eFault_ForSoftLim = new CanTalonSRX.param_t("eFault_ForSoftLim", CanTalonJNI.CanTalonSRX_eFault_ForSoftLim_get()); + public final static CanTalonSRX.param_t eFault_RevSoftLim = new CanTalonSRX.param_t("eFault_RevSoftLim", CanTalonJNI.CanTalonSRX_eFault_RevSoftLim_get()); + public final static CanTalonSRX.param_t eStckyFault_OverTemp = new CanTalonSRX.param_t("eStckyFault_OverTemp", CanTalonJNI.CanTalonSRX_eStckyFault_OverTemp_get()); + public final static CanTalonSRX.param_t eStckyFault_UnderVoltage = new CanTalonSRX.param_t("eStckyFault_UnderVoltage", CanTalonJNI.CanTalonSRX_eStckyFault_UnderVoltage_get()); + public final static CanTalonSRX.param_t eStckyFault_ForLim = new CanTalonSRX.param_t("eStckyFault_ForLim", CanTalonJNI.CanTalonSRX_eStckyFault_ForLim_get()); + public final static CanTalonSRX.param_t eStckyFault_RevLim = new CanTalonSRX.param_t("eStckyFault_RevLim", CanTalonJNI.CanTalonSRX_eStckyFault_RevLim_get()); + public final static CanTalonSRX.param_t eStckyFault_ForSoftLim = new CanTalonSRX.param_t("eStckyFault_ForSoftLim", CanTalonJNI.CanTalonSRX_eStckyFault_ForSoftLim_get()); + public final static CanTalonSRX.param_t eStckyFault_RevSoftLim = new CanTalonSRX.param_t("eStckyFault_RevSoftLim", CanTalonJNI.CanTalonSRX_eStckyFault_RevSoftLim_get()); + public final static CanTalonSRX.param_t eAppliedThrottle = new CanTalonSRX.param_t("eAppliedThrottle", CanTalonJNI.CanTalonSRX_eAppliedThrottle_get()); + public final static CanTalonSRX.param_t eCloseLoopErr = new CanTalonSRX.param_t("eCloseLoopErr", CanTalonJNI.CanTalonSRX_eCloseLoopErr_get()); + public final static CanTalonSRX.param_t eFeedbackDeviceSelect = new CanTalonSRX.param_t("eFeedbackDeviceSelect", CanTalonJNI.CanTalonSRX_eFeedbackDeviceSelect_get()); + public final static CanTalonSRX.param_t eRevMotDuringCloseLoopEn = new CanTalonSRX.param_t("eRevMotDuringCloseLoopEn", CanTalonJNI.CanTalonSRX_eRevMotDuringCloseLoopEn_get()); + public final static CanTalonSRX.param_t eModeSelect = new CanTalonSRX.param_t("eModeSelect", CanTalonJNI.CanTalonSRX_eModeSelect_get()); + public final static CanTalonSRX.param_t eProfileSlotSelect = new CanTalonSRX.param_t("eProfileSlotSelect", CanTalonJNI.CanTalonSRX_eProfileSlotSelect_get()); + public final static CanTalonSRX.param_t eRampThrottle = new CanTalonSRX.param_t("eRampThrottle", CanTalonJNI.CanTalonSRX_eRampThrottle_get()); + public final static CanTalonSRX.param_t eRevFeedbackSensor = new CanTalonSRX.param_t("eRevFeedbackSensor", CanTalonJNI.CanTalonSRX_eRevFeedbackSensor_get()); + public final static CanTalonSRX.param_t eLimitSwitchEn = new CanTalonSRX.param_t("eLimitSwitchEn", CanTalonJNI.CanTalonSRX_eLimitSwitchEn_get()); + public final static CanTalonSRX.param_t eLimitSwitchClosedFor = new CanTalonSRX.param_t("eLimitSwitchClosedFor", CanTalonJNI.CanTalonSRX_eLimitSwitchClosedFor_get()); + public final static CanTalonSRX.param_t eLimitSwitchClosedRev = new CanTalonSRX.param_t("eLimitSwitchClosedRev", CanTalonJNI.CanTalonSRX_eLimitSwitchClosedRev_get()); + public final static CanTalonSRX.param_t eSensorPosition = new CanTalonSRX.param_t("eSensorPosition", CanTalonJNI.CanTalonSRX_eSensorPosition_get()); + public final static CanTalonSRX.param_t eSensorVelocity = new CanTalonSRX.param_t("eSensorVelocity", CanTalonJNI.CanTalonSRX_eSensorVelocity_get()); + public final static CanTalonSRX.param_t eCurrent = new CanTalonSRX.param_t("eCurrent", CanTalonJNI.CanTalonSRX_eCurrent_get()); + public final static CanTalonSRX.param_t eBrakeIsEnabled = new CanTalonSRX.param_t("eBrakeIsEnabled", CanTalonJNI.CanTalonSRX_eBrakeIsEnabled_get()); + public final static CanTalonSRX.param_t eEncPosition = new CanTalonSRX.param_t("eEncPosition", CanTalonJNI.CanTalonSRX_eEncPosition_get()); + public final static CanTalonSRX.param_t eEncVel = new CanTalonSRX.param_t("eEncVel", CanTalonJNI.CanTalonSRX_eEncVel_get()); + public final static CanTalonSRX.param_t eEncIndexRiseEvents = new CanTalonSRX.param_t("eEncIndexRiseEvents", CanTalonJNI.CanTalonSRX_eEncIndexRiseEvents_get()); + public final static CanTalonSRX.param_t eQuadApin = new CanTalonSRX.param_t("eQuadApin", CanTalonJNI.CanTalonSRX_eQuadApin_get()); + public final static CanTalonSRX.param_t eQuadBpin = new CanTalonSRX.param_t("eQuadBpin", CanTalonJNI.CanTalonSRX_eQuadBpin_get()); + public final static CanTalonSRX.param_t eQuadIdxpin = new CanTalonSRX.param_t("eQuadIdxpin", CanTalonJNI.CanTalonSRX_eQuadIdxpin_get()); + public final static CanTalonSRX.param_t eAnalogInWithOv = new CanTalonSRX.param_t("eAnalogInWithOv", CanTalonJNI.CanTalonSRX_eAnalogInWithOv_get()); + public final static CanTalonSRX.param_t eAnalogInVel = new CanTalonSRX.param_t("eAnalogInVel", CanTalonJNI.CanTalonSRX_eAnalogInVel_get()); + public final static CanTalonSRX.param_t eTemp = new CanTalonSRX.param_t("eTemp", CanTalonJNI.CanTalonSRX_eTemp_get()); + public final static CanTalonSRX.param_t eBatteryV = new CanTalonSRX.param_t("eBatteryV", CanTalonJNI.CanTalonSRX_eBatteryV_get()); + public final static CanTalonSRX.param_t eResetCount = new CanTalonSRX.param_t("eResetCount", CanTalonJNI.CanTalonSRX_eResetCount_get()); + public final static CanTalonSRX.param_t eResetFlags = new CanTalonSRX.param_t("eResetFlags", CanTalonJNI.CanTalonSRX_eResetFlags_get()); + public final static CanTalonSRX.param_t eFirmVers = new CanTalonSRX.param_t("eFirmVers", CanTalonJNI.CanTalonSRX_eFirmVers_get()); + public final static CanTalonSRX.param_t eSettingsChanged = new CanTalonSRX.param_t("eSettingsChanged", CanTalonJNI.CanTalonSRX_eSettingsChanged_get()); + + public final int swigValue() { + return swigValue; + } + + public String toString() { + return swigName; + } + + public static param_t swigToEnum(int swigValue) { + if (swigValue < swigValues.length && swigValue >= 0 && swigValues[swigValue].swigValue == swigValue) + return swigValues[swigValue]; + for (int i = 0; i < swigValues.length; i++) + if (swigValues[i].swigValue == swigValue) + return swigValues[i]; + throw new IllegalArgumentException("No enum " + param_t.class + " with value " + swigValue); + } + + private param_t(String swigName) { + this.swigName = swigName; + this.swigValue = swigNext++; + } + + private param_t(String swigName, int swigValue) { + this.swigName = swigName; + this.swigValue = swigValue; + swigNext = swigValue+1; + } + + private param_t(String swigName, param_t swigEnum) { + this.swigName = swigName; + this.swigValue = swigEnum.swigValue; + swigNext = this.swigValue+1; + } + + private static param_t[] swigValues = { eProfileParamSlot0_P, eProfileParamSlot0_I, eProfileParamSlot0_D, eProfileParamSlot0_F, eProfileParamSlot0_IZone, eProfileParamSlot0_CloseLoopRampRate, eProfileParamSlot1_P, eProfileParamSlot1_I, eProfileParamSlot1_D, eProfileParamSlot1_F, eProfileParamSlot1_IZone, eProfileParamSlot1_CloseLoopRampRate, eProfileParamSoftLimitForThreshold, eProfileParamSoftLimitRevThreshold, eProfileParamSoftLimitForEnable, eProfileParamSoftLimitRevEnable, eOnBoot_BrakeMode, eOnBoot_LimitSwitch_Forward_NormallyClosed, eOnBoot_LimitSwitch_Reverse_NormallyClosed, eOnBoot_LimitSwitch_Forward_Disable, eOnBoot_LimitSwitch_Reverse_Disable, eFault_OverTemp, eFault_UnderVoltage, eFault_ForLim, eFault_RevLim, eFault_HardwareFailure, eFault_ForSoftLim, eFault_RevSoftLim, eStckyFault_OverTemp, eStckyFault_UnderVoltage, eStckyFault_ForLim, eStckyFault_RevLim, eStckyFault_ForSoftLim, eStckyFault_RevSoftLim, eAppliedThrottle, eCloseLoopErr, eFeedbackDeviceSelect, eRevMotDuringCloseLoopEn, eModeSelect, eProfileSlotSelect, eRampThrottle, eRevFeedbackSensor, eLimitSwitchEn, eLimitSwitchClosedFor, eLimitSwitchClosedRev, eSensorPosition, eSensorVelocity, eCurrent, eBrakeIsEnabled, eEncPosition, eEncVel, eEncIndexRiseEvents, eQuadApin, eQuadBpin, eQuadIdxpin, eAnalogInWithOv, eAnalogInVel, eTemp, eBatteryV, eResetCount, eResetFlags, eFirmVers, eSettingsChanged }; + private static int swigNext = 0; + private final int swigValue; + private final String swigName; } } diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_CTR_Code.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_CTR_Code.java index 9246cfec27..fe9e6a8787 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_CTR_Code.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_CTR_Code.java @@ -11,15 +11,15 @@ package edu.wpi.first.wpilibj.hal; public class SWIGTYPE_p_CTR_Code { private long swigCPtr; - protected SWIGTYPE_p_CTR_Code(long cPtr, boolean futureUse) { + public SWIGTYPE_p_CTR_Code(long cPtr, boolean futureUse) { swigCPtr = cPtr; } - protected SWIGTYPE_p_CTR_Code() { + public SWIGTYPE_p_CTR_Code() { swigCPtr = 0; } - protected static long getCPtr(SWIGTYPE_p_CTR_Code obj) { + public static long getCPtr(SWIGTYPE_p_CTR_Code obj) { return (obj == null) ? 0 : obj.swigCPtr; } } diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_UINT8.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_UINT8.java index 6a802b5623..f4873f3082 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_UINT8.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_UINT8.java @@ -15,11 +15,11 @@ public class SWIGTYPE_p_UINT8 { swigCPtr = cPtr; } - protected SWIGTYPE_p_UINT8() { + public SWIGTYPE_p_UINT8() { swigCPtr = 0; } - protected static long getCPtr(SWIGTYPE_p_UINT8 obj) { + public static long getCPtr(SWIGTYPE_p_UINT8 obj) { return (obj == null) ? 0 : obj.swigCPtr; } } diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_double.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_double.java index 0ba558ef07..04a269d4f0 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_double.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_double.java @@ -11,15 +11,15 @@ package edu.wpi.first.wpilibj.hal; public class SWIGTYPE_p_double { private long swigCPtr; - protected SWIGTYPE_p_double(long cPtr, boolean futureUse) { + public SWIGTYPE_p_double(long cPtr, boolean futureUse) { swigCPtr = cPtr; } - protected SWIGTYPE_p_double() { + public SWIGTYPE_p_double() { swigCPtr = 0; } - protected static long getCPtr(SWIGTYPE_p_double obj) { + public static long getCPtr(SWIGTYPE_p_double obj) { return (obj == null) ? 0 : obj.swigCPtr; } } diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CanTalon.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_float.java similarity index 57% rename from wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CanTalon.java rename to wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_float.java index e3bf757091..62678700c5 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/CanTalon.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_float.java @@ -8,5 +8,19 @@ package edu.wpi.first.wpilibj.hal; -public class CanTalon { +public class SWIGTYPE_p_float { + private long swigCPtr; + + public SWIGTYPE_p_float(long cPtr, boolean futureUse) { + swigCPtr = cPtr; + } + + public SWIGTYPE_p_float() { + swigCPtr = 0; + } + + public static long getCPtr(SWIGTYPE_p_float obj) { + return (obj == null) ? 0 : obj.swigCPtr; + } } + diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_int.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_int.java index 0e0cbe5ca4..e0b14b5e8f 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_int.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_int.java @@ -11,15 +11,15 @@ package edu.wpi.first.wpilibj.hal; public class SWIGTYPE_p_int { private long swigCPtr; - protected SWIGTYPE_p_int(long cPtr, boolean futureUse) { + public SWIGTYPE_p_int(long cPtr, boolean futureUse) { swigCPtr = cPtr; } - protected SWIGTYPE_p_int() { + public SWIGTYPE_p_int() { swigCPtr = 0; } - protected static long getCPtr(SWIGTYPE_p_int obj) { + public static long getCPtr(SWIGTYPE_p_int obj) { return (obj == null) ? 0 : obj.swigCPtr; } } diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_int32_t.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_int32_t.java new file mode 100644 index 0000000000..1d8644123b --- /dev/null +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_int32_t.java @@ -0,0 +1,26 @@ +/* ---------------------------------------------------------------------------- + * This file was automatically generated by SWIG (http://www.swig.org). + * Version 2.0.11 + * + * Do not make changes to this file unless you know what you are doing--modify + * the SWIG interface file instead. + * ----------------------------------------------------------------------------- */ + +package edu.wpi.first.wpilibj.hal; + +public class SWIGTYPE_p_int32_t { + private long swigCPtr; + + public SWIGTYPE_p_int32_t(long cPtr, boolean futureUse) { + swigCPtr = cPtr; + } + + public SWIGTYPE_p_int32_t() { + swigCPtr = 0; + } + + public static long getCPtr(SWIGTYPE_p_int32_t obj) { + return (obj == null) ? 0 : obj.swigCPtr; + } +} + diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_uint32_t.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_uint32_t.java new file mode 100644 index 0000000000..dd6f826bef --- /dev/null +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_uint32_t.java @@ -0,0 +1,26 @@ +/* ---------------------------------------------------------------------------- + * This file was automatically generated by SWIG (http://www.swig.org). + * Version 2.0.11 + * + * Do not make changes to this file unless you know what you are doing--modify + * the SWIG interface file instead. + * ----------------------------------------------------------------------------- */ + +package edu.wpi.first.wpilibj.hal; + +public class SWIGTYPE_p_uint32_t { + private long swigCPtr; + + public SWIGTYPE_p_uint32_t(long cPtr, boolean futureUse) { + swigCPtr = cPtr; + } + + public SWIGTYPE_p_uint32_t() { + swigCPtr = 0; + } + + public static long getCPtr(SWIGTYPE_p_uint32_t obj) { + return (obj == null) ? 0 : obj.swigCPtr; + } +} + diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_uint8_t.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_uint8_t.java new file mode 100644 index 0000000000..2bc9d25133 --- /dev/null +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/SWIGTYPE_p_uint8_t.java @@ -0,0 +1,26 @@ +/* ---------------------------------------------------------------------------- + * This file was automatically generated by SWIG (http://www.swig.org). + * Version 2.0.11 + * + * Do not make changes to this file unless you know what you are doing--modify + * the SWIG interface file instead. + * ----------------------------------------------------------------------------- */ + +package edu.wpi.first.wpilibj.hal; + +public class SWIGTYPE_p_uint8_t { + private long swigCPtr; + + public SWIGTYPE_p_uint8_t(long cPtr, boolean futureUse) { + swigCPtr = cPtr; + } + + public SWIGTYPE_p_uint8_t() { + swigCPtr = 0; + } + + public static long getCPtr(SWIGTYPE_p_uint8_t obj) { + return (obj == null) ? 0 : obj.swigCPtr; + } +} + diff --git a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/hal/CanTalonJNI.java b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/hal/CanTalonJNI.java index 7ceed8708a..030312e9f7 100644 --- a/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/hal/CanTalonJNI.java +++ b/wpilibj/wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/hal/CanTalonJNI.java @@ -9,6 +9,21 @@ package edu.wpi.first.wpilibj.hal; public class CanTalonJNI { + public final static native long new_doublep(); + public final static native long copy_doublep(double jarg1); + public final static native void delete_doublep(long jarg1); + public final static native void doublep_assign(long jarg1, double jarg2); + public final static native double doublep_value(long jarg1); + public final static native long new_intp(); + public final static native long copy_intp(int jarg1); + public final static native void delete_intp(long jarg1); + public final static native void intp_assign(long jarg1, int jarg2); + public final static native int intp_value(long jarg1); + public final static native long new_floatp(); + public final static native long copy_floatp(float jarg1); + public final static native void delete_floatp(long jarg1); + public final static native void floatp_assign(long jarg1, float jarg2); + public final static native float floatp_value(long jarg1); public final static native long new_CtreCanNode(long jarg1); public final static native void delete_CtreCanNode(long jarg1); public final static native long CtreCanNode_GetDeviceNumber(long jarg1, CtreCanNode jarg1_); @@ -16,6 +31,123 @@ public class CanTalonJNI { public final static native long new_CanTalonSRX__SWIG_1(); public final static native void delete_CanTalonSRX(long jarg1); public final static native void CanTalonSRX_Set(long jarg1, CanTalonSRX jarg1_, double jarg2); + public final static native int CanTalonSRX_kMode_DutyCycle_get(); + public final static native int CanTalonSRX_kMode_PositionCloseLoop_get(); + public final static native int CanTalonSRX_kMode_VelocityCloseLoop_get(); + public final static native int CanTalonSRX_kMode_CurrentCloseLoop_get(); + public final static native int CanTalonSRX_kMode_VoltCompen_get(); + public final static native int CanTalonSRX_kMode_SlaveFollower_get(); + public final static native int CanTalonSRX_kMode_NoDrive_get(); + public final static native int CanTalonSRX_kLimitSwitchOverride_UseDefaultsFromFlash_get(); + public final static native int CanTalonSRX_kLimitSwitchOverride_DisableFwd_DisableRev_get(); + public final static native int CanTalonSRX_kLimitSwitchOverride_DisableFwd_EnableRev_get(); + public final static native int CanTalonSRX_kLimitSwitchOverride_EnableFwd_DisableRev_get(); + public final static native int CanTalonSRX_kLimitSwitchOverride_EnableFwd_EnableRev_get(); + public final static native int CanTalonSRX_kBrakeOverride_UseDefaultsFromFlash_get(); + public final static native int CanTalonSRX_kBrakeOverride_OverrideCoast_get(); + public final static native int CanTalonSRX_kBrakeOverride_OverrideBrake_get(); + public final static native int CanTalonSRX_kFeedbackDev_DigitalQuadEnc_get(); + public final static native int CanTalonSRX_kFeedbackDev_AnalogPot_get(); + public final static native int CanTalonSRX_kFeedbackDev_AnalogEncoder_get(); + public final static native int CanTalonSRX_kFeedbackDev_CountEveryRisingEdge_get(); + public final static native int CanTalonSRX_kFeedbackDev_CountEveryFallingEdge_get(); + public final static native int CanTalonSRX_kFeedbackDev_PosIsPulseWidth_get(); + public final static native int CanTalonSRX_kProfileSlotSelect_Slot0_get(); + public final static native int CanTalonSRX_kProfileSlotSelect_Slot1_get(); + public final static native int CanTalonSRX_kStatusFrame_General_get(); + public final static native int CanTalonSRX_kStatusFrame_Feedback_get(); + public final static native int CanTalonSRX_kStatusFrame_Encoder_get(); + public final static native int CanTalonSRX_kStatusFrame_AnalogTempVbat_get(); + public final static native int CanTalonSRX_eProfileParamSlot0_P_get(); + public final static native int CanTalonSRX_eProfileParamSlot0_I_get(); + public final static native int CanTalonSRX_eProfileParamSlot0_D_get(); + public final static native int CanTalonSRX_eProfileParamSlot0_F_get(); + public final static native int CanTalonSRX_eProfileParamSlot0_IZone_get(); + public final static native int CanTalonSRX_eProfileParamSlot0_CloseLoopRampRate_get(); + public final static native int CanTalonSRX_eProfileParamSlot1_P_get(); + public final static native int CanTalonSRX_eProfileParamSlot1_I_get(); + public final static native int CanTalonSRX_eProfileParamSlot1_D_get(); + public final static native int CanTalonSRX_eProfileParamSlot1_F_get(); + public final static native int CanTalonSRX_eProfileParamSlot1_IZone_get(); + public final static native int CanTalonSRX_eProfileParamSlot1_CloseLoopRampRate_get(); + public final static native int CanTalonSRX_eProfileParamSoftLimitForThreshold_get(); + public final static native int CanTalonSRX_eProfileParamSoftLimitRevThreshold_get(); + public final static native int CanTalonSRX_eProfileParamSoftLimitForEnable_get(); + public final static native int CanTalonSRX_eProfileParamSoftLimitRevEnable_get(); + public final static native int CanTalonSRX_eOnBoot_BrakeMode_get(); + public final static native int CanTalonSRX_eOnBoot_LimitSwitch_Forward_NormallyClosed_get(); + public final static native int CanTalonSRX_eOnBoot_LimitSwitch_Reverse_NormallyClosed_get(); + public final static native int CanTalonSRX_eOnBoot_LimitSwitch_Forward_Disable_get(); + public final static native int CanTalonSRX_eOnBoot_LimitSwitch_Reverse_Disable_get(); + public final static native int CanTalonSRX_eFault_OverTemp_get(); + public final static native int CanTalonSRX_eFault_UnderVoltage_get(); + public final static native int CanTalonSRX_eFault_ForLim_get(); + public final static native int CanTalonSRX_eFault_RevLim_get(); + public final static native int CanTalonSRX_eFault_HardwareFailure_get(); + public final static native int CanTalonSRX_eFault_ForSoftLim_get(); + public final static native int CanTalonSRX_eFault_RevSoftLim_get(); + public final static native int CanTalonSRX_eStckyFault_OverTemp_get(); + public final static native int CanTalonSRX_eStckyFault_UnderVoltage_get(); + public final static native int CanTalonSRX_eStckyFault_ForLim_get(); + public final static native int CanTalonSRX_eStckyFault_RevLim_get(); + public final static native int CanTalonSRX_eStckyFault_ForSoftLim_get(); + public final static native int CanTalonSRX_eStckyFault_RevSoftLim_get(); + public final static native int CanTalonSRX_eAppliedThrottle_get(); + public final static native int CanTalonSRX_eCloseLoopErr_get(); + public final static native int CanTalonSRX_eFeedbackDeviceSelect_get(); + public final static native int CanTalonSRX_eRevMotDuringCloseLoopEn_get(); + public final static native int CanTalonSRX_eModeSelect_get(); + public final static native int CanTalonSRX_eProfileSlotSelect_get(); + public final static native int CanTalonSRX_eRampThrottle_get(); + public final static native int CanTalonSRX_eRevFeedbackSensor_get(); + public final static native int CanTalonSRX_eLimitSwitchEn_get(); + public final static native int CanTalonSRX_eLimitSwitchClosedFor_get(); + public final static native int CanTalonSRX_eLimitSwitchClosedRev_get(); + public final static native int CanTalonSRX_eSensorPosition_get(); + public final static native int CanTalonSRX_eSensorVelocity_get(); + public final static native int CanTalonSRX_eCurrent_get(); + public final static native int CanTalonSRX_eBrakeIsEnabled_get(); + public final static native int CanTalonSRX_eEncPosition_get(); + public final static native int CanTalonSRX_eEncVel_get(); + public final static native int CanTalonSRX_eEncIndexRiseEvents_get(); + public final static native int CanTalonSRX_eQuadApin_get(); + public final static native int CanTalonSRX_eQuadBpin_get(); + public final static native int CanTalonSRX_eQuadIdxpin_get(); + public final static native int CanTalonSRX_eAnalogInWithOv_get(); + public final static native int CanTalonSRX_eAnalogInVel_get(); + public final static native int CanTalonSRX_eTemp_get(); + public final static native int CanTalonSRX_eBatteryV_get(); + public final static native int CanTalonSRX_eResetCount_get(); + public final static native int CanTalonSRX_eResetFlags_get(); + public final static native int CanTalonSRX_eFirmVers_get(); + public final static native int CanTalonSRX_eSettingsChanged_get(); + public final static native long CanTalonSRX_SetParam(long jarg1, CanTalonSRX jarg1_, int jarg2, double jarg3); + public final static native long CanTalonSRX_RequestParam(long jarg1, CanTalonSRX jarg1_, int jarg2); + public final static native long CanTalonSRX_GetParamResponse(long jarg1, CanTalonSRX jarg1_, int jarg2, long jarg3); + public final static native long CanTalonSRX_GetParamResponseInt32(long jarg1, CanTalonSRX jarg1_, int jarg2, long jarg3); + public final static native long CanTalonSRX_SetPgain(long jarg1, CanTalonSRX jarg1_, long jarg2, double jarg3); + public final static native long CanTalonSRX_SetIgain(long jarg1, CanTalonSRX jarg1_, long jarg2, double jarg3); + public final static native long CanTalonSRX_SetDgain(long jarg1, CanTalonSRX jarg1_, long jarg2, double jarg3); + public final static native long CanTalonSRX_SetFgain(long jarg1, CanTalonSRX jarg1_, long jarg2, double jarg3); + public final static native long CanTalonSRX_SetIzone(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_SetCloseLoopRampRate(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_SetSensorPosition(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_SetForwardSoftLimit(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_SetReverseSoftLimit(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_SetForwardSoftEnable(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_SetReverseSoftEnable(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_GetPgain(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_GetIgain(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_GetDgain(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_GetFgain(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_GetIzone(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_GetCloseLoopRampRate(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_GetForwardSoftLimit(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_GetReverseSoftLimit(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_GetForwardSoftEnable(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_GetReverseSoftEnable(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_SetStatusFrameRate(long jarg1, CanTalonSRX jarg1_, long jarg2, long jarg3); + public final static native long CanTalonSRX_ClearStickyFaults(long jarg1, CanTalonSRX jarg1_); public final static native long CanTalonSRX_GetFault_OverTemp(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetFault_UnderVoltage(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetFault_ForLim(long jarg1, CanTalonSRX jarg1_, long jarg2); @@ -29,14 +161,13 @@ public class CanTalonJNI { public final static native long CanTalonSRX_GetStckyFault_RevLim(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetStckyFault_ForSoftLim(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetStckyFault_RevSoftLim(long jarg1, CanTalonSRX jarg1_, long jarg2); - public final static native long CanTalonSRX_GetAppliedThrottle11(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_GetAppliedThrottle(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetCloseLoopErr(long jarg1, CanTalonSRX jarg1_, long jarg2); - public final static native long CanTalonSRX_GetSelectlFeedbackDevice(long jarg1, CanTalonSRX jarg1_, long jarg2); + public final static native long CanTalonSRX_GetFeedbackDeviceSelect(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetModeSelect(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetLimitSwitchEn(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetLimitSwitchClosedFor(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetLimitSwitchClosedRev(long jarg1, CanTalonSRX jarg1_, long jarg2); - public final static native long CanTalonSRX_GetCloseLoopCellSelect(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetSensorPosition(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetSensorVelocity(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetCurrent(long jarg1, CanTalonSRX jarg1_, long jarg2); @@ -54,14 +185,14 @@ public class CanTalonJNI { public final static native long CanTalonSRX_GetResetCount(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetResetFlags(long jarg1, CanTalonSRX jarg1_, long jarg2); public final static native long CanTalonSRX_GetFirmVers(long jarg1, CanTalonSRX jarg1_, long jarg2); - public final static native long CanTalonSRX_SetDemand24(long jarg1, CanTalonSRX jarg1_, int jarg2); - public final static native long CanTalonSRX_SetLimitSwitchEn(long jarg1, CanTalonSRX jarg1_, int jarg2); - public final static native long CanTalonSRX_SetSelectlFeedbackDevice(long jarg1, CanTalonSRX jarg1_, int jarg2); + public final static native long CanTalonSRX_SetDemand(long jarg1, CanTalonSRX jarg1_, int jarg2); + public final static native long CanTalonSRX_SetOverrideLimitSwitchEn(long jarg1, CanTalonSRX jarg1_, int jarg2); + public final static native long CanTalonSRX_SetFeedbackDeviceSelect(long jarg1, CanTalonSRX jarg1_, int jarg2); public final static native long CanTalonSRX_SetRevMotDuringCloseLoopEn(long jarg1, CanTalonSRX jarg1_, int jarg2); - public final static native long CanTalonSRX_SetBrakeType(long jarg1, CanTalonSRX jarg1_, int jarg2); + public final static native long CanTalonSRX_SetOverrideBrakeType(long jarg1, CanTalonSRX jarg1_, int jarg2); public final static native long CanTalonSRX_SetModeSelect(long jarg1, CanTalonSRX jarg1_, int jarg2); - public final static native long CanTalonSRX_SetCloseLoopCellSelect(long jarg1, CanTalonSRX jarg1_, int jarg2); + public final static native long CanTalonSRX_SetProfileSlotSelect(long jarg1, CanTalonSRX jarg1_, int jarg2); public final static native long CanTalonSRX_SetRampThrottle(long jarg1, CanTalonSRX jarg1_, int jarg2); - public final static native long CanTalonSRX_SetRevEncoderPosAndVel(long jarg1, CanTalonSRX jarg1_, int jarg2); + public final static native long CanTalonSRX_SetRevFeedbackSensor(long jarg1, CanTalonSRX jarg1_, int jarg2); public final static native long CanTalonSRX_SWIGUpcast(long jarg1); } diff --git a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CANTalonTest.java b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CANTalonTest.java index 2cb7def479..7e9f1358d5 100644 --- a/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CANTalonTest.java +++ b/wpilibj/wpilibJavaIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CANTalonTest.java @@ -19,6 +19,8 @@ import edu.wpi.first.wpilibj.fixtures.SampleFixture; import edu.wpi.first.wpilibj.test.AbstractComsSetup; import edu.wpi.first.wpilibj.hal.CanTalonSRX; +import edu.wpi.first.wpilibj.hal.CanTalonJNI; +import edu.wpi.first.wpilibj.hal.SWIGTYPE_p_double; /** * Basic test (borrowed straight from SampleTest) for running the CAN TalonSRX. @@ -61,10 +63,21 @@ public class CANTalonTest extends AbstractComsSetup { talon.SetModeSelect(0); // Set Talon to 50% forwards throttle. talon.Set(0.5); + long currentp = CanTalonJNI.new_doublep();//new SWIGTYPE_p_double(, true); + talon.GetTemp(new SWIGTYPE_p_double(currentp, true)); + System.out.println(CanTalonJNI.doublep_value(currentp)); Timer.delay(1.5); // Turn Talon off. talon.Set(0.0); assertTrue(true); + + Timer.delay(2); + CANTalon tal = new CANTalon(0); + tal.enableControl(); + tal.set(0.5); + System.out.println(tal.getTemp()); + Timer.delay(1.0); + tal.disable(); } } diff --git a/wpilibj/wpilibJavaJNI/lib/CanTalonSRXJNI.cpp b/wpilibj/wpilibJavaJNI/lib/CanTalonSRXJNI.cpp index 56d5eb1878..d8e0ee9f0f 100644 --- a/wpilibj/wpilibJavaJNI/lib/CanTalonSRXJNI.cpp +++ b/wpilibj/wpilibJavaJNI/lib/CanTalonSRXJNI.cpp @@ -214,10 +214,259 @@ static void SWIGUNUSED SWIG_JavaThrowException(JNIEnv *jenv, SWIG_JavaExceptionC #include "ctre/CanTalonSRX.h" +static double *new_doublep() { + return new double(); +} + +static double *copy_doublep(double value) { + return new double(value); +} + +static void delete_doublep(double *obj) { + if (obj) delete obj; +} + +static void doublep_assign(double *obj, double value) { + *obj = value; +} + +static double doublep_value(double *obj) { + return *obj; +} + + +static int *new_intp() { + return new int(); +} + +static int *copy_intp(int value) { + return new int(value); +} + +static void delete_intp(int *obj) { + if (obj) delete obj; +} + +static void intp_assign(int *obj, int value) { + *obj = value; +} + +static int intp_value(int *obj) { + return *obj; +} + + +static float *new_floatp() { + return new float(); +} + +static float *copy_floatp(float value) { + return new float(value); +} + +static void delete_floatp(float *obj) { + if (obj) delete obj; +} + +static void floatp_assign(float *obj, float value) { + *obj = value; +} + +static float floatp_value(float *obj) { + return *obj; +} + + #ifdef __cplusplus extern "C" { #endif +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_new_1doublep(JNIEnv *jenv, jclass jcls) { + jlong jresult = 0 ; + double *result = 0 ; + + (void)jenv; + (void)jcls; + result = (double *)new_doublep(); + *(double **)&jresult = result; + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_copy_1doublep(JNIEnv *jenv, jclass jcls, jdouble jarg1) { + jlong jresult = 0 ; + double arg1 ; + double *result = 0 ; + + (void)jenv; + (void)jcls; + arg1 = (double)jarg1; + result = (double *)copy_doublep(arg1); + *(double **)&jresult = result; + return jresult; +} + + +SWIGEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_delete_1doublep(JNIEnv *jenv, jclass jcls, jlong jarg1) { + double *arg1 = (double *) 0 ; + + (void)jenv; + (void)jcls; + arg1 = *(double **)&jarg1; + delete_doublep(arg1); +} + + +SWIGEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_doublep_1assign(JNIEnv *jenv, jclass jcls, jlong jarg1, jdouble jarg2) { + double *arg1 = (double *) 0 ; + double arg2 ; + + (void)jenv; + (void)jcls; + arg1 = *(double **)&jarg1; + arg2 = (double)jarg2; + doublep_assign(arg1,arg2); +} + + +SWIGEXPORT jdouble JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_doublep_1value(JNIEnv *jenv, jclass jcls, jlong jarg1) { + jdouble jresult = 0 ; + double *arg1 = (double *) 0 ; + double result; + + (void)jenv; + (void)jcls; + arg1 = *(double **)&jarg1; + result = (double)doublep_value(arg1); + jresult = (jdouble)result; + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_new_1intp(JNIEnv *jenv, jclass jcls) { + jlong jresult = 0 ; + int *result = 0 ; + + (void)jenv; + (void)jcls; + result = (int *)new_intp(); + *(int **)&jresult = result; + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_copy_1intp(JNIEnv *jenv, jclass jcls, jint jarg1) { + jlong jresult = 0 ; + int arg1 ; + int *result = 0 ; + + (void)jenv; + (void)jcls; + arg1 = (int)jarg1; + result = (int *)copy_intp(arg1); + *(int **)&jresult = result; + return jresult; +} + + +SWIGEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_delete_1intp(JNIEnv *jenv, jclass jcls, jlong jarg1) { + int *arg1 = (int *) 0 ; + + (void)jenv; + (void)jcls; + arg1 = *(int **)&jarg1; + delete_intp(arg1); +} + + +SWIGEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_intp_1assign(JNIEnv *jenv, jclass jcls, jlong jarg1, jint jarg2) { + int *arg1 = (int *) 0 ; + int arg2 ; + + (void)jenv; + (void)jcls; + arg1 = *(int **)&jarg1; + arg2 = (int)jarg2; + intp_assign(arg1,arg2); +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_intp_1value(JNIEnv *jenv, jclass jcls, jlong jarg1) { + jint jresult = 0 ; + int *arg1 = (int *) 0 ; + int result; + + (void)jenv; + (void)jcls; + arg1 = *(int **)&jarg1; + result = (int)intp_value(arg1); + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_new_1floatp(JNIEnv *jenv, jclass jcls) { + jlong jresult = 0 ; + float *result = 0 ; + + (void)jenv; + (void)jcls; + result = (float *)new_floatp(); + *(float **)&jresult = result; + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_copy_1floatp(JNIEnv *jenv, jclass jcls, jfloat jarg1) { + jlong jresult = 0 ; + float arg1 ; + float *result = 0 ; + + (void)jenv; + (void)jcls; + arg1 = (float)jarg1; + result = (float *)copy_floatp(arg1); + *(float **)&jresult = result; + return jresult; +} + + +SWIGEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_delete_1floatp(JNIEnv *jenv, jclass jcls, jlong jarg1) { + float *arg1 = (float *) 0 ; + + (void)jenv; + (void)jcls; + arg1 = *(float **)&jarg1; + delete_floatp(arg1); +} + + +SWIGEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_floatp_1assign(JNIEnv *jenv, jclass jcls, jlong jarg1, jfloat jarg2) { + float *arg1 = (float *) 0 ; + float arg2 ; + + (void)jenv; + (void)jcls; + arg1 = *(float **)&jarg1; + arg2 = (float)jarg2; + floatp_assign(arg1,arg2); +} + + +SWIGEXPORT jfloat JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_floatp_1value(JNIEnv *jenv, jclass jcls, jlong jarg1) { + jfloat jresult = 0 ; + float *arg1 = (float *) 0 ; + float result; + + (void)jenv; + (void)jcls; + arg1 = *(float **)&jarg1; + result = (float)floatp_value(arg1); + jresult = (jfloat)result; + return jresult; +} + + SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_new_1CtreCanNode(JNIEnv *jenv, jclass jcls, jlong jarg1) { jlong jresult = 0 ; UINT8 arg1 ; @@ -312,6 +561,1749 @@ SWIGEXPORT void JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1 } +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kMode_1DutyCycle_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kMode_DutyCycle; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kMode_1PositionCloseLoop_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kMode_PositionCloseLoop; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kMode_1VelocityCloseLoop_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kMode_VelocityCloseLoop; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kMode_1CurrentCloseLoop_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kMode_CurrentCloseLoop; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kMode_1VoltCompen_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kMode_VoltCompen; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kMode_1SlaveFollower_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kMode_SlaveFollower; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kMode_1NoDrive_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kMode_NoDrive; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kLimitSwitchOverride_1UseDefaultsFromFlash_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kLimitSwitchOverride_UseDefaultsFromFlash; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kLimitSwitchOverride_1DisableFwd_1DisableRev_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kLimitSwitchOverride_DisableFwd_DisableRev; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kLimitSwitchOverride_1DisableFwd_1EnableRev_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kLimitSwitchOverride_DisableFwd_EnableRev; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kLimitSwitchOverride_1EnableFwd_1DisableRev_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kLimitSwitchOverride_EnableFwd_DisableRev; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kLimitSwitchOverride_1EnableFwd_1EnableRev_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kLimitSwitchOverride_EnableFwd_EnableRev; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kBrakeOverride_1UseDefaultsFromFlash_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kBrakeOverride_UseDefaultsFromFlash; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kBrakeOverride_1OverrideCoast_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kBrakeOverride_OverrideCoast; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kBrakeOverride_1OverrideBrake_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kBrakeOverride_OverrideBrake; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kFeedbackDev_1DigitalQuadEnc_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kFeedbackDev_DigitalQuadEnc; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kFeedbackDev_1AnalogPot_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kFeedbackDev_AnalogPot; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kFeedbackDev_1AnalogEncoder_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kFeedbackDev_AnalogEncoder; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kFeedbackDev_1CountEveryRisingEdge_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kFeedbackDev_CountEveryRisingEdge; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kFeedbackDev_1CountEveryFallingEdge_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kFeedbackDev_CountEveryFallingEdge; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kFeedbackDev_1PosIsPulseWidth_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kFeedbackDev_PosIsPulseWidth; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kProfileSlotSelect_1Slot0_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kProfileSlotSelect_Slot0; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kProfileSlotSelect_1Slot1_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kProfileSlotSelect_Slot1; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kStatusFrame_1General_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kStatusFrame_General; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kStatusFrame_1Feedback_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kStatusFrame_Feedback; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kStatusFrame_1Encoder_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kStatusFrame_Encoder; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1kStatusFrame_1AnalogTempVbat_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + int result; + + (void)jenv; + (void)jcls; + result = (int)CanTalonSRX::kStatusFrame_AnalogTempVbat; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot0_1P_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot0_P; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot0_1I_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot0_I; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot0_1D_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot0_D; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot0_1F_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot0_F; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot0_1IZone_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot0_IZone; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot0_1CloseLoopRampRate_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot0_CloseLoopRampRate; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot1_1P_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot1_P; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot1_1I_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot1_I; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot1_1D_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot1_D; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot1_1F_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot1_F; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot1_1IZone_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot1_IZone; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSlot1_1CloseLoopRampRate_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSlot1_CloseLoopRampRate; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSoftLimitForThreshold_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSoftLimitForThreshold; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSoftLimitRevThreshold_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSoftLimitRevThreshold; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSoftLimitForEnable_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSoftLimitForEnable; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileParamSoftLimitRevEnable_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileParamSoftLimitRevEnable; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eOnBoot_1BrakeMode_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eOnBoot_BrakeMode; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eOnBoot_1LimitSwitch_1Forward_1NormallyClosed_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eOnBoot_LimitSwitch_Forward_NormallyClosed; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eOnBoot_1LimitSwitch_1Reverse_1NormallyClosed_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eOnBoot_LimitSwitch_Reverse_NormallyClosed; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eOnBoot_1LimitSwitch_1Forward_1Disable_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eOnBoot_LimitSwitch_Forward_Disable; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eOnBoot_1LimitSwitch_1Reverse_1Disable_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eOnBoot_LimitSwitch_Reverse_Disable; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFault_1OverTemp_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFault_OverTemp; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFault_1UnderVoltage_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFault_UnderVoltage; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFault_1ForLim_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFault_ForLim; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFault_1RevLim_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFault_RevLim; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFault_1HardwareFailure_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFault_HardwareFailure; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFault_1ForSoftLim_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFault_ForSoftLim; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFault_1RevSoftLim_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFault_RevSoftLim; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eStckyFault_1OverTemp_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eStckyFault_OverTemp; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eStckyFault_1UnderVoltage_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eStckyFault_UnderVoltage; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eStckyFault_1ForLim_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eStckyFault_ForLim; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eStckyFault_1RevLim_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eStckyFault_RevLim; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eStckyFault_1ForSoftLim_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eStckyFault_ForSoftLim; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eStckyFault_1RevSoftLim_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eStckyFault_RevSoftLim; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eAppliedThrottle_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eAppliedThrottle; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eCloseLoopErr_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eCloseLoopErr; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFeedbackDeviceSelect_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFeedbackDeviceSelect; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eRevMotDuringCloseLoopEn_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eRevMotDuringCloseLoopEn; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eModeSelect_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eModeSelect; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eProfileSlotSelect_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eProfileSlotSelect; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eRampThrottle_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eRampThrottle; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eRevFeedbackSensor_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eRevFeedbackSensor; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eLimitSwitchEn_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eLimitSwitchEn; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eLimitSwitchClosedFor_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eLimitSwitchClosedFor; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eLimitSwitchClosedRev_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eLimitSwitchClosedRev; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eSensorPosition_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eSensorPosition; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eSensorVelocity_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eSensorVelocity; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eCurrent_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eCurrent; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eBrakeIsEnabled_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eBrakeIsEnabled; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eEncPosition_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eEncPosition; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eEncVel_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eEncVel; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eEncIndexRiseEvents_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eEncIndexRiseEvents; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eQuadApin_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eQuadApin; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eQuadBpin_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eQuadBpin; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eQuadIdxpin_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eQuadIdxpin; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eAnalogInWithOv_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eAnalogInWithOv; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eAnalogInVel_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eAnalogInVel; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eTemp_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eTemp; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eBatteryV_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eBatteryV; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eResetCount_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eResetCount; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eResetFlags_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eResetFlags; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eFirmVers_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eFirmVers; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jint JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1eSettingsChanged_1get(JNIEnv *jenv, jclass jcls) { + jint jresult = 0 ; + CanTalonSRX::_param_t result; + + (void)jenv; + (void)jcls; + result = (CanTalonSRX::_param_t)CanTalonSRX::eSettingsChanged; + jresult = (jint)result; + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetParam(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2, jdouble jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + CanTalonSRX::param_t arg2 ; + double arg3 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + arg2 = (CanTalonSRX::param_t)jarg2; + arg3 = (double)jarg3; + result = (arg1)->SetParam(arg2,arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1RequestParam(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + CanTalonSRX::param_t arg2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + arg2 = (CanTalonSRX::param_t)jarg2; + result = (arg1)->RequestParam(arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetParamResponse(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + CanTalonSRX::param_t arg2 ; + double *arg3 = 0 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + arg2 = (CanTalonSRX::param_t)jarg2; + arg3 = *(double **)&jarg3; + if (!arg3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "double & reference is null"); + return 0; + } + result = (arg1)->GetParamResponse(arg2,*arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetParamResponseInt32(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + CanTalonSRX::param_t arg2 ; + int32_t *arg3 = 0 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + arg2 = (CanTalonSRX::param_t)jarg2; + arg3 = *(int32_t **)&jarg3; + if (!arg3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int32_t & reference is null"); + return 0; + } + result = (arg1)->GetParamResponseInt32(arg2,*arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetPgain(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jdouble jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + double arg3 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = (double)jarg3; + result = (arg1)->SetPgain(arg2,arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetIgain(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jdouble jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + double arg3 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = (double)jarg3; + result = (arg1)->SetIgain(arg2,arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetDgain(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jdouble jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + double arg3 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = (double)jarg3; + result = (arg1)->SetDgain(arg2,arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetFgain(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jdouble jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + double arg3 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = (double)jarg3; + result = (arg1)->SetFgain(arg2,arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetIzone(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + int32_t arg3 ; + uint32_t *argp2 ; + int32_t *argp3 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + argp3 = *(int32_t **)&jarg3; + if (!argp3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null int32_t"); + return 0; + } + arg3 = *argp3; + result = (arg1)->SetIzone(arg2,arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetCloseLoopRampRate(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + int32_t arg3 ; + uint32_t *argp2 ; + int32_t *argp3 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + argp3 = *(int32_t **)&jarg3; + if (!argp3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null int32_t"); + return 0; + } + arg3 = *argp3; + result = (arg1)->SetCloseLoopRampRate(arg2,arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetSensorPosition(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t arg2 ; + int32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(int32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null int32_t"); + return 0; + } + arg2 = *argp2; + result = (arg1)->SetSensorPosition(arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetForwardSoftLimit(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t arg2 ; + int32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(int32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null int32_t"); + return 0; + } + arg2 = *argp2; + result = (arg1)->SetForwardSoftLimit(arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetReverseSoftLimit(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t arg2 ; + int32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(int32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null int32_t"); + return 0; + } + arg2 = *argp2; + result = (arg1)->SetReverseSoftLimit(arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetForwardSoftEnable(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t arg2 ; + int32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(int32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null int32_t"); + return 0; + } + arg2 = *argp2; + result = (arg1)->SetForwardSoftEnable(arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetReverseSoftEnable(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t arg2 ; + int32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(int32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null int32_t"); + return 0; + } + arg2 = *argp2; + result = (arg1)->SetReverseSoftEnable(arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetPgain(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + double *arg3 = 0 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = *(double **)&jarg3; + if (!arg3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "double & reference is null"); + return 0; + } + result = (arg1)->GetPgain(arg2,*arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetIgain(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + double *arg3 = 0 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = *(double **)&jarg3; + if (!arg3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "double & reference is null"); + return 0; + } + result = (arg1)->GetIgain(arg2,*arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetDgain(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + double *arg3 = 0 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = *(double **)&jarg3; + if (!arg3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "double & reference is null"); + return 0; + } + result = (arg1)->GetDgain(arg2,*arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetFgain(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + double *arg3 = 0 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = *(double **)&jarg3; + if (!arg3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "double & reference is null"); + return 0; + } + result = (arg1)->GetFgain(arg2,*arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetIzone(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + int32_t *arg3 = 0 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = *(int32_t **)&jarg3; + if (!arg3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int32_t & reference is null"); + return 0; + } + result = (arg1)->GetIzone(arg2,*arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetCloseLoopRampRate(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + int32_t *arg3 = 0 ; + uint32_t *argp2 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + arg3 = *(int32_t **)&jarg3; + if (!arg3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int32_t & reference is null"); + return 0; + } + result = (arg1)->GetCloseLoopRampRate(arg2,*arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetForwardSoftLimit(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t *arg2 = 0 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + arg2 = *(int32_t **)&jarg2; + if (!arg2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int32_t & reference is null"); + return 0; + } + result = (arg1)->GetForwardSoftLimit(*arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetReverseSoftLimit(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t *arg2 = 0 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + arg2 = *(int32_t **)&jarg2; + if (!arg2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int32_t & reference is null"); + return 0; + } + result = (arg1)->GetReverseSoftLimit(*arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetForwardSoftEnable(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t *arg2 = 0 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + arg2 = *(int32_t **)&jarg2; + if (!arg2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int32_t & reference is null"); + return 0; + } + result = (arg1)->GetForwardSoftEnable(*arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetReverseSoftEnable(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + int32_t *arg2 = 0 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + arg2 = *(int32_t **)&jarg2; + if (!arg2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int32_t & reference is null"); + return 0; + } + result = (arg1)->GetReverseSoftEnable(*arg2); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetStatusFrameRate(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2, jlong jarg3) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + uint32_t arg2 ; + uint8_t arg3 ; + uint32_t *argp2 ; + uint8_t *argp3 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + argp2 = *(uint32_t **)&jarg2; + if (!argp2) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint32_t"); + return 0; + } + arg2 = *argp2; + argp3 = *(uint8_t **)&jarg3; + if (!argp3) { + SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "Attempt to dereference null uint8_t"); + return 0; + } + arg3 = *argp3; + result = (arg1)->SetStatusFrameRate(arg2,arg3); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1ClearStickyFaults(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_) { + jlong jresult = 0 ; + CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; + CTR_Code result; + + (void)jenv; + (void)jcls; + (void)jarg1_; + arg1 = *(CanTalonSRX **)&jarg1; + result = (arg1)->ClearStickyFaults(); + *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); + return jresult; +} + + SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetFault_1OverTemp(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; @@ -585,7 +2577,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetAppliedThrottle11(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetAppliedThrottle(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; int *arg2 = 0 ; @@ -600,7 +2592,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int & reference is null"); return 0; } - result = (arg1)->GetAppliedThrottle11(*arg2); + result = (arg1)->GetAppliedThrottle(*arg2); *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); return jresult; } @@ -627,7 +2619,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetSelectlFeedbackDevice(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetFeedbackDeviceSelect(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; int *arg2 = 0 ; @@ -642,7 +2634,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int & reference is null"); return 0; } - result = (arg1)->GetSelectlFeedbackDevice(*arg2); + result = (arg1)->GetFeedbackDeviceSelect(*arg2); *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); return jresult; } @@ -732,27 +2724,6 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetCloseLoopCellSelect(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { - jlong jresult = 0 ; - CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; - int *arg2 = 0 ; - CTR_Code result; - - (void)jenv; - (void)jcls; - (void)jarg1_; - arg1 = *(CanTalonSRX **)&jarg1; - arg2 = *(int **)&jarg2; - if (!arg2) { - SWIG_JavaThrowException(jenv, SWIG_JavaNullPointerException, "int & reference is null"); - return 0; - } - result = (arg1)->GetCloseLoopCellSelect(*arg2); - *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); - return jresult; -} - - SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1GetSensorPosition(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jlong jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; @@ -1110,7 +3081,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetDemand24(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetDemand(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; int arg2 ; @@ -1121,13 +3092,13 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ (void)jarg1_; arg1 = *(CanTalonSRX **)&jarg1; arg2 = (int)jarg2; - result = (arg1)->SetDemand24(arg2); + result = (arg1)->SetDemand(arg2); *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); return jresult; } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetLimitSwitchEn(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetOverrideLimitSwitchEn(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; int arg2 ; @@ -1138,13 +3109,13 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ (void)jarg1_; arg1 = *(CanTalonSRX **)&jarg1; arg2 = (int)jarg2; - result = (arg1)->SetLimitSwitchEn(arg2); + result = (arg1)->SetOverrideLimitSwitchEn(arg2); *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); return jresult; } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetSelectlFeedbackDevice(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetFeedbackDeviceSelect(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; int arg2 ; @@ -1155,7 +3126,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ (void)jarg1_; arg1 = *(CanTalonSRX **)&jarg1; arg2 = (int)jarg2; - result = (arg1)->SetSelectlFeedbackDevice(arg2); + result = (arg1)->SetFeedbackDeviceSelect(arg2); *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); return jresult; } @@ -1178,7 +3149,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetBrakeType(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetOverrideBrakeType(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; int arg2 ; @@ -1189,7 +3160,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ (void)jarg1_; arg1 = *(CanTalonSRX **)&jarg1; arg2 = (int)jarg2; - result = (arg1)->SetBrakeType(arg2); + result = (arg1)->SetOverrideBrakeType(arg2); *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); return jresult; } @@ -1212,7 +3183,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetCloseLoopCellSelect(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetProfileSlotSelect(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; int arg2 ; @@ -1223,7 +3194,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ (void)jarg1_; arg1 = *(CanTalonSRX **)&jarg1; arg2 = (int)jarg2; - result = (arg1)->SetCloseLoopCellSelect(arg2); + result = (arg1)->SetProfileSlotSelect(arg2); *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); return jresult; } @@ -1246,7 +3217,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ } -SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetRevEncoderPosAndVel(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { +SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_1SetRevFeedbackSensor(JNIEnv *jenv, jclass jcls, jlong jarg1, jobject jarg1_, jint jarg2) { jlong jresult = 0 ; CanTalonSRX *arg1 = (CanTalonSRX *) 0 ; int arg2 ; @@ -1257,7 +3228,7 @@ SWIGEXPORT jlong JNICALL Java_edu_wpi_first_wpilibj_hal_CanTalonJNI_CanTalonSRX_ (void)jarg1_; arg1 = *(CanTalonSRX **)&jarg1; arg2 = (int)jarg2; - result = (arg1)->SetRevEncoderPosAndVel(arg2); + result = (arg1)->SetRevFeedbackSensor(arg2); *(CTR_Code **)&jresult = new CTR_Code((const CTR_Code &)result); return jresult; } diff --git a/wpilibj/wpilibJavaJNI/swigTalon/CanTalonSRX.i b/wpilibj/wpilibJavaJNI/swigTalon/CanTalonSRX.i index b01ab1d6e4..0100efe0bf 100644 --- a/wpilibj/wpilibJavaJNI/swigTalon/CanTalonSRX.i +++ b/wpilibj/wpilibJavaJNI/swigTalon/CanTalonSRX.i @@ -3,5 +3,9 @@ #include "ctre/CanTalonSRX.h" %} +%include "cpointer.i" +%pointer_functions(double, doublep); +%pointer_functions(int, intp); +%pointer_functions(float, floatp); %include "CtreCanNode.h" %include "CanTalonSRX.h" diff --git a/wpilibj/wpilibJavaJNI/swigTalon/README b/wpilibj/wpilibJavaJNI/swigTalon/README index 59c289a7a5..ff44615791 100644 --- a/wpilibj/wpilibJavaJNI/swigTalon/README +++ b/wpilibj/wpilibJavaJNI/swigTalon/README @@ -3,3 +3,7 @@ for the CAN Talon stuff using swig. This whole directory is a temporary measure until I (James Kuszmaul--11/18/2014) or someone else figures out how to integrate the swig stuff into the build system. For now, all the generated JNI bindings are checked into git, so that it should work until someone goes and updates ctre/CanTalonSRX.* + +In order for this to work, I had to change the CanTalonSRX constructor to take a int deviceNumber instead of a uint8_t. + +Also, in all the SWIGTYPE* files, you must change protected methods to public functions. diff --git a/wpilibj/wpilibJavaJNI/swigTalon/generateJNI.sh b/wpilibj/wpilibJavaJNI/swigTalon/generateJNI.sh index d8ac303024..26a67a455a 100755 --- a/wpilibj/wpilibJavaJNI/swigTalon/generateJNI.sh +++ b/wpilibj/wpilibJavaJNI/swigTalon/generateJNI.sh @@ -14,4 +14,5 @@ swig -c++ -package edu.wpi.first.wpilibj.hal -java CanTalonSRX.i # Stick generated files into appropriate places. cp CanTalonSRX_wrap.cxx ../lib/CanTalonSRXJNI.cpp mv CanTalonJNI.java ../../wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/hal/ +rm CanTalon.java # useless file. cp *.java ../../wpilibJavaDevices/src/main/java/edu/wpi/first/wpilibj/