Home
2015.0.8 PDF - Read the Docs
Contents
1. 10 Chapter 1 Contents RobotPy WPILib Documentation Release master Table 1 1 continued from previous page wpilib DigitalSourcel channel DigitalSource Interface wpilib DoubleSolenoid args Controls 2 channels of high voltage Digital Output wpilib DriverStationl Provide access to the network communication data to from the Driver Station wpilib Encoder args kwargs Reads from quadrature encoders wpilib GearTooth channell Interface to the gear tooth sensor supplied by FIRST wpilib Gyro channel Interface to a gyro device via an AnalogInput wpilib I2C port deviceAddress I2C bus interface class wpilib InterruptableSensorBasel Base for sensors to be used with interrupts wpilib IterativeRobot IterativeRobot implements a specific type of Robot Program framework extendin wpilib Jaguar channel Texas Instruments Vex Robotics Jaguar Speed Controller as a PWM device wpilib Joystick portf Handle input from standard Joysticks connected to the Driver Station wpilib LiveWindow The public interface for putting sensors and actuators on the LiveWindow wpilib LiveWindowSendable A special type of object that can be displayed on the live window wpilib MotorSafety Provides mechanisms to safely shutdown motors if they aren t updated often enou wpilib PIDController args Can be used to control devices via a PID Control Loop wpilib PowerDistributionPanel Use to
2. 1 6 wpilib interfaces Package 123 RobotPy WPILib Documentation Release master class Range Bases builtins object k16G 3 k2G 0 k4G 1 k8G 2 Accelerometer getxX Common interface for getting the x axis acceleration Returns The acceleration along the x axis in g forces Accelerometer getyY Common interface for getting the y axis acceleration Returns The acceleration along the y axis in g forces Accelerometer getZ Common interface for getting the z axis acceleration Returns The acceleration along the z axis in g forces Accelerometer setRange range Common interface for setting the measuring range of an accelerometer Parameters range The maximum acceleration positive or negative that the accelerometer will measure Not all accelerometers support all ranges 1 6 2 Controller class woilib interfaces Controller Bases builtins object An interface for controllers Controllers run control loops the most command are PID controllers and there variants but this includes anything that is controlling an actuator in a separate thread disable Stops the control loop from running until explicitly re enabled by calling enable enable Allows the control loop to run 1 6 3 CounterBase class woilib interfaces CounterBase Bases builtins object Interface for counting the number of ticks on a digital input channel Encoders Gear tooth sensors and counters should all subclass this so it
3. m m m Lib comm ib comm lib command printcommand 119 mand scheduler 120 mand startcommand 121 mand subsystem 121 mand waitcommand 122 Lib command waitforchildren 123 lib command waituntilcommand 123 ib compressor 41 lib controllerpower 42 lib counter 44 ib digitalinput 49 Lib com ib com Labs Lib com com wpi lib digitaloutput 50 wpil ib digitalsource 51 wpil wpil lib doublesolenoid 51 lib driverstation 52 wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil ib iba ib ib ib ib ip ib ip ib iba ib Tps ip ib ip ib ib ib encoder 56 geartooth 60 gyro 60 i2c 61 nterfaces 123 nterfaces accelerometer 123 nterfaces controller 124 nterfaces counterbase 124 nterfaces generichid 125 nterfaces namedsendable 127 nterfaces pidoutput 127 nterfaces pidsource 127 nterfaces potentiometer 127 nterfaces speedcontroller 127 nterruptablesensorbase 63 iterativerobot 64 jaguar 66 joystick 67 livewindow 71 H H He H H H He H H H H lips livewindowsendable 72 wpi wpil ib lib motorsafety 73 wpi wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil ip ia ib ib ibs ib ip ib ibs ib ia ib ib ib ib ib pidcontroller 74 powerdistri
4. wpilib smartdashboard SmartDashboard static method 96 getBrakeEnableDuringNeutral wpilib cantalon CANTalon method 37 getBrightness wpilib impl dummycamera USB Camera method 12 13 getBumper wpilib interfaces generichid GenericHID method 125 method 41 getClosedLoopError method 37 getCloseLoopRampRate method 37 getCompressorCurrent wpilib compressor Compressor method 41 getCompressorCurrentTooHighFault wpilib compressor Compressor 42 getCompressorCurrentTooHighStickyFault wpilib compressor Compressor 42 getCompressorNotConnectedFault wpilib compressor Compressor 42 getCompressorNotConnectedStickyFault wpilib compressor Compressor 42 getCompressorShortedFault wpilib compressor Compressor 42 getCompressorShortedStickyFault wpilib compressor Compressor 42 getControlMode method 28 getControlMode wpilib cantalon CANTalon method 37 getCurrent wpilib powerdistributionpanel PowerDistributionPanel method 76 getCurrent3 V3 wpilib controllerpower ControllerPower static method 42 wpilib cantalon CANTalon wpilib cantalon CANTalon method method method method method method wpilib canjaguar CANJaguar Index 141 RobotPy WPILib Documentation Release master getCurrent5V wpilib controllerpower ControllerPower static method 43 getCurrent6V wpilib controllerpower ControllerPower static method 43 getCurre
5. Parameters command the command to cancel get Returns whether or not the trigger is active This method will be called repeatedly a command is linked to the Trigger Returns whether or not the trigger condition is active grab Returns whether get returns True or the internal table for Smart Dashboard use is pressed toggleWhenAct ive command Toggles a command when the trigger becomes active Parameters command the command to toggle whenActive command Starts the given command whenever the trigger just becomes active Parameters command the command to start whenInactive command Starts the command when the trigger becomes inactive Parameters command the command to start whileActive command Constantly starts the given command while the button is held Command start will be called repeatedly while the trigger is active and will be canceled when the trigger becomes inactive Parameters command the command to start 1 5 wpilib command Package Objects in this package allow you to implement a robot using Command based programming Command based pro gramming is a design pattern to help you organize your robot programs by organizing your robot program into components based on Command and Subsystem 1 5 wpilib command Package 111 RobotPy WPILib Documentation Release master The python implementation of the Command framework closely follows the Java language implementation Ro
6. Subsystems are used within the command system as requirements for Command Only one command which requires a subsystem can run at a time Also subsystems can have default commands which are started if there is no command running which requires this subsystem See also Command Creates a subsystem Parameters name the name of the subsystem if None it will be set to the name to the name of the class 1 5 wpilib command Package 121 RobotPy WPILib Documentation Release master confirmCommand Call this to alert Subsystem that the current command is actually the command Sometimes the Subsystem is told that it has no command while the Scheduler is going through the loop only to be soon after given a new one This will avoid that situation getCurrentCommand Returns the command which currently claims this subsystem Returns the command which currently claims this subsystem getDefaultCommand Returns the default command or None if there is none Returns the default command getName Returns the name of this subsystem which is by default the class name Returns the name of this subsystem initDefaultCommand Initialize the default command for a subsystem By default subsystems have no default command but if they do the default command is set with this method It is called on all Subsystems by CommandBase in the users program after all the Subsystems are created setCurrentCommand command Sets th
7. Return type float Raises KeyError if the key doesn t exist and defaultValue is not provided static get Int key defaultValue lt class wpilib smartdashboard SmartDashboard _defaultValueSentry gt Returns the value at the specified key Parameters e key str the key e defaultValue returned if the key doesn t exist Return type float Raises KeyError if the key doesn t exist and defaultValue is not provided static getNumber key defaultValue lt class wpilib smartdashboard SmartDashboard defaultValueSentry 5 Returns the value at the specified key Parameters e key str the key e defaultValue returned if the key doesn t exist Return type float Raises KeyError if the key doesn t exist and defaultValue is not provided static get String key defaultValue lt class wpilib smartdashboard SmartDashboard _defaultValueSentry gt Returns the value at the specified key Parameters e key str the key e defaultValue returned if the key doesn t exist Return type str Raises KeyError if the key doesn t exist and defaultValue is not provided 1 3 wpilib Package 97 RobotPy WPILib Documentation Release master static putBoolean key value Maps the specified key to the specified value in this table The key can not be None The value can be retrieved by calling the get method with a key that is egual to the original key Parameters e key str
8. Returns whether or not this group is interruptible A command group will be uninterruptible if setInter ruptable False was called or if it is currently running an uninterruptible command or child Returns whether or not this CommandGroup is interruptible 1 5 3 PIDCommand class woilib command PIDCommand p i d period None f 0 0 name None Bases woilib command Command This class defines a Command which interacts heavily with a PID loop It provides some convenience methods to run an internal PIDController It will also start and stop said PIDCon troller when the PIDCommand is first initialized and ended interrupted 116 Chapter 1 Contents RobotPy WPILib Documentation Release master Instantiates a PIDCommand that will use the given p i and d values It will use the class name as its name unless otherwise specified It will also space the time between PID loop calculations to be egual to the given period Parameters e p the proportional value e i the integral value e d the derivative value e period the time in seconds between calculations optional e f the feed forward value e name the name optional getPIDController Returns the PIDController used by this PIDCommand Use this if you would like to fine tune the pid loop Notice that calling setSetpoint on the controller will not result in the setpoint being trimmed to be in the range defined by setSetpointRange Returns the PIDC
9. 44 Chapter 1 Contents RobotPy WPILib Documentation Release master And to keep consistency with Java wpilib encodingType up source down source inverted If the passed object has a getChannelForRouting function it is assumed to be a DigitalSource If the passed object has a createOutput function it is assumed to be an AnalogTrigger In addition extra keyword parameters may be provided for mode inverted and encodingType Parameters upSource The source channel num DigitalInput or AnalogTrigger that should be used for up counting e downSource The source channel num DigitalInput or AnalogTrigger that should be used for down counting or direction control e mode How and what the counter counts see Mode Defaults to Mode kTwoPulse for zero or one source and Mode kExternalDirection for two sources inverted Flips the direction of counting Defaults to False if unspecified Only used when two sources are specified e encodingType Either k1X or k2X to indicate 1X or 2X decoding 4X decoding is not supported by Counter use Encoder instead Defaults to k1X if unspecified Only used when two sources are specified class EncodingType Bases builtins object The number of edges for the counterbase to increment or decrement on k1x 0 k2X 1 k4xX 2 class Counter Mode Bases builtins object Mode determines how and what the counter counts kExternalDirection 3 external direction mode
10. CANTalon getEncVelocity Get the current encoder velocity regardless of whether it is the current feedback device Returns The current speed of the encoder CANTalon getF CANTalon getFaultForLim CANTalon getFaultForSoftLinm CANTalon getFaultHardwareFailure CANTalon getFaultOverTemp CANTalon getFaultRevLim CANTalon getFaultRevSoftLin CANTalon getFaultUnderVoltage CANTalon getFirmwareVersion Returns The version of the firmware running on the Talon CANTalon getI CANTalon getIZone CANTalon getIaccum CANTalon getNumberOfQuadIdxRises Get the number of of rising edges seen on the index pin Returns number of rising edges on idx pin CANTalon getOutputCurrent Returns the current going through the Talon in Amperes CANTalon getOutputVoltage Returns The voltage being output by the Talon in Volts CANTalon getP Get the current proportional constant Returns double proportional constant for current profile CANTalon getPinStateQuadaA Returns IO level of QUADA pin CANTalon getPinStateQuacB Returns IO level of QUADB pin CANTalon getPinStateQuadIdx Returns IO level of QUAD Index pin CANTalon getPosition CANTalon getSensorPosition CANTalon getSensorVelocity 38 Chapter 1 Contents RobotPy WPILib Documentation Release master CANTalon getSetpoint Returns The latest value set using set CANTalon getSp
11. Default is no timeout See isTimedOut cancel This will cancel the current command This will cancel the current command eventually It can be called multiple times And it can be called when the command is not running If the command is running though then the command will be marked 112 Chapter 1 Contents RobotPy WPILib Documentation Release master as canceled and eventually removed Warning A command can not be canceled if it is a part of a CommandGroup you must cancel the CommandGroup instead doesRequire system Checks if the command requires the given Subsystem Parameters system the system Returns whether or not the subsystem is required or False if given None end Called when the command ended peacefully This is where you may want to wrap up loose ends like shutting off a motor that was being used in the command execute The execute method is called repeatedly until this Command either finishes or is canceled getGroup Returns the CommandGroup that this command is a part of Will return None if this Command is not in a group Returns the CommandGroup that this command is a part of or None if not in group getName Returns the name of this command If no name was specified in the constructor then the default is the name of the class Returns the name of this command getRequirements Returns the requirements as a set of Subsystems of this command initialize
12. Returns Current time value for this timer in seconds Return type float static get FPGATimestamp Return the system clock time in seconds Return the time from the FPGA hardware clock in seconds since the FPGA started Returns Robot running time in seconds Return type float static getMat chTime Return the approximate match time The FMS does not currently send the official match time to the robots This returns the time since the enable signal sent from the Driver Station At the beginning of autonomous the time is reset to 0 0 seconds At the beginning of teleop the time is reset to 15 0 seconds If the robot is disabled this returns 0 0 seconds Returns Match time in seconds since the beginning of autonomous Return type float getMsClock Returns the system clock time in milliseconds Return type int hasPeriodPassed period Check if the period specified has passed and if it has advance the start time by that period This is useful to decide if it s time to do periodic work without drifting later by the time it took to get around to checking Parameters period The period to check for in seconds Returns If the period has passed Return type bool reset Reset the timer by setting the time to 0 Make the timer startTime the current time so new requests will be relative now start Start the timer running Just set the running flag to true indicating that all time requests should be relative to the syst
13. The initialize method is called the first time this Command is run after being started interrupted Called when the command ends because somebody called cancel or another command shared the same requirements as this one and booted it out This is where you may want to wrap up loose ends like shutting off a motor that was being used in the command Generally it is useful to simply call the end method within this method isCanceled Returns whether or not this has been canceled Returns whether or not this has been canceled isFinished Returns whether this command is finished If it is then the command will be removed and end will be called It may be useful for a team to reference the isTimedOut method for time sensitive commands Returns whether this command is finished See isTimedOut isInterruptible Returns whether or not this command can be interrupted 1 5 wpilib command Package 113 RobotPy WPILib Documentation Release master Returns whether or not this command can be interrupted isRunning Returns whether or not the command is running This may return true even if the command has just been canceled as it may not have yet called interrupted Returns whether or not the command is running isTimedOut Returns whether or not the timeSinceInitialized method returns a number which is greater than or equal to the timeout for the command If there is no timeout this will always
14. channels wpilib digitalsource DigitalSource attribute 51 check wpilib motorsafety MotorSafety method 73 checkAnalogInputChannel wpilib sensorbase SensorBase static method 94 clearlaccum wpilib cantalon CANTalon method 36 BEaultsO wpilib cantalon CANTalon method 36 clearStickyFaults wpilib powerdistributionpanel PowerDistributionPanel method 76 clearUpSource wpilib counter Counter method 46 closeCamera wpilib impl dummycamera USBCamera method 12 13 wpilib canjaguar CANJaguar NeutralMode tribute 26 Command class in wpilib command command 112 CommandGroup class in wpilib command commandgroup 115 CommandGroup Entry class in wpilib command commandgroup 115 components wpilib livewindow LiveWindow attribute 72 Compressor class in wpilib compressor 41 configEncoderCodesPerRev wpilib canjaguar CANJaguar method 26 Coast at configFaultTime wpilib canjaguar CANJaguar method 26 configForwardLimit wpilib canjaguar CANJaguar method 26 configFwdLimitSwitchNormallyOpen wpilib cantalon CANTalon method 36 configLimitMode wpilib canjaguar CANJaguar method 26 configMaxOutputVoltage wpilib canjaguar CANJaguar method 26 138 Index RobotPy WPILib Documentation Release master configNeutralMode method 27 configPotentiometerTurns wpilib canjaguar CANJaguar method 27 configReverseLimit wpilib canjaguar CANJaguar method 27
15. kPulseLength 2 pulse length mode kSemiperiod 1 semi period mode kTwoPulse 0 two pulse mode class Counter PIDSourceParameter Bases builtins object A description for the type of output value to provide toa PIDController kAngle 2 kDistance 0 kRate 1 Counter allocatedDownSource False Counter allocatedUpSource False 1 3 wpilib Package 45 RobotPy WPILib Documentation Release master Counter clearDownSource Disable the down counting source to the counter Counter clearUpSource Disable the up counting source to the counter Counter counter Counter free Counter get Read the current counter value Read the value at this instant It may still be running so it reflects the current value Next time it is read it might have a different value Counter getDirection The last direction the counter value changed Returns The last direction the counter value changed Return type bool Counter getDistance Read the current scaled counter value Read the value at this instant scaled by the distance per pulse defaults to 1 Returns Scaled value Return type float Counter getFPGAIndex Returns The Counter s FPGA index Counter getPeriod Get the Period of the most recent count Returns the time interval of the most recent count This can be used for velocity calculations to determine shaft speed Returns The period of the last two pulses in units of seconds Return
16. 1023 full forward This includes demand which specifies duty cycle when in duty cycle mode and rampRamp which is in throttle units per 10ms if nonzero When in default PercentVBus mode set and get are automatically scaled to a 1 0 to 1 0 range to match other motor controllers Pos and velocity close loops are calc d as err target posOrVel iErr err if IZone 0 and abs err gt IZone ClearlIaccum output P x err I x iErr D dErr F target dErr err lastErr P I and D gains are always positive F can be negative Motor direction can be reversed using reverseOutput if sensor and motor are out of phase Similarly feedback sensor can also be reversed multiplied by 1 using reverseSensor 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 Ims 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 sam
17. For this reason a Com mand s requirements can not be changed after being added to a group It is recommended that this method be called in the constructor Parameters command The command to be added timeout The timeout in seconds optional CommandGroup addSequential command timeout None Adds a new Command to the group with an optional timeout The Command will be started after all the previously added Commands Once the Command is started it will be run until it finishes or the time expires whichever is sooner if a timeout is provided Note that the given Command will have no knowledge that it is on a timer Note that any requirements the given Command has will be added to the group For this reason a Com mand s requirements can not be changed after being added to a group It is recommended that this method be called in the constructor Parameters command The Command to be added e timeout The timeout in seconds optional CommandGrou CommandGrou CommandGrou CommandGrou CommandGrou CommandGrou p end p cancelConflicts command execute initialize interrupted isFinished Returns True if all the Commands in this group have been started and have finished Teams may override this method although they should probably reference super isFinished if they do Returns whether this CommandGroup is finished CommandGroup isInterruptible
18. Parameters degrees float The angle in degrees to set the servo 1 3 48 SmartDashboard class wwilib SmartDashboard Bases builtins object The bridge between robot programs and the SmartDashboard on the laptop When a value is put into the SmartDashboard it pops up on the SmartDashboard on the remote host Users can put values into and get values from the SmartDashboard These values can also be accessed by a NetworkTables client via the SmartDashboard table from networktables import NetworkTable sd NetworkTable getTable SmartDashboard sd putXXX and sd getXXX work as expected here static getBoolean key default Value class wpilib smartdashboard SmartDashboard _defaultValueSentry gt Returns the value at the specified key 96 Chapter 1 Contents RobotPy WPILib Documentation Release master Parameters e key str the key e defaultValue returned if the key doesn t exist Returns the value Raises KeyError if the key doesn t exist and defaultValue is not provided static getData key Returns the value at the specified key Parameters key str the key Returns the value Raises KeyError if the key doesn t exist static getDouble key defaultValue lt class wpilib smartdashboard SmartDashboard defaultValueSentry 5 Returns the value at the specified key Parameters e key str the key e defaultValue returned if the key doesn t exist
19. Programmer s Guide 9 RobotPy WPILib Documentation Release master Gazebo simulation This is currently experimental and will be updated in the coming weeks If you want to play with it now and help us fix the bugs check out the robotpy frcsim github repository Next steps Next we ll discuss some topic that will be decided upon in the future if someone writes more documentation here Until then remember that the FIRST documentation and our example programs are great resources to learn more about programming with WPILib 1 2 3 Simulation and Testing An important but often neglected part of developing your robot code is to test it Because we feel strongly about testing and simulation the RobotPy project provides tools to make those types of things easier through the pyfrc project To get started check out the pyfrc documentation 1 3 wpilib Package The WPI Robotics library WPILib is a set of classes that interfaces to the hardware in the FRC control system and your robot There are classes to handle sensors motors the driver station and a number of other utility functions like timing and field management The library is designed to e Deal with all the low level interfacing to these components so you can concentrate on solving this year s robot problem This is a philosophical decision to let you focus on the higher level design of your robot rather than deal with the details of the processor and the operat
20. attribute 57 attribute 11 13 kFixedOutdoor1 wpilib impl dummycamera USB Camera WhiteBalance attribute 11 13 kFixedOutdoor2 wpilib impl dummycamera USB Camera WhiteBalance attribute 12 13 kForward wpilib doublesolenoid DoubleSolenoid Value attribute 52 kForward wpilib relay Relay Direction attribute 83 kForward wpilib relay Relay Value attribute 84 kForwardLimit wpilib canjaguar CANJaguar attribute 29 kFrontLeft wpilib robotdrive RobotDrive MotorType at tribute 87 kFrontRight wpilib robotdrive RobotDrive MotorType attribute 87 kFullMessageIDMask wpilib canjaguar CANJaguar at tribute 29 kGateDriverFault tribute 29 kGearToothThreshold wpilib geartooth GearTooth at tribute 60 kGsPerLSB wpilib adx1345 i2c ADXL345 IRC at tribute 15 kGsPerLSB_ wpilib adx1345 spi ADXL345 SPI at tribute 17 kInches wpilib ultrasonic Ultrasonic Unit attribute 105 kIn Window wpilib analogtrigger Analog Trigger AnalogTriggerType attribute 22 kIn Window wpilib analogtriggeroutput AnalogTriggerOutput AnalogTrigg attribute 24 kJoystickPorts wpilib driverstation DriverStation at tribute 55 kLeft wpilib interfaces generichid GenericHID Hand at tribute 125 kLeftRumble val wpilib joystick Joystick RumbleType attribute 67 kMaxMessageDataSize wpilib canjaguar CANJaguar at wpilib canjaguar CANJaguar at kDistance wpilib interfaces pidsource PIDSource PIDSourceParamete ribute
21. channel direction None Bases woilib SensorBase Controls VEX Robotics Spike style relay outputs Relays are intended to be connected to Spikes or similar relays The relay channels controls a pair of pins that are either both off one on the other on or both on This translates into two Spike outputs at Ov one at 12v and one at Ov one at Ov and the other at 12v or two Spike outputs at 12V This allows off full forward or full reverse control of motors without variable speed It also allows the two channels forward and reverse to be used independently for something that does not care about voltage polarity like a solenoid Relay constructor given a channel Initially the relay is set to both lines at Ov Parameters e channel int The channel number for this relay 0 3 e direction Relay Direction The direction that the Relay object will control If not specified defaults to allowing both directions class Direction Bases builtins object The Direction s that a relay is configured to operate in kBoth 0 Both directions are valid kForward 1 Only forward is valid kReverse 2 Only reverse is valid 1 3 wpilib Package 83 RobotPy WPILib Documentation Release master class Relay Value Bases builtins object The state to drive a Relay to kForward 2 Forward koff 0 Off kon 1 On for relays with defined direction kReverse 3 Reverse Relay free Relay get Get the
22. configRevLimitS witchNormallyOpen wpilib cantalon CANTalon method 36 configSoftPositionLimits wpilib canjaguar CANJaguar method 27 wpilib canjaguar CANJaguar confirmCommand wpilib command subsystem Subsystem method 121 containsKey wpilib preferences Preferences method 77 Controller class in wpilib interfaces controller 124 ControllerPower class in wpilib controllerpower 42 Counter class in wpilib counter 44 counter wpilib counter Counter attribute 46 Counter EncodingType class in wpilib counter 45 Counter Mode class in wpilib counter 45 Counter PIDSourceParameter class in wpilib counter 45 CounterBase class in wpilib interfaces counterbase 124 CounterBase EncodingType class in wpilib interfaces counterbase 124 createOutput wpilib analogtrigger AnalogTrigger method 22 Current wpilib canjaguar CANJaguar ControlMode at tribute 25 Current wpilib cantalon CANTalon ControlMode at tribute 35 D decodingScaleFactor wpilib encoder Encoder method 57 DEFAULT wpilib sendablechooser SendableChooser at tribute 93 DEFAULT_SAFETY_EXPIRATION wpilib motorsafety MotorSafety 73 defaultSolenoidModule attribute 94 delay wpilib timer Timer static method 103 devices wpilib spi SPI attribute 101 DigitalInput class in wpilib digitalinput 49 DigitalOutput class in wpilib digitaloutput 50 DigitalSource class in wpilib digitalsource 51 disable wpi
23. e channel int The DIO channel index or DigitalSource that the sensor is connected to e directionSensitive bool True to enable the pulse length decoding in hardware to specify count direction Defaults to False enableDirectionSensing directionSensitive kGearToothThreshold 5 5e 05 1 3 24 Gyro class woilib Gyro channel Bases woilib SensorBase Interface to a gyro device via an AnalogInput Use a rate gyro to return the robots heading relative to a starting position The Gyro class tracks the robots heading based on the starting position As the robot rotates the new heading is computed by integrating the rate of rotation returned by the sensor When the class is instantiated it does a short calibration routine where it samples the gyro while at rest to determine the default offset This is subtracted from each sample to determine the heading Gyro constructor Also initializes the gyro Calibrate the gyro by running for a number of samples and computing the center value Then use the center value as the Accumulator center value for subsequent measurements It s important to make sure that the robot is not moving while the centering calculations are in progress this is typically done when the robot is first turned on while it s sitting at rest before the competition starts Parameters channel The analog channel index or AnalogInput object that the gyro is connected to Gyros can only be used on on board channe
24. outputValue is in volts In Current mode outputValue is in amperes In Speed mode outputValue is in position change 10ms In Position mode output Value is in encoder ticks or an analog value depending on the sensor Parameters outputValue The setpoint value as described above 1 3 wpilib Package 39 RobotPy WPILib Documentation Release master CANTalon setCloseLoopRampRate rampRate Set the closed loop ramp rate for the current profile Limits the rate at which the throttle will change Only affects position and speed closed loop modes Parameters rampRate Maximum change in voltage in volts sec See setProfile For selecting a certain profile CANTalon setD d Set the derivative constant of the currently selected profile Parameters d Derivative constant for the currently selected PID profile See setProfile For selecting a certain profile CANTalon setF f Set the feedforward value of the currently selected profile Parameters f Feedforward constant for the currently selected PID profile See setProfile For selecting a certain profile CANTalon setFeedbackDevice device CANTalon setForwardSoftLimit forwardLimit CANTalon setI i Set the integration constant of the currently selected profile Parameters i Integration constant for the currently selected PID profile See setProfile For selecting a certain profile CANTalon setIZone izone Set the integration zone of the c
25. robotpy feeds 2014 e Run this opkg install python3 e Then run this pip3 install pynivision robotpy hal roborio wpilib Note When powered off your RoboRIO does not keep track of the correct date and as a result pip may fail with an SSL related error message To set the date you can either e Set the date via the web interface e You can login to your roboRIO via SSH and set the date via the date command date s 2015 01 03 00 00 00 Upgrading requires you to run the same commands but with the appropriate flags set to tell pip3 opkg to upgrade the packages for you 4 Chapter 1 Contents RobotPy WPILib Documentation Release master 1 2 Programmer s Guide 1 2 1 Anatomy of a robot Note The following assumes you have some familiarity with python and is meant as a primer to creating robot code using the python version of wpilib If you re not familiar with python you might try these resources e CodeAcademy e Wikibooks python tutorial e Python 3 4 Tutorial This tutorial will go over the things necessary for very basic robot code that can run on an FRC robot using the python version of WPILib Code that is written for RobotPy can be ran on your PC using various simulation tools that are available Create your Robot code Your robot code must start within a file called robot py Your code can do anything a normal python program can such as importing other python modules amp packages Here are
26. should form an X across the robot Parameters magnitude The speed that the robot should drive in a given direction direction The direction the robot should drive in degrees The direction and maginitute are independent of the rotation rate rotation The rate of rotation for the robot that is completely independent of the magnitute or direction 1 0 1 0 static RobotDrive normalize wheelSpeeds Normalize all wheel speeds if the magnitude of any wheel is greater than 1 0 static RobotDrive rotateVector x y angle Rotate a vector in Cartesian space RobotDrive setCANJaguarSyncGroup syncGroup Set the number of the sync group for the motor controllers If the motor controllers are class CANJaguar s then they will be added to this sync group causing them to update their values at the same time 1 3 wpilib Package 89 RobotPy WPILib Documentation Release master Parameters syncGroup The update group to add the motor controllers to RobotDrive setInvertedMotor motor isInverted Invert a motor direction This is used when a motor should run in the opposite direction as the drive code would normally run it Motors that are direct drive would be inverted the drive code assumes that the motors are geared with one reversal Parameters e motor The motor index to invert e isInverted True if the motor should be inverted when operated RobotDrive setLeftRightMotorOutputs leftOutput r
27. wpilib canjaguar CANJaguar method 33 setVoltageModePotentiometer wpilib canjaguar CANJaguar method 33 set VoltageModeQuadEncoder wpilib canjaguar CANJaguar method 33 wpilib canjaguar CANJaguar wpilib canjaguar CANJaguar method 34 setVoltageRampRate method 41 wpilib cantalon CANTalon setWhiteBalanceAuto wpilib impl dummycamera USB Camera method 12 13 setWhiteBalanceHoldCurrent wpilib _impl dummycamera USBCamera method 12 14 setSetpoint wpilib command pidsubsystem PIDSubsystensetWhiteBalanceManual method 119 setSetpoint wpilib pidcontroller PIDController method 76 wpilib _impl dummycamera USBCamera method 12 14 154 Index RobotPy WPILib Documentation Release master setZero wpilib analogaccelerometer AnalogAccelerometeTABLE NAME method 18 setZeroLatch wpilib pwm PWM method 83 SmartDashboard class in wpilib smartdashboard 96 wpilib preferences Preferences at tribute 77 tablesToData Wwpilib smartdashboard SmartDashboard attribute 98 SoftPositionLimits wpilib canjaguar CANJaguar LimitModdalon class in wpilib talon 102 attribute 25 Solenoid class in wpilib solenoid 99 SolenoidBase class in wpilib solenoidbase 99 Speed wpilib canjaguar CAN Jaguar ControlMode attribute 25 Speed wpilib cantalon CANTalon ControlMode at tribute 36 SpeedController class in wpilib interfaces speedcontroller 127 SPI
28. wpilib canjaguar CANJaguar method 30 requires wpilib command command Command method 114 reset wpilib counter Counter method 47 reset wpilib encoder Encoder method 58 reset wpilib gyro Gyro method 61 reset wpilib interfaces counterbase CounterBase method 125 reset wpilib pidcontroller PIDController method 75 reset wpilib timer Timer method 104 resetAccumulator wpilib analoginput AnalogInput method 20 resetTotalEnergy wpilib powerdistributionpanel PowerDistributionPanel method 77 Resource class in wpilib resource 84 returnPIDInput wpilib command pidcommand PIDCommand method 117 Index 151 RobotPy WPILib Documentation Release master returnPIDInput wpilib command pidsubsystem PIDSubsyset wpilib victorsp VictorSP method 109 method 118 reverseOutput wpilib cantalon CANTalon method 39 reverseSensor wpilib cantalon CANTalon method 39 RobotBase class in wpilib robotbase 85 RobotDrive class in wpilib robotdrive 87 RobotDrive MotorType class in wpilib robotdrive 87 robotInit wpilib iterativerobot IterativeRobot method 65 robotInit wpilib samplerobot SampleRobot method 92 robotMain wpilib samplerobot SampleRobot method 92 RobotState class in wpilib robotstate 91 rotateVector Wpilib robotdrive RobotDrive static method 89 run wpilib command command Command method 114 run wpilib command scheduler Sched
29. 17 kPowerCtl Link wpilib adx1345 i2c ADXL345 I2C at tribute 16 kPowerCtl Link wpilib adx1345 spi ADXL345 SPI at tribute 17 kPowerCtl_Measure wpilib adx1345 i2c ADXL345 I2C attribute 16 kPowerCtl_Measure wpilib adx1345 spi ADXL345 SPI attribute 17 kPowerCtI Sleep wpilib adx1345 i2c ADXL345 RC at tribute 16 kPowerCtl Sleep wpilib adx1345 spi ADXL345 SPI at tribute 17 kPowerCtlRegister wpilib adx1345 i2c ADXL345 I2C attribute 15 kPowerCtlRegister wpilib adx1345 spi ADXL345 SPI attribute 17 kPriority wpilib ultrasonic Ultrasonic attribute 106 kPulseLength wpilib counter Counter Mode attribute 45 kPwmChannels wpilib sensorbase SensorBase attribute 95 kPwmDisabled wpilib pwm PWM attribute 82 kOuadEncoder wpilib canjaguar CANJaguar Mode at tribute 26 30 wpilib interfaces generichid GenericHID Hand attribute 125 kRightRumble_val wpilib joystick Joystick RumbleType attribute 67 kRisingPulse wpilib analogtrigger Analog Trigger Analog TriggerType attribute 22 kRisingPulse wpilib analogtriggeroutput AnalogTriggerOutput AnalogTrig attribute 24 kSamplesPerSecond wpilib gyro Gyro attribute 61 kSemiperiod wpilib counter Counter Mode attribute 45 kSendMessagePeriod wpilib canjaguar CANJaguar at tribute 30 kSize 160x120 wpilib impl dummycamera CameraServer attribute 12 14 kSize320x240 wpilib _impl dummycamera CameraServer attribute 12 14 kSize640x480 wpili
30. 30 attribute 127 kEncoder wpilib canjaguar CANJaguar Mode attribute kMaxNumberOfMotors attribute 89 wpilib robotdrive RobotDrive 25 kMaxServoAngle wpilib servo Servo attribute 96 kExternalDirection wpilib counter CounterMode at kMaxUltrasonicTime wpilib ultrasonic Ultrasonic tribute 45 attribute 106 keys wpilib preferences Preferences method 79 kMecanumCartesian_Reported kFallingPulse wpilib analogtrigger AnalogTrigger AnalogTriggerTyp wpilib robotdrive RobotDrive attribute attribute 22 89 kFallingPulse wpilib analogtriggeroutput AnalogTriggerOukMecaminmP hia Rdpprted attribute 24 wpilib robotdrive RobotDrive attribute 89 148 Index RobotPy WPILib Documentation Release master kMillimeters wpilib ultrasonic Ultrasonic Unit attribute 105 kMinServoAngle wpilib servo Servo attribute 96 kMXP wpilib i2c 12C Port attribute 62 kMXP wpilib spi SPI Port attribute 100 kNumAxis wpilib joystick Joystick AxisType attribute 67 kNumButton wpilib joystick Joystick ButtonType attribute 67 kOff wpilib doublesolenoid DoubleSolenoid Value at tribute 52 kOff wpilib relay Relay Value attribute 84 kOn wpilib relay Relay Value attribute 84 kOnboard wpilib i2c I2C Port attribute 62 kOnboardCSO wpilib spi SPI Port attribute 100 kOnboardCSI wpilib spi SPI Port attribute 100 kOnboardCS2 wpilib spi SPI Port attribute 100 kOnboardCS3 wpilib spi SPI Port at
31. 88 getInputVoltagel wpilib controllerpower ControllerPower getOffset wpilib analoginput AnalogInput method 19 static method 44 getInstance wpilib impl dummycamera CameraServer static method 12 14 getInstance wpilib command scheduler Scheduler static method 120 getInstance wpilib driverstation DriverStation static method 53 getInstance wpilib preferences Preferences static method 78 getInt wpilib preferences Preferences method 78 getInt wpilib smartdashboard SmartDashboard static method 97 getInWindow wpilib analogtrigger AnalogTrigger method 22 getIZone wpilib cantalon CANTalon method 38 getKeys wpilib preferences Preferences method 78 getLocation wpilib driverstation DriverStation method 53 getLSBWeight wpilib analoginput AnalogInput method 19 getMagnitude wpilib joystick Joystick method 68 getMatchTime wpilib driverstation DriverStation method 53 getMatchTime wpilib timer Timer static method 104 getMaxNegativePwm wpilib pwm PWM method 81 getMaxPositivePwm wpilib pwm PWM method 81 getMessage wpilib canjaguar CANJaguar method 29 getMinNegativePwm wpilib pwm PWM method 81 getMinPositivePwm wpilib pwm PWM method 81 getOutputCurrent wpilib canjaguar CANJaguar method 29 getOutputCurrent wpilib cantalon CANTalon method 38 getOutputVoltage wpilib canjaguar CANJaguar method 29 getOutputVolt
32. 93 P PercentageTolerance_onTarget wpilib pidcontroller PIDController 74 PercentVbus wpilib canjaguar CANJaguar ControlMode attribute 25 PercentVbus wpilib cantalon CANTalon ControlMode attribute 35 PIDCommand class in wpilib command pidcommand 116 PIDController class in wpilib pidcontroller 74 pidGet wpilib analogaccelerometer AnalogAccelerometer method 18 pidGet wpilib analoginput AnalogInput method 20 pidGet wpilib analogpotentiometer AnalogPotentiometer method 21 pidGet wpilib counter Counter method 47 pidGet wpilib encoder Encoder method 58 pidGet wpilib gyro Gyro method 61 pidGet wpilib interfaces pidsource PIDSource method 127 pidGet wpilib ultrasonic Ultrasonic method 106 PIDOutput class in wpilib interfaces pidoutput 127 PIDSource class in wpilib interfaces pidsource 127 PIDSource PIDSourceParameter class in wpilib interfaces pidsource 127 method 150 Index RobotPy WPILib Documentation Release master PIDSubsystem class in wpilib command pidsubsystem 118 pid Write wpilib canjaguar CANJaguar method 30 pid Write wpilib cantalon CANTalon method 39 pidWrite wpilib interfaces pidoutput PIDOutput method 127 pidWrite wpilib jaguar Jaguar method 66 pidWrite wpilib talon Talon method 102 pidWrite wpilib talonsrx TalonSRX method 103 pidWriteQ wpilib victor Victor method 108 pid Write wp
33. By default kDefaultMaxServoPWM ms is used as the maxPWM value By default kDefaultMinServoPWM ms is used as the minPWM value Parameters channel int The PWM channel to which the servo is attached 0 9 are on board 10 19 are on the MXP port 1 3 wpilib Package 95 RobotPy WPILib Documentation Release master get Get the servo position Servo values range from 0 0 to 1 0 corresponding to the range of full left to full right Returns Position from 0 0 to 1 0 Return type float getAngle Get the servo angle Assume that the servo angle is linear with respect to the PWM value big assumption need to test Returns The angle in degrees to which the servo is set Return type float getServoAngleRange kDefaultMaxServoPWM 2 4 kDefaultMinServoPWM 0 6 kMaxServoAngle 180 0 kMinServoAngle 0 0 set value Set the servo position Servo values range from 0 0 to 1 0 corresponding to the range of full left to full right Parameters value float Position from 0 0 to 1 0 setAngle degrees Set the servo angle Assumes that the servo angle is linear with respect to the PWM value big assumption need to test Servo angles that are out of the supported range of the servo simply saturate in that direction In other words if the servo has a range of X degrees to Y degrees than angles of less than X result in an angle of X being set and angles of more than Y degrees result in an angle of Y being set
34. FPGA Parameters e speed float The speed to set Value should be between 1 0 and 1 0 e syncGroup The update group to add this set to pending updateSyncGroup If 0 update immediately 1 3 54 Timer class woilib Timer Bases builtins object Provides time related functionality for the robot Note Prefer to use this module for time functions instead of the t ime module in the standard library This will make it easier for your code to work properly in simulation static delay seconds Pause the thread for a specified time Pause the execution of the thread for a specified period of time given in seconds Motors will continue to run at their last assigned values and sensors will continue to update Only the thread containing the wait will pause until the wait time is expired 1 3 wpilib Package 103 RobotPy WPILib Documentation Release master Parameters seconds float Length of time to pause Warning If you re tempted to use this function for autonomous mode to time transitions between actions don t do it Delaying the main robot thread for more than a few milliseconds is generally discouraged and will cause problems and possibly leave the robot unresponsive get Get the current time from the timer If the clock is running it is derived from the current system clock the start time stored in the timer class If the clock is not running then return the time when it was last stopped
35. Get the input current to the robot controller Returns The controller input current value in Amps Return type float static getInputVoltage Get the input voltage to the robot controller Returns The controller input voltage value in Volts Return type float static getVoltage3V3 Get the voltage of the 3 3V rail Returns The controller 3 3V rail voltage value in Volts Return type float static getvVoltage5V Get the voltage of the 5V rail Returns The controller 5V rail voltage value in Volts Return type float static get Voltage6V Get the voltage of the 6V rail Returns The controller 6V rail voltage value in Volts Return type float 1 3 16 Counter class woilib Counter args kwargs Bases woilib SensorBase Counts the number of ticks on a DigitalInput channel This is a general purpose class for counting repetitive events It can return the number of counts the period of the most recent cycle and detect when the signal being counted has stopped by supplying a maximum cycle time All counters will immediately start counting reset them if you need them to be zeroed before use Counter constructor The counter will start counting immediately Positional arguments may be either channel numbers DigitalSource sources or AnalogTrigger sources in the following order A source is any valid single argument input to set UpSource and setDownSource none upSource supSource down source
36. Get the recently set outputValue set point The scale and the units depend on the mode the Jaguar is in In percentVbus mode the outputValue is from 1 0 to 1 0 same as PWM Jaguar In voltage mode the outputValue is in volts In current mode the outputValue is in amps In speed mode the outputValue is in rotations minute In position mode the outputValue is in rotations Returns The most recently set outputValue set point CANJaguar getBusVoltage Get the voltage at the battery input terminals of the Jaguar Returns The bus voltage in Volts CANJaguar getControlMode Get the active control mode from the Jaguar Ask the Jagaur what mode it is in Return ControlMode that the Jag is in CANJaguar getD Get the Derivative gain of the controller Returns The derivative gain CANJaguar getDescription CANJaguar getDevicelD CANJaguar getDeviceNumber Returns The CAN ID passed in the constructor CANJaguar getFaults Get the status of any faults the Jaguar has detected Returns A bit mask of faults defined by the Faults constants e kCurrentFault e kBusVoltageFault e kTemperatureFault e GateDriverFault CANJaguar getFirmwareVersion Get the version of the firmware running on the Jaguar Returns The firmware version 0 if the device did not respond CANJaguar getForwardLimitOK Get the status of the forward limit switch Returns True if the motor is allowed to turn
37. If the passed object has a createOutput function it is assumed to be an AnalogTrigger Alternatively sources and or channels may be passed as keyword arguments The behavior of specifying both a source and a number for the same channel is undefined as is passing both a positional and a keyword argument for the same channel 48 Chapter 1 Contents RobotPy WPILib Documentation Release master Parameters e channel int the DIO channel to use as the up source 0 9 are on board 10 25 are on the MXP e source DigitalInput The digital source to count e analogTrigger AnalogTrigger The analog trigger object that is used for the Up Source e triggerType AnalogTriggerType The analog trigger output that will trigger the counter Defaults to kState if not specified Counter setUpSourceEdge risingEdge fallingEdge Set the edge sensitivity on an up counting source Set the up source to either detect rising edges or falling edges Parameters e risingEdge bool True to count rising edge e fallingEdge bool True to count falling edge Counter setUpdateWhenEmpty enabled Select whether you want to continue updating the event timer output when there are no samples captured The output of the event timer has a buffer of periods that are averaged and posted to a register on the FPGA When the timer detects that the event source has stopped based on the MaxPeriod the buffer of samples to be averaged is emp
38. Parameters hand which hand default right Returns True if the bumper is pressed GenericHID getPOV pov 0 Get the state of a POV 1 6 wpilib interfaces Package 125 RobotPy WPILib Documentation Release master Parameters pov which POV default is 0 Returns The angle of the POV in degrees or 1 if the POV is not pressed GenericHID getRawAxis which Get the raw axis Parameters which index of the axis Returns the raw value of the selected axis GenericHID getRawButton button Is the given button pressed Parameters button which button number Returns True if the button is pressed GenericHID getThrottle Get the throttle Returns the throttle value GenericHID getTop hand None Is the top button pressed Parameters hand which hand default right Returns True if the top button for the given hand is pressed GenericHID getTrigger hand None Is the trigger pressed Parameters hand which hand default right Returns True if the trigger for the given hand is pressed GenericHID getTwist Get the twist value Returns the twist value GenericHID getX hand None Get the x position of HID Parameters hand which hand left or right default right Returns the x position GenericHID getY hand None Get the y position of the HID Parameters hand which hand left or right default right Returns the y position GenericHID getZ hand None Get the z position of the H
39. Road Electronics CTRE Talon and Talon SR Speed Controller via PW wpilib TalonSRX channel Cross the Road Electronics CTRE Talon SRX Speed Controller via PWM wpilib TimerQ Provides time related functionality for the robot wpilib Ultrasonic pingChannel Ultrasonic rangefinder control wpilib Utility Contains global utility functions wpilib Victor channel VEX Robotics Victor 888 Speed Controller via PWM wpilib VictorSP channel VEX Robotics Victor SP Speed Controller via PWM 1 31 CameraServer class woilib _impl USBCamera name None Bases builtins object class WhiteBalance Bases builtins object kFixedFlourescent2 5200 kFixedFluorescent1 5100 kFixedIndoor 3000 1 3 wpilib Package 11 RobotPy WPILib Documentation Release master kFixedOutdoorl1 4000 kFixedOutdoor2 5000 USBCamera closeCamera USBCamera getBrightness Get the brightness as a percentage 0 100 USBCamera getImage image USBCamera getImageData data maxsize USBCamera kDefaultCameraName b cam0 USBCamera openCamera USBCamera setBrightness brightness Set the brightness as a percentage 0 100 USBCamera setExposureAuto Set the exposure to auto aperature USBCamera setExposureHoldCurrent Set the exposure to hold current USBCamera setExposureManual value Set the exposure to manual as a percentage 0 100 USBCamera setFPS fps USBCamera setSize width height USBCamera setWhiteBalanceAuto Se
40. WPILib Documentation Release master used for tracking allocation of hardware channels but this is purely arbitrary The resource class does not do any actual allocation but simply tracks if a given index is currently in use Allocate storage for a new instance of Resource Allocate a bool array of values that will get initialized to indicate that no resources have been allocated yet The indicies of the resources are 0 size 1 Parameters size The number of blocks to allocate allocate obj index None Allocate a resource When index is None or unspecified a free resource value within the range is located and returned after it is marked allocated Otherwise it is verified unallocated then returned Parameters obj The object requesting the resource e index The resource to allocate Returns The index of the allocated block Raises IndexError If there are no resources available to be allocated or the specified index is already used free index Force free an allocated resource After a resource is no longer needed for example a destructor is called for a channel assignment class free will release the resource value so it can be reused somewhere else in the program Parameters index The index of the resource to free 1 3 39 RobotBase class wpilib RobotBase Bases builtins object Implement a Robot Program framework The RobotBase class is intended to be subclassed by a user creating a robot program O
41. as keyword arguments The behavior of mixes of keyword arguments in other than the combinations above is undefined If specified positionally the value and joystick versions are disambiguated by looking for a getY function Parameters e leftStick The joystick to control the left side of the robot 90 Chapter 1 Contents RobotPy WPILib Documentation Release master leftAxis The axis to select on the left side Joystick object defaults to the Y axis if unspecified rightStick The joystick to control the right side of the robot rightAxis The axis to select on the right side Joystick object defaults to the Y axis if unspecified leftValue The value to control the left side of the robot right Value The value to control the right side of the robot squaredInputs Setting this parameter to True decreases the sensitivity at lower speeds Defaults to True if unspecified 1 3 41 RobotState class woilib RobotState Bases builtins object Provides an interface to determine the current operating state of the robot code imp1 None static isAutonomous static isDisabled static isEnabled static isOperatorControl static isTest 1 3 42 SafePWM class wpilib SafePWM channel Bases wpilib PWM woilib MotorSafety A raw PWM interface that implements the Mot orSafety interface Constructor for a SafePWM object taking a channel number Parameters channel int The channel
42. can be used to build more advanced classes for control and driving All counters will immediately start counting reset them if you need them to be zeroed before use class EncodingType Bases builtins object The number of edges for the counterbase to increment or decrement on 124 Chapter 1 Contents RobotPy WPILib Documentation Release master k1x 0 Count only the rising edge k2x 1 Count both the rising and falling edge k4x 2 Count rising and falling on both channels CounterBase get Get the count Returns the count CounterBase getDirection Determine which direction the counter is going Returns True for one direction False for the other CounterBase getPeriod Get the time between the last two edges counted Returns the time beteween the last two ticks in seconds CounterBase getStopped Determine if the counter is not moving Returns True if the counter has not changed for the max period CounterBase reset Reset the count to zero CounterBase setMaxPeriod maxPeriod Set the maximum time between edges to be considered stalled Parameters maxPeriod the maximum period in seconds 1 6 4 GenericHID class woilib interfaces GenericHID Bases builtins object GenericHID Interface class Hand Bases builtins object Which hand the Human Interface Device is associated with kLeft 0 Left hand kRight 1 Right hand GenericHID getBumper hand None Is the bumper pressed
43. channel The channel number to check static checkSolenoidModule moduleNumber Verify that the solenoid module is correct Parameters moduleNumber The solenoid module module number to check 94 Chapter 1 Contents RobotPy WPILib Documentation Release master defaultSolenoidModule 0 Default solenoid module free Free the resources used by this object static getDefaultSolenoidModule Get the number of the default solenoid module Returns The number of the default solenoid module kAnalogInputChannels Number of analog input channels kAnalogOutputChannels 2 Number of analog output channels kDigitalChannels 26 Number of digital channels per roboRIO kPDPChannels 16 Number of power distribution channels kPwmChannels 20 Number of PWM channels per roboRIO kRelayChannels 4 Number of relay channels per roboRIO kSolenoidChannels 8 Number of solenoid channels per module kSolenoidModules 2 Number of solenoid modules kSystemClockTicksPerMicrosecond 40 Ticks per microsecond static setDefaultSolenoidModule moduleNumber Set the default location for the Solenoid module Parameters moduleNumber The number of the solenoid module to use 1 3 47 Servo class wpilib Servo channel Bases woilib PWM Standard hobby style servo The range parameters default to the appropriate values for the Hitec HS 322HD servo provided in the FIRST Kit of Parts in 2008 Constructor
44. get Get the recently set value of the PWM Returns The most recently set value for the PWM between 1 0 and 1 0 Return type float pidWrite output Write out the PID value as seen in the PIDOutput base object Parameters output float Write out the PWM value as was found in the PIDCont roller set speed syncGroup 0 Set the PWM value The PWM value is set using a range of 1 0 to 1 0 appropriately scaling the value for the FPGA Parameters e speed float The speed to set Value should be between 1 0 and 1 0 e syncGroup The update group to add this set to pending updateSyncGroup If 0 update immediately 1 4 wpilib buttons Package Classes in this package are used to interface various types of buttons to a command based robot If you are not using the Command framework you can ignore these classes wpilib buttons Button This class provides an easy way to link commands to OI inputs wpilib buttons InternalButton This class is intended to be used within a program wpilib buttons JoystickButtonf Create a joystick button for triggering commands wpilib buttons NetworkButton wpilib buttons Trigger This class provides an easy way to link commands to inputs 1 4 1 Button class wpilib buttons Button Bases wpilib buttons Trigger This class provides an easy way to link commands to Ol inputs It is very easy to link a button to a command For instance you could link the trigger bu
45. in g forces ADXL345 I2C getY Get the y axis acceleration Returns The acceleration along the y axis in g forces ADXL345 I2C getZ Get the z axis acceleration Returns The acceleration along the z axis in g forces DXL345 I2C kAddress 29 DXL345 I2C kDataFormatRegister 49 DXL345 I2C kDataFormat FullRes DXL345 I2C kDataFormat IntInvert 32 DXL345 I2C kDataFormat Justify 4 DXL345 I2C kDataFormat SPI 64 DXL345 I2C kDataFormat SelfTest 128 DXL345 I2C kDataRegister 50 gt Pp PP D p SP PSP p H DXL345_12C kGsPerLSB 0 00390625 1 3 wpilib Package 15 RobotPy WPILib Documentation Release master DXL345 I2C kPowerCtlRegister 45 DXL345 I2C kPowerCtl1 AutoSleep 16 DXL345 I2C kPowerCtl Link 32 DXL345 I2C kPowerCtl Measure 8 DXL345_I2C kPowerCtl_Sleep 4 gt D gt Pp Pp P P DXL345_I2C setRange range Set the measuring range of the accelerometer Parameters range ADXL345 I2C Range The maximum acceleration positive or nega tive that the accelerometer will measure 1 3 4 ADXL345_SPI class woilib ADXL345_SPI port range Bases woilib SensorBase ADXL345 accelerometer device via spi Constructor Use this when the device is the first only device on the bus Parameters e port The SPI port that the accelerometer is connected to e range The range or that the accelerometer will measure class Axes Bases builtins object kx 0 ky 2 kzZz 4 class A
46. in this scale The library already compensates for the decoding type Set this value based on the encoder s rated Pulses per Revo lution and factor in gearing reductions following the encoder shaft This distance can be in any units you like linear or angular Parameters distancePerPulse The scale factor that will be used to convert pulses to useful units Encoder setIndexSource source indexing type 3 Set the index source for the encoder When this source rises the encoder count automatically resets Parameters e source Either an initialized DigitalSource or a DIO channel number e indexing type The state that will cause the encoder to reset Type Either a DigitalInput or number Type A value from wpilib IndexingType Encoder setMaxPeriod maxPeriod Sets the maximum period for stopped detection Sets the value that represents the maximum period of the Encoder before it will assume that the attached device is stopped This timeout allows users to determine if the wheels or other shaft has stopped rotating This method compensates for the decoding type Parameters maxPeriod The maximum time between rising and falling edges before the FPGA will report the device stopped This is expressed in seconds Encoder setMinRate minRate Set the minimum rate of the device before the hardware reports it stopped Parameters minRate The minimum rate The units are in distance per second as scaled by the value from
47. master startCompetition Provide an alternate main loop via startCompetition teleopInit Initialization code for teleop mode should go here Users should override this method for initialization code which will be called each time the robot enters teleop mode teleopPeriodic Periodic code for teleop mode should go here Users should override this method for code which will be called periodically at a regular rate while the robot is in teleop mode testInit Initialization code for test mode should go here Users should override this method for initialization code which will be called each time the robot enters test mode testPeriodic Periodic code for test mode should go here Users should override this method for code which will be called periodically at a regular rate while the robot is in test mode 1 3 28 Jaguar class wpilib Jaguar channel Bases woilib SafePWM Texas Instruments Vex Robotics Jaguar Speed Controller as a PWM device See also CANJaguar for CAN control of a Jaguar Constructor Parameters channel The PWM channel that the Jaguar is attached to 0 9 are on board 10 19 are on the MXP port get Get the recently set value of the PWM Returns The most recently set value for the PWM between 1 0 and 1 0 Return type float pidWrite output Write out the PID value as seen in the PIDOutput base object Parameters output float Write out the PWM value as was fou
48. of the USER button on the RoboRIO Returns True if the button is currently pressed down Return type bool 1 3 57 Victor class wpilib Victor channel Bases woilib SafePWM VEX Robotics Victor 888 Speed Controller via PWM The Vex Robotics Victor 884 Speed Controller can also be used with this class but may need to be calibrated per the Victor 884 user manual Note The Victor uses the following bounds for PWM values These values were determined empirically and optimized for the Victor 888 These values should work reasonably well for Victor 884 controllers also but if users experience issues such as asymmetric behaviour around the deadband or inability to saturate the controller in either direction calibration is recommended The calibration procedure can be found in the Victor 884 User Manual available from VEX Robotics http content vexrobotics com docs ifi v884 users manual 9 25 06 pdf 2 027ms full forward 1 525ms the high end of the deadband range 1 3 wpilib Package 107 RobotPy WPILib Documentation Release master 1 507ms center of the deadband range off 1 49ms the low end of the deadband range 1 026ms full reverse Constructor Parameters channel int The PWM channel that the Victor is attached to 0 9 are on board 10 19 are on the MXP port get Get the recently set value of the PWM Returns The most recently set value for the PWM between 1
49. output channel There can only be a single pulse going at any time Parameters e channel The channel to pulse e pulseLength float The length of the pulse pwmGenerator set value Set the value of a digital output Parameters value bool True is on off is False 50 Chapter 1 Contents RobotPy WPILib Documentation Release master setPWMRate rate Change the PWM freguency of the PWM output on a Digital Output line The valid range is from 0 6 Hz to 19 kHz The freguency resolution is logarithmic There is only one PWM freguency for all channnels Parameters rate float The frequency to output all digital output PWM signals updateDutyCycle dutyCycle Change the duty cycle that is being generated on the line The resolution of the duty cycle is 8 bit for low frequencies 1kHz or less but is reduced the higher the frequency of the PWM signal is Parameters dutyCycle float The duty cycle to change to 0 1 1 3 19 DigitalSource class wpilib DigitalSource channel input Bases wpilib InterruptableSensorBase DigitalSource Interface The DigitalSource represents all the possible inputs for a counter or a guadrature encoder The source may be either a digital input or an analog input If the caller just provides a channel then a digital input will be constructed and freed when finished for the source The source can either be a digital input or analog trigger but not both Parameters
50. set the boolean at position S A V E to true Also if the value of any variable is in the NetworkTable then that represents non existence in the Preferences table Creates a preference class that will automatically read the file in a different thread Any call to its methods will be blocked until the thread is finished reading FILE NAME home Ivuser wpilib preferences ini NEW_LINE n SAVE_FIELD S A V E TABLE_NAME Preferences VALUE PREFIX VALUE_SUFFIX An containsKey key Returns whether or not there is a key with the given name Parameters key the key Returns True if there is a value at the given key 1 3 wpilib Package 77 RobotPy WPILib Documentation Release master get key d None Returns the value at the given key Parameters e key the key e d the return value if the key doesn t exist default is None Returns the value or d None if none exists getBoolean key backup Returns the boolean at the given key If this table does not have a value for that position then the given backup value will be returned Parameters e key the key e backup the value to return if none exists in the table Returns either the value in the table or the backup Raises ValueError if value cannot be converted to integer getFloat key backup Returns the float at the given key If this table does not have a value for that position then the giv
51. should overload this method to run code that should run while the field is disabled Called once each time the robot enters the disabled state logger lt logging Logger object at 0x7f2574e50f98 gt A python logging object that you can use to send messages to the log It is recommended to use this instead of print statements operatorControl Operator control tele operated code should go here Users should add Operator Control code to this method that should run while the field is in the Operator Control tele operated period Called once each time the robot enters the operator controlled state robotInit Robot wide initialization code should go here Users should override this method for default Robot wide initialization which will be called when the robot is first powered on It will be called exactly time Note It is simpler to override this function instead of defining a constructor for your robot class robotMain Robot main program for free form programs This should be overridden by user subclasses if the intent is to not use the autonomous and operator Control methods In that case the program is responsible for sensing when to run the autonomous and operator control functions in their program This method will be called immediately after the constructor is called If it has not been overridden by a user subclass i e the default version runs then the robotInit disabled autonomous and operat
52. supporting a second module other than the default clearAl1lPCMStickyFaults enabled Get the enabled status of the compressor Returns True if the compressor is on Return type bool getClosedLoopControl Gets the current operating mode of the PCM Returns True if compressor is operating on closed loop mode otherwise return False Return type bool 1 3 wpilib Package 41 RobotPy WPILib Documentation Release master getCompressorCurrent Get the current being used by the compressor Returns Current consumed in amps for the compressor motor Return type float getCompressorCurrentTooHighFault Returns True if PCM is in fault state Compressor Drive is disabled due to compressor current being too high getCompressorCurrentTooHighStickyFault Returns True if PCM sticky fault is set Compressor Drive is disabled due to compressor current being too high getCompressorNotConnectedFault Returns True if PCM is in fault state Compressor does not appear to be wired i e compressor is not drawing enough current getCompressorNotConnectedStickyFault Returns True if PCM sticky fault is set Compressor does not appear to be wired i e compres sor is not drawing enough current getCompressorShortedFault Returns True if PCM is in fault state Compressor Output appears to be shorted getCompressorShortedStickyFault Returns True if PCM sticky fault is set Compressor Output appears to be shor
53. the basic things you need to know to get your robot code working Importing necessary modules All of the code that actually interacts with your robot s hardware is contained in a library called WPILib This library was originally implemented in C and Java Your robot code must import this library module and create various objects that can be used to interface with the robot hardware To import wpilib it s just as simple as this import wpilib Note Because RobotPy implements the same WPILib as C Java you can learn a lot about how to write robot code from the many C Java focused WPILib resources that already exist including FIRST s official documentation Just translate the code into python Robot object Every valid robot program must define a robot object that inherits from either woilib IterativeRobot or wpilib SampleRobot These objects define a number of functions that you need to override which get called at various times e wpilib IterativeRobot functions e wpilib SampleRobot functions Note It is recommended that inexperienced programmers use the IterativeRobot framework which is what this guide will discuss An incomplete version of your robot object might look like this 1 2 Programmer s Guide 5 RobotPy WPILib Documentation Release master class MyRobot wpilib IterativeRobot def robotInit self self motor wpilib Jaguar 1 The robotInit function is where you initia
54. the key e value the value static putData args kwargs Maps the specified key to the specified value in this table The value can be retrieved by calling the get method with a key that is egual to the original key Two argument formats are supported key data Parameters e key str the key cannot be None e data the value Or the single argument value Parameters value the named value getName is called to retrieve the value static putDouble key value Maps the specified key to the specified value in this table The key can not be None The value can be retrieved by calling the get method with a key that is egual to the original key Parameters e key str the key e value int or float the value static putInt key value Maps the specified key to the specified value in this table The key can not be None The value can be retrieved by calling the get method with a key that is egual to the original key Parameters e key str the key e value int or float the value static putNumber key value Maps the specified key to the specified value in this table The key can not be None The value can be retrieved by calling the get method with a key that is egual to the original key Parameters e key str the key e value int or float the value static putString key value Maps the specified key to the specified value in this table The key can not be None The value can be r
55. the two limits This filter will fail if more than one sample in a row is errantly in between the two limits You may see this problem if attempting to use this feature with a mechanical rollover sensor such as a 360 degree no stop potentiometer without signal conditioning because the rollover transition is not sharp clean enough Using the averaging engine may help with this but rotational speeds of the sensor will then be limited Create an object that represents one of the four outputs from an analog trigger Because this class derives from DigitalSource it can be passed into routing functions for Counter Encoder etc 1 3 wpilib Package 23 RobotPy WPILib Documentation Release master Parameters e trigger The trigger for which this is an output e outputType An enum that specifies the output on the trigger to represent class AnalogTriggerType Bases builtins object Defines the state in which the AnalogTrigger triggers kFallingPulse 3 kInWindow 0 kRisingPulse 2 kState 1 AnalogTriggerOutput free AnalogTriggerOutput get Get the state of the analog trigger output Returns The state of the analog trigger output Return type AnalogTriggerType AnalogTriggerOutput getAnalogTriggerForRouting AnalogTriggerOutput getChannelForRouting AnalogTriggerOutput getModuleForRout ing 1 3 11 BuiltinAccelerometer class woilib BuiltInAccelerometer range 2 Bases woilib LiveWind
56. this value to be more stable but it will update more slowly Returns A scaled sample from the output of the oversample and average engine for this channel getChannel Get the channel number Returns The channel number static getGlobalSampleRate Get the current sample rate This assumes one entry in the scan list This is a global setting for all channels Returns Sample rate getLSBWeight Get the factory scaling least significant bit weight constant The least significant bit weight constant for the channel that was calibrated in manufacturing and stored in an eeprom Volts LSB_Weight 1e 9 raw Offset 1e 9 Returns Least significant bit weight getOffset Get the factory scaling offset constant The offset constant for the channel that was calibrated in manufac turing and stored in an eeprom Volts LSB_Weight 1e 9 raw Offset 1e 9 Returns Offset constant getOversampleBits Get the number of oversample bits This gets the number of oversample bits from the FPGA The actual number of oversampled values is 2 bits The oversampling is done automatically in the FPGA Returns The number of oversample bits getValue Get a sample straight from this channel The sample is a 12 bit value representing the OV to 5V range of 1 3 wpilib Package 19 RobotPy WPILib Documentation Release master the A D converter The units are in A D converter codes Use get Voltage to get th
57. to You could create the Jaguar object that is using port 4 using the following python code in your robotInit method self motor wpilib Jaguar 4 Looking through the documentation some more you would notice that to set the PWM value of the motor you need to call the Jaguar set function The docs say that the value needs to be between 1 0 and 1 0 so to set the motor full speed forward you could do this self motor set 1 Other motors and sensors have similar conventions Robot drivetrain control For standard types of drivetrains 2 or 4 wheel and mecanum you ll want to use the Robot Drive class to control the motors instead of writing your own code to do it When you create a RobotDrive object you either specify which PWM channels to automatically create a motor for self robot_drive wpilib RobotDrive 0 1 Or you can pass in motor controller instances 6 Chapter 1 Contents RobotPy WPILib Documentation Release master 1 motor wpilib Talon 0 r motor wpilib Talon 1 self robot drive wpilib RobotDrive 1 motor r motor Once you have one of these objects it has various methods that you can use to control the robot via joystick or you can specify the control inputs manually See also Documentation for the woilib RobotDrive object and the FIRST WPILib Programming Guide Robot Operating Modes IterativeRobot During a competition the robot transitions into various modes depending on the st
58. type float static getCurrent 6V Get the current output of the 6V rail Returns The controller 6V rail output current value in Amps Return type float static getEnabled3V3 Get the enabled state of the 3 3V rail The rail may be disabled due to a controller brownout a short circuit on the rail or controller over voltage Returns True if enabled False otherwise Return type bool static getEnabled5V Get the enabled state of the 5V rail The rail may be disabled due to a controller brownout a short circuit on the rail or controller over voltage Returns True if enabled False otherwise Return type bool static getEnabled6vV Get the enabled state of the 6V rail The rail may be disabled due to a controller brownout a short circuit on the rail or controller over voltage Returns True if enabled False otherwise Return type bool static getFaultCount3V3 Get the count of the total current faults on the 3 3V rail since the controller has booted Returns The number of faults Return type int static getFaultCount5V Get the count of the total current faults on the SV rail since the controller has booted Returns The number of faults Return type int static getFaultCount 6V Get the count of the total current faults on the 6V rail since the controller has booted Returns The number of faults Return type int 1 3 wpilib Package 43 RobotPy WPILib Documentation Release master static getInputCurrent
59. via PWM Constructor for a Talon original or Talon SR Parameters channel int The PWM channel that the Talon is attached to 0 9 are on board 10 19 are on the MXP port Note The Talon uses the following bounds for PWM values These values should work reasonably well for most controllers but if users experience issues such as asymmetric behavior around the deadband or inability to saturate the controller in either direction calibration is recommended The calibration procedure can be found in the Talon User Manual available from CTRE 2 037ms full forward 1 539ms the high end of the deadband range 1 513ms center of the deadband range off 1 487ms the low end of the deadband range 0 989ms full reverse get Get the recently set value of the PWM Returns The most recently set value for the PWM between 1 0 and 1 0 Return type float pidWrite output Write out the PID value as seen in the PIDOutput base object Parameters output float Write out the PWM value as was found in the PIDCont roller set speed syncGroup 0 Set the PWM value The PWM value is set using a range of 1 0 to 1 0 appropriately scaling the value for the FPGA Parameters e speed float The speed to set Value should be between 1 0 and 1 0 e syncGroup The update group to add this set to pending updateSyncGroup If 0 update immediately 1 3 53 TalonSRX class woilib TalonS
60. will NOT save the value to memory between power cycles to do that you must call save which must be used with care at some point after calling this Parameters e key the key e value the value putFloat key value Puts the given float into the preferences table The key may not have any whitespace nor an equals sign This will NOT save the value to memory between power cycles to do that you must call save which must be used with care at some point after calling this Parameters e key the key e value the value put Int key value Puts the given int into the preferences table The key may not have any whitespace nor an eguals sign This will NOT save the value to memory between power cycles to do that you must call save which must be used with care at some point after calling this Parameters e key the key e value the value putString key value Puts the given string into the preferences table The value may not have guotation marks nor may the key have any whitespace nor an eguals sign 1 3 wpilib Package 79 RobotPy WPILib Documentation Release master This will NOT save the value to memory between power cycles to do that you must call save which must be used with care at some point after calling this Parameters e key the key e value the value read The internal method to read from a file This will be called in its own thread when the preference
61. with the PWM Object Returns The channel number Return type int getFullRangeScaleFactor Get the scale for positions getMaxNegativePwm getMaxPositivePwm getMinNegativePwn getMinPositivePwm getNegativeScaleFactor Get the scale for negative speeds getPosition Get the PWM value in terms of a position This is intended to be used by servos Note setBounds must be called first Returns The position the servo is set to between 0 0 and 1 0 Return type float 1 3 wpilib Package 81 RobotPy WPILib Documentation Release master PWM PWM PWM PW PW PW PW PW PW getPositiveScaleFactor Get the scale for positive speeds getRaw Get the PWM value directly from the hardware Read a raw value from a PWM channel Returns Raw PWM control value Range 0 255 Return type int get Speed Get the PWM value in terms of speed This is intended to be used by speed controllers Note setBounds must be called first Returns The most recently set speed between 1 0 and 1 0 Return type float kDefaultPwmCenter 1 5 the PWM range center in ms kDefaultPwmPeriod 5 05 the default PWM period measured in ms kDefaultPwmStepsDown 1000 the number of PWM steps below the centerpoint kPwmDisabled 0 the value to use to disable port setBounds max deadbandMax center deadbandMin min
62. 0 and 1 0 Return type float pidWrite output Write out the PID value as seen in the PIDOutput base object Parameters output float Write out the PWM value as was found in the PIDCont roller set speed syncGroup 0 Set the PWM value The PWM value is set using a range of 1 0 to 1 0 appropriately scaling the value for the FPGA Parameters e speed float The speed to set Value should be between 1 0 and 1 0 e syncGroup The update group to add this set to pending updateSyncGroup If 0 update immediately 1 3 58 VictorSP class wpilib VictorSP channel Bases woilib SafePWM VEX Robotics Victor SP Speed Controller via PWM Constructor Parameters channel int The PWM channel that the VictorSP is attached to 0 9 are on board 10 19 are on the MXP port Note The Talon uses the following bounds for PWM values These values should work reasonably well for most controllers but if users experience issues such as asymmetric behavior around the deadband or inability to saturate the controller in either direction calibration is recommended The calibration procedure can be found in the VictorSP User Manual 2 004ms full forward 1 520ms the high end of the deadband range 1 500ms center of the deadband range off 1 480ms the low end of the deadband range 0 997ms full reverse 108 Chapter 1 Contents RobotPy WPILib Documentation Release master
63. 27 RobotPy WPILib Documentation Release master disable Disable the speed controller get Common interface for getting the current set speed of a speed controller Returns The current set speed Value is between 1 0 and 1 0 set speed syncGroup 0 Common interface for setting the speed of a speed controller Parameters e speed The speed to set Value should be between 1 0 and 1 0 e syncGroup The update group to add this set to pending updateSyncGroup If 0 or unspecified update immediately 1 7 RobotPy Installer Note This is not the RobotPy installation guide see Getting Started if you re looking for that Most FRC robots are not placed on networks that have access to the internet particularly at competition arenas The RobotPy installer is designed for this type of two phase operation with individual steps for downloading and installing packages separately As of 2015 the RobotPy installer now supports downloading external packages from the python package repository pypi via pip and installing those packages onto the robot We cannot make any guarantees about the guality of external packages so use them at your own risk Note If your robot is on a network that has internet access then you can manually install packages via opkg or pip However if you use the RobotPy installer to install packages then you can easily reinstall them on your robot in the case you need to re
64. 78 getForwardLimitOK wpilib canjaguar CANJaguar method 28 getFPGAIndex wpilib counter Counter method 46 getFPGAIndex wpilib encoder Encoder method 58 getFPGARevision wpilib utility Utility static method 107 getFPGATime wpilib utility Utility static method 107 getFPGATimestamp wpilib timer Timer static method 104 getFPGAVersion wpilib utility Utility static method 107 getFullRangeScaleFactor wpilib pwm PWM method 81 getGlobalSampleRate wpilib analoginput AnalogInput static method 19 getGroup wpilib command command Command method 113 getHardwareVersion method 28 getI wpilib canjaguar CANJaguar method 29 getI wpilib cantalon CANTalon method 38 getI wpilib pidcontroller PIDController method 75 getlaccum wpilib cantalon CANTalon method 38 wpilib canjaguar CANJaguar 142 Index RobotPy WPILib Documentation Release master getImage wpilib impl dummycamera USB Camera method 12 13 getImageData wpilib _impl dummycamera USBCamera getNumber method 12 13 getIndex wpilib analogtrigger AnalogTrigger method 22 getNegativeScaleFactor wpilibpwm PWM method 81 wpilib smartdashboard SmartDashboard static method 97 getNumberOfQuadIdxRises wpilib cantalon CANTalon method 38 getInputCurrent wpilib controllerpower ControllerPower getNumMotors wpilib robotdrive RobotDrive method static method 43
65. 8 free wpilib sensorbase SensorBase method 95 free wpilib solenoid Solenoid method 99 G GearTooth class in wpilib geartooth 60 General wpilib cantalon CANTalon StatusFrameRate at tribute 36 GenericHID class in wpilib interfaces generichid 125 GenericHID Hand class in wpilib interfaces generichid 125 get wpilib analogpotentiometer AnalogPotentiometer method 21 get wpilib analogtriggeroutput AnalogTriggerOutput method 24 get wpilib buttons internalbutton InternalButton method 110 get wpilib buttons joystickbutton JoystickButton method 110 get wpilib buttons networkbutton NetworkButton method 110 get wpilib buttons trigger Trigger method 111 get wpilib canjaguar CANJaguar method 27 get wpilib cantalon CANTalon method 37 get wpilib counter Counter method 46 get wpilib digitalinput DigitalInput method 49 get wpilib doublesolenoid DoubleSolenoid method 52 get wpilib encoder Encoder method 57 get wpilib interfaces counterbase CounterBase method 125 get wpilib interfaces potentiometer Potentiometer method 127 get wpilib interfaces speedcontroller SpeedController method 128 get wpilib jaguar Jaguar method 66 get wpilib pidcontroller PIDController method 74 get wpilib preferences Preferences method 78 get wpilib relay Relay method 84 get wpilib servo Servo method 95 get wpilib solenoid Sol
66. Camera WhiteBalan attribute 11 13 kDefaultCameraName wpilib impl dummycamera USB CakkeredIndoor wpilib impl dummycamera USBCamera WhiteBalance attribute 12 13 kDefaultExpirationTime attribute 88 kDefaultMaxOutput wpilib robotdrive RobotDrive at tribute 89 kDefaultMaxServoPWM wpilib servo Servo attribute 96 kDefaultMinServoPWM wpilib servo Servo attribute 96 kDefaultPeriod wpilib pidcontroller PIDController at tribute 75 kDefaultPwmCenter wpilib pwm PWM attribute 82 kDefaultPwmPeriod wpilib pwm PWM attribute 82 kDefaultPwmStepsDown wpilib pwm PWM attribute 82 kDefaultSensitivity attribute 89 kDefaultThrottleAxis wpilib joystick Joystick attribute wpilib robotdrive RobotDrive wpilib robotdrive RobotDrive 70 kDefaultTopButton Wwpilib joystick Joystick attribute 70 kDefaultTriggerButton wpilib joystick Joystick at tribute 70 kDefaultTwistAxis wpilib joystick Joystick attribute 70 kDefaultVoltsPerDegreePerSecond wpilib gyro Gyro at tribute 61 kDefaultX Axis wpilib joystick Joystick attribute 70 kDefaultYAxis wpilib joystick Joystick attribute 70 kDefaultZAxis wpilib joystick Joystick attribute 70 kDelayForSolicitedSignals wpilib cantalon CANTalon attribute 39 kDigitalChannels wpilib sensorbase SensorBase at tribute 95 kDistance wpilib counter Counter PIDSourceParameter attribute 45 kDistance wpilib encoder Encoder PIDSourceParameter
67. DXL345_SPI Range Bases builtins object k16G 3 k2G 0 k4G 1 k8G 2 ADXL345 SPI getAcceleration axis Get the acceleration of one axis in Gs Parameters axis The axis to read from Returns An object containing the acceleration measured on each axis of the ADXL345 in Gs ADXL345 SPI getAccelerations Get the acceleration of all axes in Gs Returns X Y Z tuple of acceleration measured on all axes of the ADXL345 in Gs ADXL345 SPI getX Get the x axis acceleration Returns The acceleration along the x axis in g forces 16 Chapter 1 Contents RobotPy WPILib Documentation Release master ADXL345 SPI getY Get the y axis acceleration Returns The acceleration along the y axis in g forces ADXL345 SPI getZ Get the z axis acceleration Returns The acceleration along the z axis in g forces DXL345 SPI kAddress MultiByte 64 DXL345 SPI kAddress Read 128 DXL345 SPI kDataFormatRegister 49 DXL345 SPI kDataFormat FullRes 8 DXL345 SPI kDataFormat IntInvert 32 DXL345 SPI kDataFormat Justify 4 DXL345 SPI kDataFormat SPI 64 DXL345 SPI kDataFormat SelfTest 128 DXL345 SPI kDataRegister 50 DXL345 SPI kGsPerLSB 0 00390625 DXL345 SPI kPowerCtlRegister 45 DXL345_SP1 kPowerCtl_AutoSleep 16 DXL345 SPI kPowerCtl Link 32 DXL345_SPI kPowerCt1_Measure 8 DXL345_SPI kPowerCtl_Sleep 4 gt gt p D PP D p PP D PP PP SP Se PS DXL345 SPI setRange range Set the measuring range of the
68. ID Parameters hand which hand left or right default right Returns the z position 126 Chapter 1 Contents RobotPy WPILib Documentation Release master 1 6 5 NamedSendable class wpilib interfaces NamedSendable Bases woilib Sendable The interface for sendable objects that gives the sendable a default name in the Smart Dashboard getName Returns The name of the subtable of SmartDashboard that the Sendab1e object will use 1 6 6 PIDOutput class wpilib interfaces PIDOutput Bases builtins object This interface allows PIDController to write its results to its output pidWrite output Set the output to the value calculated by PIDCont roller Parameters output the value calculated by PID Controller 1 6 7 PIDSource class wpilib interfaces PIDSource Bases builtins object This interface allows for PIDController to automatically read from this object class PIDSourceParameter Bases builtins object A description for the type of output value to providetoa PIDController kAngle 2 kDistance 0 kRate 1 PIDSource pidGet Get the result to use in PIDController Returns the result to use in PIDController 1 6 8 Potentiometer class wpilib interfaces Potentiometer Bases woilib interfaces PIDSource get 1 6 9 SpeedController class woilib interfaces SpeedController Bases woilib interfaces PIDOutput Interface for speed controlling devices 1 6 wpilib interfaces Package 1
69. Joystick method 70 144 Index RobotPy WPILib Documentation Release master wpilib command scheduler Scheduler method 120 getUserButton wpilib utility Utility static method 107 getValue wpilib analoginput AnalogInput method 19 getVoltage wpilib analoginput AnalogInput method 20 getVoltage method 21 getType wpilib analogoutput AnalogOutput I2C class in wpilib i2c 61 IC Port class in wpilib i2c 62 impl wpilib robotstate RobotState attribute 91 IN_SEQUENCE wpilib command commandgroup CommandGroup Entry attribute 115 getVoltage wpilib powerdistributionpanel PowerDistributippBaaged wpilib driverstation DriverStation method method 77 getVoltage3 V3 wpilib controllerpower ControllerPower static method 44 getVoltage5V wpilib controllerpower ControllerPower static method 44 getVoltage6V wpilib controllerpower ControllerPower static method 44 getX wpilib adx1345_i2c ADXL345_I2C method 15 getX wpilib adx1345 spi ADXL345 SPI method 16 getX wpilib builtinaccelerometer BuiltInAccelerometer method 24 getX wpilib interfaces accelerometer Accelerometer method 124 getX wpilib interfaces generichid GenericHID method 126 getX wpilib joystick Joystick method 70 getY wpilib adx1345 i2c ADXL345 I2C method 15 getY wpilib adx1345 spi ADXL345 SPI method 17 getY wpilib builtinaccelerometer BuiltInAccelerometer
70. L345 SPI k4X wpilib interfaces counterbase CounterBase EncodingType attribute 17 attribute 125 kDataFormat Justify wpilib adx1345 i2c ADXL345 RC k4X wpilib pwm PWM PeriodMultiplier attribute 81 attribute 15 k8G wpilib adx1345 i2c ADXL345 I2C Range at kDataFormat Justify wpilib adx1345 spi ADXL345 SPI tribute 15 attribute 17 k8G wpilib adx1345 spi ADXL345 SPI Range at kDataFormat SelfTest wpilib adx1345 i2c ADXL345 I2C tribute 16 attribute 15 k8G wpilib builtinaccelerometer BuiltInAccelerometer RangDataFormat SelfTest wpilib adx1345 spi ADXL345 SPI attribute 24 attribute 17 k8G wpilib interfaces accelerometer Accelerometer Range kDataFormat SPI wpilib adx1345 i2c ADXL345 I2C attribute 124 attribute 15 kAccumulatorChannels wpilib analoginput AnalogInput kDataFormat SPI wpilib adx1345 spi ADXL345 SPI attribute 20 attribute 17 kAccumulatorSlot wpilib analoginput AnalogInput at kDataFormatRegister wpilib adx1345 i2c ADXL345 I2C tribute 20 attribute 15 kAddress wpilib adx1345 i2c ADXL345 I2C attribute kDataFormatRegister wpilib adx1345 spi ADXL345 SPI 15 attribute 17 Index 147 RobotPy WPILib Documentation Release master kDataRegister wpilib adx1345 i2c ADXL345 I2C at tribute 15 kDataRegister wpilib adx1345 spi ADXL345 SPI at tribute 17 kFixedFlourescent2 wpilib impl dummycamera USB Camera WhiteBalan attribute 11 13 kFixedFluorescent1 wpilib impl dummycamera USB
71. Linux OSX python3 installer py install robotpy It will ask you a few questions and copy the right files over to your robot and set things up for you Next you ll want to create some code or maybe use one of our examples and upload it to your robot Refer to our Programmer s Guide for more information RobotPy WPILib Documentation Release master Upgrading From the same directory that you unzipped previously you can run the same installer script to upgrade your robotpy installation You need to doitin two phases one while connected to the internet to download the new release and one while connected to the Robot s network When connected to the internet Windows py installer py download robotpy Linux OSX python3 installer py download robotpy Then connect to the Robot s network Windows py installer py install robotpy Linux OSX python3 installer py install robotpy If you want to use a beta version of RobotPy if available you can add the pre argument to the download install command listed above 1 1 2 Manual installation If you really want to do this it s not so bad but then you lose out on the benefits of the automated installer in particular this method reguires internet access to install the files on the RoboRIO in case you need to reimage your RoboRIO e Connect your RoboRIO to the internet e SSH in and copy the following to etc opkg robotpy conf src gz robotpy http www tortall net
72. LiveWindow mode This allows default sensor and actuator values to be created that are replaced with the custom names from users calling addActuator and addSensor liveWindowEnabled False livewindowTable None static run The run method is called repeatedly to keep the values refreshed on the screen in test mode sensors set static setEnabled enabled Set the enabled state of LiveWindow If it s being enabled turn off the scheduler and remove all the commands from the queue and enable all the components registered for LiveWindow If it s being disabled stop all the registered components and reenable the scheduler TODO add code to disable PID loops when enabling LiveWindow The commands should reenable the PID loops themselves when they get rescheduled This prevents arms from starting to move around etc after a period of adjusting them in LiveWindow mode statusTable None static updateValues Puts all sensor values on the live window 1 3 31 LiveWindowSendable class woilib LiveWindowSendable Bases woilib Sendable A special type of object that can be displayed on the live window 72 Chapter 1 Contents RobotPy WPILib Documentation Release master 1 3 32 MotorSafety class wpilib MotorSafety Bases builtins object Provides mechanisms to safely shutdown motors if they aren t updated often enough The MotorSafety object is constructed for every object that wants to implement the Motor Safe
73. PI Axes attribute 16 kZ wpilib joystick Joystick AxisType attribute 67 L limit wpilib robotdrive RobotDrive static method 89 LiveWindow class in wpilib livewindow 71 liveWindowEnabled wpilib livewindow Live Window at tribute 72 Live WindowSendable class in wpilib livewindowsendable 72 livewindow Table wpilib livewindow LiveWindow attribute 72 lockChanges wpilib command command Command method 114 logger wpilib iterativerobot IterativeRobot attribute 65 logger wpilib samplerobot SampleRobot attribute 92 M main Wpilib robotbase RobotBase static method 86 mecanumDrive_Cartesian wpilib robotdrive RobotDrive 89 wpilib canjaguar CANJaguar at method wpilib robotdrive RobotDrive method 89 MotorSafety class in wpilib motorsafety 73 N NamedSendable class in wpilib interfaces namedsendable 127 NetworkButton class in wpilib buttons networkbutton 110 NEW_LINE wpilib preferences Preferences attribute 77 nextPeriodReady Wwpilib iterativerobot IterativeRobot method 65 normalize wpilib robotdrive RobotDrive method 89 static O onTarget wpilib command pidsubsystem PIDSubsystem method 118 onTarget wpilib pidcontroller PIDController method 75 openCamera wpilib impl dummycamera USBCamera method 12 13 operatorControl wpilib samplerobot SampleRobot method 92 OPTIONS wpilib sendablechooser SendableChooser at tribute
74. PILib Documentation Release master Returns The GPIO channel number that this object represents Return type int 1 3 18 DigitalOutput class wpilib DigitalOutput channel Bases woilib DigitalSource Writes to a digital output Other devices that are implemented elsewhere will automatically allocate digital inputs and outputs as required Create an instance of a digital output Parameters channel the DIO channel for the digital output 0 9 are on board 10 25 are on the MXP disablePWM Change this line from a PWM output back to a static Digital Output line Free up one of the 6 DO PWM generator resources that were in use enablePWM initialDutyCycle Enable a PWM Output on this line Allocate one of the 6 DO PWM generator resources Supply the initial duty cycle to output so as to avoid a glitch when first starting The resolution of the duty cycle is 8 bit for low frequencies 1kHz or less but is reduced the higher the frequency of the PWM signal is Parameters initialDutyCycle float The duty cycle to start generating 0 1 free Free the resources associated with a digital output getChannel Returns The GPIO channel number that this object represents isPulsing Determine if the pulse is still going Determine if a previously started pulse is still going Returns True if pulsing Return type bool pulse channel pulseLength Generate a single pulse Write a pulse to the specified digital
75. Relay State Gets the current state of the relay When set to kForwardOnly or kReverseOnly value is returned as kOn kOff not kForward kReverse per the recommendation in Set Returns The current state of the relay Return type Relay Value Relay port Relay relayChannels lt wpilib resource Resource object at 0x7f2574e7e780 gt Relay set value Set the relay state Valid values depend on which directions of the relay are controlled by the object When set to kBothDirections the relay can be set to any of the four states Ov Ov 12v Ov Ov 12v 12v 12v When set to kForwardOnly or kReverseOnly you can specify the constant for the direction or you can simply specify kOff and kOn Using only kOff and kOn is recommended Parameters value Relay Value The state to set the relay Relay setDirection direction Set the Relay Direction Changes which values the relay can be set to depending on which direction is used Valid inputs are kBothDirections kForwardOnly and kReverseOnly Parameters direction Relay Direction The direction for the relay to operate in 1 3 38 Resource class wpilib Resource size Bases builtins object Tracks resources in the program The Resource class is a convenient way of keeping track of allocated arbitrary resources in the program Re sources are just indices that have an lower and upper bound that are tracked by this class In the library they are 84 Chapter 1 Contents RobotPy
76. RobotPy WPILib Documentation Release master RobotPy development team February 04 2015 Contents 1 Contents 3 T1 Gettme Started 2 4 54 2 2842 46 x BP Le ak 2d ee kh be ee hee Babi 3 1 2 Programmer s Guide oy 5 2 scp e E RAE ee ws KAS RO AE Re eR eS 5 1 35 Awpilib Package eia vik Se Bing eet Ph ee dee ec be thant a ee eed amp wha s 10 14 wpilib buttons Package a mk sita a eG Bo DRE RS RRS Bh eG SSS 109 15 wpilbcommand Package s ix to coe 588 bbe bea ee wae eee ee Seas 111 1 6 wpilib interfaces Package io a50 oa ae AAS pS apa Te aib a Ea 123 1 7 RobotPy Installer ss eccede De ae bobo DRA AA RA Bm RS hae ee al Gea Y 128 1 8 Implementation Details ss sagas ede nh ae a san BAN BR AG BR BA SS 8 129 NO SUPPOR y e e a he aos ea ety bee a A eee Be Oe he ye ah we OS ee so ei 131 2 Indices and tables 133 Python Module Index 135 RobotPy WPILib Documentation Release master Welcome to RobotPy RobotPy is a community of FIRST mentors and students dedicated to developing python related projects for the FIRST Robotics Competition This documentation site describes how to use the python version of WPILib It is a pure python implementation of WPILib so that teams can use to write their robot code in Python a powerful dynamic programming language There is a lot of good documentation but there s still room for improvement We welcome contributions from others Contents 1 RobotPy WPILib Documentat
77. RobotPy WPILib Documentation Release master e minimumOutput the minimum percentage to write to the output e maximumOutput the maximum percentage to write to the output setPID p i d f None Set the PID Controller gain parameters Set the proportional integral and differential coefficients Parameters e p Proportional coefficient e i Integral coefficient e d Differential coefficient f Feed forward coefficient optional setPercentTolerance percentage Set the percentage error which is considered tolerable for use with onTarget Input of 15 0 15 percent Parameters percentage percent error which is tolerable setSetpoint setpoint Set the setpoint for the PIDController Parameters setpoint the desired setpoint setTolerance percent Set the percentage error which is considered tolerable for use with onTarget Input of 15 0 15 percent Parameters percent error which is tolerable Deprecated since version 2015 1 Use setPercentTolerance or setAbsoluteTolerance instead 1 3 34 PowerDistributionPanel class wpilib PowerDistributionPanel Bases wpilib SensorBase Use to obtain voltage current temperature power and energy from the CAN PDP The PDP must be at CAN Address 0 clearStickyFaults Clear all pdp sticky faults getCurrent channel Query the current of a single channel of the PDP Returns The current of one of the PDP channels channels 0 15 in A
78. Rx channel Bases woilib SafePWM Cross the Road Electronics CTRE Talon SRX Speed Controller via PWM 102 Chapter 1 Contents RobotPy WPILib Documentation Release master See also See CANTalon for CAN control of Talon SRX Constructor for a TalonSRX connected via PWM Parameters channel int The PWM channel that the TalonSRX is attached to 0 9 are on board 10 19 are on the MXP port Note The TalonSRX uses the following bounds for PWM values These values should work reasonably well for most controllers but if users experience issues such as asymmetric behavior around the deadband or inability to saturate the controller in either direction calibration is recommended The calibration procedure can be found in the TalonSRX User Manual available from CTRE 2 004ms full forward 1 520ms the high end of the deadband range 1 500ms center of the deadband range off 1 480ms the low end of the deadband range 0 997ms full reverse get Get the recently set value of the PWM Returns The most recently set value for the PWM between 1 0 and 1 0 Return type float pidWrite output Write out the PID value as seen in the PIDOutput base object Parameters output float Write out the PWM value as was found in the PIDCont roller set speed syncGroup 0 Set the PWM value The PWM value is set using a range of 1 0 to 1 0 appropriately scaling the value for the
79. Set the bounds on the PWM pulse widths This sets the bounds on the PWM values for a particular type of controller The values determine the upper and lower speeds as well as the deadband bracket Parameters e max float The max PWM pulse width in ms e deadbandMax float The high end of the deadband range pulse width in ms e center float The center off pulse width in ms e deadbandMin float The low end of the deadband pulse width in ms e min float The minimum pulse width in ms PWM setPeriodMultiplier mult Slow down the PWM signal for old devices Parameters mult PWM PeriodMultiplier The period multiplier to apply to this channel PWM setPosition pos Set the PWM value based on a position This is intended to be used by servos 82 Chapter 1 Contents RobotPy WPILib Documentation Release master Note setBounds must be called first Parameters pos float The position to set the servo between 0 0 and 1 0 PWM setRaw value Set the PWM value directly to the hardware Write a raw value to a PWM channel Parameters value int Raw PWM value Range 0 255 PWM set Speed speed Set the PWM value based on a speed This is intended to be used by speed controllers Note setBounds must be called first Parameters speed float The speed to set the speed controller between 1 0 and 1 0 PWM setZeroLatch 1 3 37 Relay class woilib Relay
80. Subsystenm system Registers a Subsystem to this Scheduler so that the Scheduler might know if a default Command needs to be run All Subsystem objects should call this Parameters system the system 120 Chapter 1 Contents RobotPy WPILib Documentation Release master remove command Removes the Command from the Scheduler Parameters command the command to remove removeAll Removes all commands run Runs a single iteration of the loop This method should be called often in order to have a functioning Command system The loop has five stages Poll the Buttons Execute Remove the Commands Send values to SmartDashboard Add Commands Add Defaults 1 5 7 StartCommand class woilib command StartCommand commandToStart Bases woilib command Command A StartCommand will call the start Q method of another command when it is initialized and will finish immedi ately Instantiates a StartCommand which will start the given command whenever its initialize is called Parameters commandToStart the Command to start initialize isFinished 1 5 8 Subsystem class woilib command Subsystem name None Bases woilib Sendable This class defines a major component of the robot A good example of a subsystem is the driveline or a claw if the robot has one All motors should be a part of a subsystem For instance all the wheel motors should be a part of some kind of Driveline subsystem
81. Talon initially during robot install Parameters normallyOpen True for normally open False for normally closed CANTalon configRevLimitSwitchNormallyOpen normallyOpen Configure the rev limit switch to be normally open or normally closed Talon will disable momentarilly if the Talon s current setting is dissimilar to the caller s requested setting Since Talon saves setting to flash this should only affect sa given Talon initially during robot install param normallyOpen true for normally open false for normally closed CANTalon disable CANTalon disableControl CANTalon enableBrakeMode brake 36 Chapter 1 Contents RobotPy WPILib Documentation Release master CANTalon enableControl CANTalon enableForwardSoftLimit enable CANTalon enableLimitSwitch forward reverse CANTalon enableReverseSoftLimit enable CANTalon free CANTalon get Gets the current status of the Talon usually a sensor value In Current mode returns output current In Speed mode returns current speed In Position omde returns current sensor position In Throttle and Follower modes returns current applied throttle Returns The current sensor value of the Talon CANTalon getAnalogInPosition Get the current analog in position regardless of whether it is the current feedback device Returns The 24bit analog position The bottom ten bits is the ADC 0 1023 on the analog pi
82. accelerometer Parameters range ADXL345 SPI Range The maximum acceleration positive or nega tive that the accelerometer will measure 1 3 5 AnalogAccelerometer class wpilib AnalogAccelerometer channel Bases woilib LiveWindowSendable Analog Accelerometer The accelerometer reads acceleration directly through the sensor Many sensors have multiple axis and can be treated as multiple devices Each is calibrated by finding the center value over a period of time Create a new instance of Accelerometer from either an existing AnalogChannel or from an analog channel port index Parameters channel port index or an already initialized AnalogInput getAcceleration Return the acceleration in Gs The acceleration is returned units of Gs Returns The current acceleration of the sensor in Gs 1 3 wpilib Package 17 RobotPy WPILib Documentation Release master Return type float pidGet Get the Acceleration for the PID Source parent Returns The current acceleration in Gs Return type float setSensitivity sensitivity Set the accelerometer sensitivity This sets the sensitivity of the accelerometer used for calculating the acceleration The sensitivity varies by accelerometer model There are constants defined for various models Parameters sensitivity float The sensitivity of accelerometer in Volts per G setZero zero Set the voltage that corresponds to 0 G The zero G voltage varies by acce
83. age wpilib cantalon CANTalon method 38 getOversampleBits wpilib analoginput AnalogInput method 19 getP wpilib canjaguar CANJaguar method 29 getP wpilib cantalon CANTalon method 38 getP wpilib pidcontroller PIDController method 75 getPCMSolenoidBlackList wpilib solenoidbase SolenoidBase 100 getPCMSolenoidVoltageFault wpilib solenoidbase SolenoidBase 100 getPCMSolenoidVoltageStickyFault wpilib solenoidbase SolenoidBase 100 getPeriod wpilib counter Counter method 46 getPeriod wpilib encoder Encoder method 58 getPeriod wpilib interfaces counterbase CounterBase method 125 method method method getPIDController wpilib command pidcommand PIDCommand method 117 getPIDController wpilib command pidsubsystem PIDSubsystem getModuleForRouting wpilib analogtriggeroutput AnalogTriggerOutpethod 118 method 24 getModuleForRouting wpilib digitalsource DigitalSource method 51 getPinStateQuadA wpilib cantalon CANTalon method 38 getPinStateQuadB wpilib cantalon CANTalon getModuleForRouting wpilib interruptablesensorbase InterruptableSnatlovBps28 method 63 getMsClock wpilib timer Timer method 104 getName wpilib command command Command method 113 getName wpilib command scheduler Scheduler method 120 getName wpilib command subsystem Subsystem method 122 getPinStateQuadIdx method 38 getPosition wpi
84. alculated 1 5 4 PIDSubsystem class woilib command PIDSubsysten p i d period None f 0 0 name None Bases woilib command Subsystem This class is designed to handle the case where there is a Subsystem which uses a single link PIDController almost constantly for instance an elevator which attempts to stay at a constant height It provides some convenience methods to run an internal PIDController It also allows access to the internal PIDController in order to give total control to the programmer Instantiates a PIDSubsystem that will use the given p i and d values It will use the class name as its name unless otherwise specified It will also space the time between PID loop calculations to be equal to the given period Parameters e p the proportional value e i the integral value e d the derivative value e period the time in seconds between calculations optional e f the feed forward value e name the name optional disable Disables the internal PIDController enable Enables the internal PIDController getPIDController Returns the PIDController used by this PIDSubsystem Use this if you would like to fine tune the pid loop Notice that calling set Setpoint on the controller will not result in the setpoint being trimmed to be in the range defined by set SetpointRange Returns the PIDCont roller used by this PIDSubsystem getPosition Returns the current position Returns the curr
85. alue that the accumulator should start from when reset setAverageBits bits Set the number of averaging bits This sets the number of averaging bits The actual number of averaged samples is 2 bits The averaging is done automatically in the FPGA Parameters bits The number of averaging bits static setGlobalSampleRate samplesPerSecond Set the sample rate per channel This is a global setting for all channels The maximum rate is 500kS s divided by the number of channels in use This is 62500 samples s per channel if all 8 channels are used Parameters samplesPerSecond The number of samples per second 20 Chapter 1 Contents RobotPy WPILib Documentation Release master setOversampleBits bits Set the number of oversample bits This sets the number of oversample bits The actual number of oversampled values is 2 bits The oversampling is done automatically in the FPGA Parameters bits The number of oversample bits 1 3 7 AnalogOutput class woilib AnalogOutput channel Bases woilib SensorBase Analog output Construct an analog output on a specified MXP channel Parameters channel The channel number to represent channels lt wpilib resource Resource object at 0x7f2574edd1d0 gt free Channel destructor getVoltage setVoltage voltage 1 3 8 AnalogPotentiometer class woilib AnalogPotentiometer channel fullRange 1 0 offset 0 0 Bases woilib LiveWindowSendable Reads a potentiomet
86. and Command method 114 setPercentMode wpilib canjaguar CANJaguar method 32 setPercentModeEncoder wpilib canjaguar CANJaguar method 32 setPercentModePotentiometer wpilib canjaguar CANJaguar method 32 setPercentModeQuadEncoder wpilib canjaguar CANJaguar method 32 setPercentTolerance wpilib command pidsubsystem PIDSubsystem method 119 setPercentTolerance wpilib pidcontroller PIDController method 76 setPeriodMultiplier wpilib pwm PWM method 82 setPID wpilib canjaguar CANJaguar method 31 setPID wpilib cantalon CANTalon method 40 setInputRange wpilib command pidsubsystem PIDSubsystetRID wpilib pidcontroller PIDController method 76 method 119 setInputRange wpilib pidcontroller PIDController method 75 setInterruptible wpilib command command Command method 114 setInverted wpilib buttons internalbutton InternalButton method 110 setInvertedMotor method 90 setIZone wpilib cantalon CANTalon method 40 wpilib robotdrive RobotDrive setPIDSourceParameter method 48 setPIDSourceParameter method 59 setPIDSourceParameter wpilib gyro Gyro method 61 setPosition wpilib cantalon CANTalon method 41 setPosition wpilib pwm PWM method 82 setPositionModePotentiometer wpilib canjaguar CANJaguar method 32 wpilib counter Counter wpilib encoder Encoder Index 153 RobotPy WPILib Documentation Release master setPositio
87. ase Base for sensors to be used with interrupts Create a new InterrupatableSensorBase allocateInterrupts watcher Allocate the interrupt Parameters watcher True if the interrupt should be in synchronous mode where the user program will have to explicitly wait for the interrupt to occur cancelInterrupts Cancel interrupts on this device This deallocates all the chipobject structures and disables any interrupts disableInterrupts Disable Interrupts without without deallocating structures enableInterrupts Enable interrupts to occur on this input Interrupts are disabled when the ReguestInterrupt call is made This gives time to do the setup of the other options before starting to field interrupts getAnalogTriggerForRouting getChannelForRout ing getModuleForRout ing 1 3 wpilib Package 63 RobotPy WPILib Documentation Release master interrupt interrupts lt wpilib resource Resource object at 0x7f2574eb38d0 readFallingTimestamp Return the timestamp for the falling interrupt that occurred most recently This is in the same time domain as getClock The falling edge interrupt should be enabled with setUpSourceEdge Returns Timestamp in seconds since boot readRisingTimestamp Return the timestamp for the rising interrupt that occurred most recently This is in the same time domain as getClock The rising edge interrupt should be enabled with setUpSourceEdge Returns Timestamp in seco
88. ate of the game During each mode functions on your robot class are called The name of the function varies based on which mode the robot is in e disabledX XX Called when robot is disabled e autonomousXXX Called when robot is in autonomous mode e teleopXXX Called when the robot is in teleoperated mode e testX XX Called when the robot is in test mode Each mode has two functions associated with it xxxInit is called when the robot first switches over to the mode and xxxPeriodic is called 50 times a second approximately it s actually called as packets are received from the driver station For example a simple robot that just drives the robot using a single joystick might have a teleopPeriodic function that looks like this def teleopPeriodic self self robot drive arcadeDrive self stick This function gets called over and over again about 50 times per second while the robot remains in teleoperated mode Warning When using the IterativeRobot as your Robot class you should avoid doing the following operations in the xxxPeriodic functions or functions that have xxxPeriodic in the call stack e Never use Timer delay as you will momentarily lose control of your robot during the delay and it will not be as responsive e Avoid using loops as unexpected conditions may cause you to lose control of your robot Main block Languages such as Java require you to define a static main function In python becau
89. ault code by providing the following functions which are called by the main loop start Competition at the appropriate times robot Init provide for initialization at robot power on init functions each of the following functions is called once when the appropriate mode is entered disabledInit called only when first disabled sautonomousInit called each and every time autonomous is entered from another mode 64 Chapter 1 Contents RobotPy WPILib Documentation Release master teleopInit called each and every time teleop is entered from another mode testInit called each and every time test mode is entered from another mode Periodic functions each of these functions is called iteratively at the appropriate periodic rate aka the slow loop The period of the iterative robot is synced to the driver station control packets giving a periodic fre quency of about 50Hz 50 times per second disabledPeriodic sautonomousPeriodic teleopPeriodic testPeriodic Constructor for RobotlterativeBase The constructor initializes the instance variables for the robot to indicate the status of initialization for disabled autonomous and teleop code autonomousInit Initialization code for autonomous mode should go here Users should override this method for initialization code which will be called each time the robot enters autonomous mode autonomousPeriodic P
90. b _impl dummycamera CameraServer attribute 12 14 kSolenoidChannels wpilib sensorbase SensorBase attribute 95 kSolenoidModules wpilib sensorbase SensorBase attribute 95 kSpeedOfSoundInchesPerSec wpilib ultrasonic Ultrasonic attribute 106 kState wpilib analogtrigger AnalogTrigger AnalogTriggerType attribute 22 Index 149 RobotPy WPILib Documentation Release master kState wpilib analogtriggeroutput AnalogTriggerOutput AnalegalimggbrTypeP olar attribute 24 kSystemClockTicksPerMicrosecond wpilib sensorbase SensorBase attribute 95 kTank Reported wpilib robotdrive RobotDrive at tribute 89 kTemperatureFault wpilib canjaguar CANJaguar at tribute 30 kThrottle wpilib joystick Joystick AxisType attribute 67 kTop wpilib joystick Joystick ButtonType attribute 67 kTrigger wpilib joystick Joystick ButtonType attribute 67 kTrustedMessages tribute 30 kTwist wpilib joystick Joystick AxisType attribute 67 kTwoPulse wpilib counter Counter Mode attribute 45 kX wpilib adx1345 i2c ADXL345 I2C Axes attribute 15 kX wpilib adx1345 spi ADXL345 SPI Axes attribute 16 kX wpilib joystick Joystick AxisType attribute 67 kY wpilib adx1345 i2c ADXL345 I2C Axes attribute 15 kY wpilib adx1345 spi ADXL345 SPI Axes attribute 16 kY wpilib joystick Joystick AxisType attribute 67 kZ wpilib adx1345 i2c ADXL345 I2C Axes attribute 15 kZ Wwpilib adx1345 spi ADXL345 S
91. botDrive kDefaultExpirationTime 0 1 kDefaultMaxOutput 1 0 kDefaultSensitivity 0 5 kMaxNumberOfMotors 4 kMecanumCartesian_Reported False kMecanumPolar_Reported False kTank_Reported False static RobotDrive limit num Limit motor values to the 1 0 to 1 0 range RobotDrive mecanumDrive_Cartesian x y rotation gyroAngle Drive method for Mecanum wheeled robots A method for driving with Mecanum wheeled robots There are 4 wheels on the robot arranged so that the front and back wheels are toed in 45 degrees When looking at the wheels from the top the roller axles should form an X across the robot This is designed to be directly driven by joystick axes Parameters x The speed that the robot should drive in the X direction 1 0 1 0 y The speed that the robot should drive in the Y direction This input is inverted to match the forward 1 0 that joysticks produce 1 0 1 0 rotation The rate of rotation for the robot that is completely independent of the transla tion 1 0 1 0 gyroAngle The current angle reading from the gyro Use this to implement field oriented controls RobotDrive mecanumDrive_Polar magnitude direction rotation Drive method for Mecanum wheeled robots A method for driving with Mecanum wheeled robots There are 4 wheels on the robot arranged so that the front and back wheels are toed in 45 degrees When looking at the wheels from the top the roller axles
92. botPy has several examples of command based robots available Each one of the objects in the Command framework has detailed documentation available If you need more infor mation for examples tutorials and other detailed information on programming your robot using this pattern we recommend that you consult the Java version of the FRC Control System documentation wpilib command Command name timeout The Command class is at the very core of the entire command framework wpilib command CommandGroup Iname A CommandGroup is a list of commands which are executed in sequence wpilib command PIDCommandfp i d This class defines a Command which interacts heavily with a PID loop wpilib command PIDSubsystemtfp i d This class is designed to handle the case where there is a Subsystem which use wpilib command PrintCommand message A PrintCommand is a command which prints out a string when it is initialized wpilib command Scheduler The Scheduler is a singleton which holds the top level running commands wpilib command StartCommand A StartCommand will call the start method of another command when it is ir wpilib command Subsystem name This class defines a major component of the robot wpilib command WaitCommand timeout A WaitCommand will wait for a certain amount of time before finishing wpilib command WaitForChildren This command will only finish if whatever CommandGroup it is in has no act wpilib command WaitUntilCom
93. but aren t This package is installed by the RobotPy installer by default 1 8 Implementation Details 129 RobotPy WPILib Documentation Release master 1 8 2 HAL Loading Currently the HAL is split into two python packages e hal Provided by the robotpy hal base package e hal impl Provided by either robotpy hal roborio or robotpy hal sim You can only have a single hal impl package installed in a particular python installation The hal package provides the definition of the functions and various types amp required constants The hal_imp1 package provides the actual implementation of the HAL functions or links them to a shared DLL via ctypes 1 8 3 Adding options to robot py When run is called that function determines available commands that can be run and parses command line arguments to pass to the commands Examples of commands include e Running the robot code e Running the robot code connected to a simulator e Running unit tests on the robot code e And lots more python setuptools has a feature that allows you to extend the commands available to robot py without needing to modify WPILib s code To add your own command do the following e Define a setuptools entrypoint in your package s setup py see below e The entrypoint name is the command to add The entrypoint must point at an object that has the following properties Must have a docstring shown when help is given Constructor mu
94. butionpanel 76 preferences 77 pwm 80 relay 83 resource 84 robotbase 85 robotdrive 87 robotstate 91 safepwm 91 samplerobot 91 sendable 93 sendablechooser 93 sensorbase 94 servo 95 smartdashboard 96 solenoid 99 wpil wpil ib solenoidbase 99 wpil wpil ib ibs spi 100 talon 102 135 RobotPy WPILib Documentation Release master wpil wpil wpil wpil wpil wpil ib ib ib iB victor 107 ip ib talonsrx 102 timer 103 ultrasonic 105 utility 107 victorsp 108 136 Python Module Index Index A all mutex wpilib solenoidbase SolenoidBase attribute AbsoluteTolerance_onTarget 99 wpilib pidcontroller PIDController method all ports wpilib solenoidbase SolenoidBase attribute 74 100 Accelerometer class in wpilib interfaces accelerometer 4llocate wpilib resource Resource method 85 123 allocated wpilib canjaguar CANJaguar attribute 26 Accelerometer Range class in allocatedDownSource wpilib counter Counter attribute wpilib interfaces accelerometer 123 45 1 add wpilib command scheduler Scheduler method allocatedUpSource wpilib counter Counter attribute 45 120 allocateInterrupts wpilib interruptablesensorbase InterruptableSensorBase addActuator wpilib livewindow LiveWindow static method 63 method 71 AnalogAccelerometer class in addActuatorChannel wpilib livewindow LiveWindow wpilib analogacce
95. cTime 0 1 Max time ms between readings Ultrasonic kPingTime 9 999999999999999e 06 Time sec for the ping trigger pulse Ultrasonic kPriority 90 Priority that the ultrasonic round robin task runs Ultrasonic kSpeedOfSoundInchesPerSec 13560 0 Ultrasonic pidGet Get the range in the current DistanceUnit PIDSource interface Returns The range in DistanceUnit Return type float Ultrasonic ping Single ping to ultrasonic sensor Send out a single ping to the ultrasonic sensor This only works if automatic round robin mode is disabled A single ping is sent out and the counter should count the semi period when it comes in The counter is reset to make the current value invalid Ultrasonic sensors lt _weakrefset WeakSet object at 0x7f2574e15fd0 ultrasonic sensor list Ultrasonic setAutomaticMode enabling Turn Automatic mode on off When in Automatic mode all sensors will fire in round robin waiting a set time between each sensor Parameters enabling bool Set to true if round robin scheduling should start for all the ultra sonic sensors This scheduling method assures that the sensors are non interfering because no two sensors fire at the same time If another scheduling algorithm is preffered it can be implemented by pinging the sensors manually and waiting for the results to come back Ultrasonic setDistanceUnits units Set the current DistanceUnit that should be used for the PIDSource in
96. ck that the analog input number is value Verify that the analog input number is one of the legal channel numbers Channel numbers are O based Parameters channel The channel number to check static checkAnalogOutputChannel channel Check that the analog input number is value Verify that the analog input number is one of the legal channel numbers Channel numbers are O based Parameters channel The channel number to check static checkDigitalChannel channel Check that the digital channel number is valid Verify that the channel number is one of the legal channel numbers Channel numbers are O based Parameters channel The channel number to check static checkPDPChannel channel Verify that the power distribution channel number is within limits Channel numbers are O based Parameters channel The channel number to check static checkPWMChannel channel Check that the digital channel number is valid Verify that the channel number is one of the legal channel numbers Channel numbers are O based Parameters channel The channel number to check static checkRelayChannel channel Check that the digital channel number is valid Verify that the channel number is one of the legal channel numbers Channel numbers are 0 based Parameters channel The channel number to check static checkSolenoidChannel channel Verify that the solenoid channel number is within limits Channel numbers are O based Parameters
97. class in wpilib spi 100 SPI Port class in wpilib spi 100 start wpilib command command Command method 114 start wpilib compressor Compressor method 42 start wpilib timer Timer method 104 startAutomaticCapture wpilib impl dummycamera CameoSgdeWhenActivel method 13 14 startCapture wpilib impl dummycamera USB Camera method 12 14 StartCommand class in wpilib command startcommand 121 startCompetition wpilib iterativerobot IterativeRobot method 66 startCompetition wpilib robotbase RobotBase method 86 startCompetition method 92 startRunning wpilib command command Command method 114 startTiming wpilib command command Command method 115 statusTable wpilib livewindow LiveWindow attribute 72 stop wpilib compressor Compressor method 42 stop wpilib timer Timer method 104 stopCapture wpilib impl dummycamera USB Camera method 12 14 stopMotor wpilib canjaguar CAN Jaguar method 34 stopMotor wpilib cantalon CANTalon method 41 stopMotor wpilib robotdrive RobotDrive method 90 stopMotor wpilib safepwm SafePWM method 91 Subsystem class in wpilib command subsystem 121 wpilib samplerobot SampleRobot TalonSRX class in wpilib talonsrx 102 tankDrive wpilib robotdrive RobotDrive method 90 task wpilib driverstation DriverStation method 55 teleopInit wpilib iterativerobot IterativeRobot method 66 teleopPeriodic wpil
98. count getAccumulatorValue Read the accumulated value 18 Chapter 1 Contents RobotPy WPILib Documentation Release master Read the value that has been accumulating The accumulator is attached after the oversample and average engine Returns The 64 bit value accumulated since the last reset getAverageBits Get the number of averaging bits This gets the number of averaging bits from the FPGA The actual number of averaged samples is 2 bits The averaging is done automatically in the FPGA Returns The number of averaging bits getAverageValue Get a sample from the output of the oversample and average engine for this channel The sample is 12 bit the bits configured in setOversampleBits The value configured in setAverageBits will cause this value to be averaged 2 bits number of samples This is not a sliding window The sample will not change until 2 OversampleBits AverageBits samples have been acquired from this channel Use getAverageVoltage to get the analog value in calibrated units Returns A sample from the oversample and average engine for this channel getAverageVoltage Get a scaled sample from the output of the oversample and average engine for this channel The value is scaled to units of Volts using the calibrated scaling data from get LSBWeight and getOffset Using oversampling will cause this value to be higher resolution but it will update more slowly Using averaging will cause
99. d by the value from setDistancePerPulse returns The current rate of the encoder Encoder getRaw Gets the raw value from the encoder The raw value is the actual count unscaled by the 1x 2x or 4x scale factor Returns Current raw count from the encoder Encoder getSamplesToAverage Get the Samples to Average which specifies the number of samples of the timer to average when calculating the period Perform averaging to account for mechanical imperfections or as oversampling to increase resolution Returns The number of samples being averaged from 1 to 127 Encoder getStopped Determine if the encoder is stopped Using the MaxPeriod value a boolean is returned that is True if the encoder is considered stopped and False if it is still moving A stopped encoder is one where the most recent pulse width exceeds the MaxPeriod Returns True if the encoder is considered stopped Encoder pidGet Implement the PIDSource interface Returns The current value of the selected source parameter 58 Chapter 1 Contents RobotPy WPILib Documentation Release master Encoder reset Reset the Encoder distance to zero Resets the current count to zero on the encoder Encoder setDistancePerPulse distancePerPulse Set the distance per pulse for this encoder This sets the multiplier used to determine the distance driven based on the count value from the encoder Do not include the decoding type
100. dsubsystem PIDSubsystem method 119 setAbsoluteTolerance wpilib pidcontroller PIDController method 75 setAccumulatorCenter wpilib analoginput AnalogInput method 20 setAccumulatorDeadband wpilib analoginput AnalogInput 20 setAccumulatorInitial Value wpilib analoginput AnalogInput 20 setAngle wpilib servo Servo method 96 setAutomaticMode wpilib ultrasonic Ultrasonic method 106 setAverageBits method 20 setAveraged wpilib analogtrigger AnalogTrigger method 22 setAxisChannel wpilib joystick Joystick method 70 setBounds wpilib pwm PWM method 82 setBrightness wpilib _impl dummycamera US BCamera method 12 13 setCANJaguarSyncGroup wpilib robotdrive RobotDrive 89 setChipSelectActiveHigh wpilib spi SPI method 101 setChipSelectActiveLow wpilib spi SPI method 101 setClockActiveHighQ wpilib spi SPI method 101 setClockActiveLow wpilib spi SPI method 101 setClockRate wpilib spi SPI method 101 setClosedLoopControl wpilib compressor Compressor method method wpilib analoginput AnalogInput method method 42 setCloseLoopRampRate wpilib cantalon CANTalon method 39 setContinuous wpilib pidcontroller PIDController method 75 setCurrentCommand wpilib command subsystem Subsystem method 122 setCurrentModeEncoder wpilib canjaguar CANJaguar method 30 setCurrentModePID method 31 setCurrentModePotentiometer w
101. e C Java so searching around the ChiefDelphi forums could be useful if you don t have a python specific question During the FRC build season you can probably expect answers to your questions within a day or two if you send messages to the mailing list As community members are also members of FRC teams you can expect that the closer we get to the end of the build season the harder it will be for community members to respond to your questions 1 9 1 Reporting Bugs If you run into a problem with RobotPy that you think is a bug or perhaps there is something wrong with the docu mentation or just too difficult to do please feel free to file bug reports on the github issue tracker Someone should respond within a day or two especially during the FIRST build season 1 9 2 Contributing new fixes or features RobotPy is intended to be a project that all members of the FIRST community can quickly and easily contribute to If you find a bug or have an idea that you think others can use 1 Fork this git repository to your github account Create your feature branch git checkout b my new feature Commit your changes git commit am Add some feature WwW N Push to the branch git push u origin my new feature 5 Create new Pull Request on github Github has a lot of documentation about forking repositories and pull requests so be sure to check out those resources 1 9 3 IRC During the FRC Build Season some RobotPy develop
102. e analog value in calibrated units Returns A sample straight from this channel getVoltage Get a scaled sample straight from this channel The value is scaled to units of Volts using the calibrated scaling data from get LSBWeight and getOffset Returns A scaled sample straight from this channel initAccumulator Initialize the accumulator isAccumulatorChannel Is the channel attached to an accumulator Returns The analog channel is attached to an accumulator kAccumulatorChannels 0 1 kAccumulatorSlot 1 pidGet Get the average voltage for use with PIDController Returns the average voltage resetAccumulator Resets the accumulator to the initial value setAccumulatorCenter center Set the center value of the accumulator The center value is subtracted from each A D value before it is added to the accumulator This is used for the center value of devices like gyros and accelerometers to make integration work and to take the device offset into account when integrating This center value is based on the output of the oversampled and averaged source from channel 1 Because of this any non zero oversample bits will affect the size of the value for this field setAccumulatorDeadband deadband Set the accumulator s deadband setAccumulatorInitialValue initialValue Set an initial value for the accumulator This will be added to all values returned to the user Parameters initial Value The v
103. e channel int Port for the digital input e input int True if input False otherwise channels lt wpilib resource Resource object at 0x7f2574eb3208 gt free getAnalogTriggerForRouting Is this an analog trigger Returns True if this is an analog trigger getChannelForRout ing Get the channel routing number Returns channel routing number getModuleForRout ing Get the module routing number Returns 0 port 1 3 20 DoubleSolenoid class woilib DoubleSolenoid args kwargs Bases woilib SolenoidBase Controls 2 channels of high voltage Digital Output The DoubleSolenoid class is typically used for pneumatics solenoids that have two positions controlled by two separate channels 1 3 wpilib Package 51 RobotPy WPILib Documentation Release master Constructor Arguments can be supplied as positional or keyword Acceptable positional argument combinations are eforwardChannel reverseChannel emoduleNumber forwardChannel reverseChannel Alternatively the above names can be used as keyword arguments Parameters e moduleNumber The module number of the solenoid module to use forwardChannel The forward channel number on the PCM 0 7 reverseChannel The reverse channel number on the PCM 0 7 class Value Bases builtins object Possible values for a DoubleSolenoid kForward 1 koff 0 kReverse 2 DoubleSolenoid free Mark the solenoid as freed DoubleSolen
104. e current command Parameters command the new current command setDefaultCommand command Sets the default command If this is not called or is called with None then there will be no default command for the subsystem Parameters command the default command or None if there should be none 1 5 9 WaitCommand class woilib command WaitCommand timeout name None Bases woilib command Command A WaitCommand will wait for a certain amount of time before finishing It is useful if you want a CommandGroup to pause for a moment See also CommandGroup Instantiates a WaitCommand with the given timeout Parameters timeout the time the command takes to run e name the name of the command optional isFinished 122 Chapter 1 Contents RobotPy WPILib Documentation Release master 1 5 10 WaitForChildren class woilib command WaitForChildren name None timeout None 1 5 11 WaitUntilCommand isFinished Bases woilib command Command Creates a new command This command will only finish if whatever CommandGroup it is in has no active children If it is not a part of a CommandGroup then it will finish immediately If it is itself an active child then the CommandGroup will never end This class is useful for the situation where you want to allow anything running in parallel to finish before continuing in the main CommandGroup sequence e name The name for this command if unspecified or No
105. e device Parameters codesPerRev The counts per revolution on the encoder CANJaguar setVoltageModePotentiometer Enable controlling the motor voltage with position feedback from a potentiometer and no speed feedback After calling this you must call enableControl to enable the device CANJaguar setVoltageModeQuadEncoder codesPerRev Enable controlling the motor voltage with position and speed feedback from a quadrature encoder After calling this you must call enableControl to enable the device 1 3 wpilib Package 33 RobotPy WPILib Documentation Release master Parameters e tag The constant link CANJaguar kOuadEncoder e codesPerRev The counts per revolution on the encoder CANJaguar setVoltageRampRate rampKate Set the maximum voltage change rate When in PercentVbus or Voltage output mode the rate at which the voltage changes can be limited to reduce current spikes set this to 0 0 to disable rate limiting Parameters rampRate The maximum rate of voltage change in Percent Voltage mode in V s CANJaguar setupPeriodicStatus Enables periodic status updates from the Jaguar CANJaguar stopMotor Common interface for stopping a motor CANJaguar updatePeriodicStatus Check for new periodic status updates and unpack them into local variables static CANJaguar updateSyncGroup syncGroup Update all the motors that have pending sets in the syncGroup Parameters syncGroup A bitma
106. e 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 gt IZone ClearlIaccum This is very useful in preventing integral windup and is highly recommended if using full PID to keep stability low CloseLoopRampRate is in throttle units per Ims Set to zero to disable ramping Works the same as RampThrot tle but only is in effect when a close loop mode and profile slot is selected class Cont rolMode Bases builtins object Current 3 Disabled 15 Follower 5 PercentVbus 0 1 3 wpilib Package 35 RobotPy WPILib Documentation Release master Position 1 Speed 2 Voltage 4 class CANTalon FeedbackDevice Bases builtins object AnalogEncoder 3 AnalogPot 2 EncFalling 5 EncRising 4 QuadEncoder 0 class CANTalon StatusFrameRate Bases builtins object enumerated types for frame rate ms AnalogTempVbat 3 Feedback 1 General 0 QuadEncoder 2 CANTalon changeControlMode controlMode CANTalon clearIaccum Clear the accumulator for I gain CANTalon clearStickyFaults CANTalon configFwdLimitSwitchNormallyOpen normallyOpen Configure the fwd limit switch to be normally open or normally closed Talon will disable momentarilly if the Talon s current setting is dissimilar to the caller s requested setting Since Talon saves setting to flash this should only affect a given
107. eWindowComponents static method wpilib livewindow LiveWindow static method 72 InOperatorControl wpilib driverstation DriverStation method 53 instances wpilib pidcontroller PIDController attribute 75 instances wpilib ultrasonic Ultrasonic attribute 105 InternalButton class in wpilib buttons internalbutton 110 interrupt Wpilib interruptablesensorbase InterruptableSensorBase attribute 63 InterruptableSensorBase class in wpilib interruptablesensorbase 63 interrupted wpilib command command Command method 113 interrupted wpilib command commandgroup CommandGroup method 116 interrupts wpilib interruptablesensorbase InterruptableSensorBase attribute 64 InTest wpilib driverstation DriverStation method 53 Invalid wpilib driverstation DriverStation Alliance at tribute 53 isAccumulatorChannel wpilib analoginput AnalogInput method 20 isAlive wpilib motorsafety MotorSafety method 73 isAutoCaptureStarted wpilib _impl dummycamera CameraServer method 12 14 Index 145 RobotPy WPILib Documentation Release master isAutomaticMode wpilib ultrasonic Ultrasonic static method 106 isAutonomous wpilib driverstation DriverStation method 55 isAutonomous wpilib robotbase RobotBase method 85 isAutonomous wpilib robotstate RobotState static method 91 isBlackListed wpilib solenoid Solenoid method 99 isBrownedOut wpilib driverstation D
108. eckPWMChannel wpilib sensorbase SensorBase static method 94 checkRelayChannel wpilib sensorbase SensorBase static method 94 checkSolenoidChannel wpilib sensorbase SensorBase static method 94 checkSolenoidModule wpilib sensorbase SensorBase static method 94 clearAIIPCMStickyFaults wpilib compressor Compressor method 41 clearAIIPCMStickyFaults wpilib solenoidbase SolenoidBase method 100 cancelConflicts wpilib command commandgroup Commafif1B9 nSource wpilib counter Counter method 45 method 116 cancelInterrupts wpilib interruptablesensorbase Interruptable Vator method 63 cancelWhenActive wpilib buttons trigger Trigger method 111 cancel WhenPressed wpilib buttons button Button method 109 CANJaguar class in wpilib canjaguar 25 CANJaguar ControlMode class in wpilib canjaguar 25 CANJaguar LimitMode class in wpilib canjaguar 25 CANJaguar Mode class in wpilib canjaguar 25 CANJaguar NeutralMode class in wpilib canjaguar 26 CANTalon class in wpilib cantalon 34 CANTalon ControlMode class in wpilib cantalon 35 CANTalon FeedbackDevice class in wpilib cantalon 36 CANTalon StatusFrameRate class in wpilib cantalon 36 changeControlMode wpilib canjaguar CANJaguar method 26 changeControlMode wpilib cantalon CANTalon method 36 channels wpilib analoginput AnalogInput attribute 18 channels wpilib analogoutput AnalogOutput attribute 21
109. ecodingScaleFactor The scale needed to convert a raw counter value into a number of encoder pulses 1 3 wpilib Package 57 RobotPy WPILib Documentation Release master Encoder get Gets the current count Returns the current count on the Encoder This method compensates for the decoding type Returns Current count from the Encoder adjusted for the 1x 2x or 4x scale factor Encoder getDirection The last direction the encoder value changed Returns The last direction the encoder value changed Encoder getDistance Get the distance the robot has driven since the last reset Returns The distance driven since the last reset as scaled by the value from setDistancePerPulse Encoder getEncodingScale Returns The encoding scale factor 1x 2x or 4x per the requested encodingType Used to divide raw edge counts down to spec d counts Encoder getFPGAIndex Returns The Encoder s FPGA index Encoder getPeriod Returns the period of the most recent pulse Returns the period of the most recent Encoder pulse in seconds This method compensates for the decoding type Deprecated since version Use get Rate in favor of this method This returns unscaled periods and getRate scales using value from getDistancePerPulse Returns Period in seconds of the most recent pulse Encoder getRate Get the current rate of the encoder Units are distance per second as scale
110. eed CANTalon getStickyFaultForLim CANTalon getStickyFaultForSoftLim CANTalon getStickyFaultOverTemp CANTalon getStickyFaultRevLim CANTalon getStickyFaultRevSoftLim CANTalon getStickyFaultUnderVoltage CANTalon getTemp Returns temperature of Talon in degrees Celsius CANTalon handle CANTalon isControlEnabled CANTalon isFwdLimitSwitchClosed Returns True if limit switch is closed False if open CANTalon isRevLimitSwitchClosed Returns True if limit switch is closed False if open CANTalon kDelayForSolicitedSignals 0 004 CANTalon pidWrite output CANTalon reverseOutput flip Flips the sign multiplies by negative one the throttle values going into the motor on the talon in closed loop modes Parameters flip True if motor output should be flipped False if not CANTalon reverseSensor flip Flips the sign multiplies by negative one the sensor values going into the talon This only affects position and velocity closed loop control Allows for situations where you may have a sensor flipped and going in the wrong direction Parameters flip True if sensor input should be flipped False if not CANTalon set outputValue syncGroup 0 Sets the appropriate output on the talon depending on the mode In PercentVbus the output is between 1 0 and 1 0 with 0 0 as stopped In Follower mode the output is the integer device ID of the talon to duplicate In Voltage mode
111. egral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller CANJaguar setCurrentModePotentiometer p i d Enable controlling the motor current with a PID loop and enable position sensing from a potentiometer After calling this you must call enableControl to enable the device Parameters e p The proportional gain of the Jaguar s PID controller e i The integral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller CANJaguar setCurrentModeQuadEncoder codesPerRev p i d Enable controlling the motor current with a PID loop and enable speed and position sensing from a quadrature encoder After calling this you must call enableControl to enable the device Parameters e codesPerRev The counts per revolution on the encoder e p The proportional gain of the Jaguar s PID controller e i The integral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller CANJaguar setD d Set the D constant for the closed loop modes Parameters d The derivative gain of the Jaguar s PID controller CANJaguar setI i Set the I constant for the closed loop modes Parameters i The integral gain of the Jaguar s PID controller CANJaguar setP p Set the P constant for the closed loop modes Parameters p The proportional gain of the Jaguar s PID controller CANJa
112. em clock 104 Chapter 1 Contents RobotPy WPILib Documentation Release master stop Stop the timer This computes the time as of now and clears the running flag causing all subseguent time reguests to be read from the accumulated time rather than looking at the system clock 1 3 55 Ultrasonic class woilib Ultrasonic pingChannel echoChannel units 0 Bases woilib SensorBase Ultrasonic rangefinder control The Ultrasonic rangefinder measures absolute distance based on the round trip time of a ping generated by the controller These sensors use two transducers a speaker and a microphone both tuned to the ultrasonic range A common ultrasonic sensor the Daventech SRF04 requires a short pulse to be generated on a digital channel This causes the chirp to be emmitted A second line becomes high as the ping is transmitted and goes low when the echo is received The time that the line is high determines the round trip distance time of flight Create an instance of the Ultrasonic Sensor This is designed to supchannel the Daventech SRFO4 and Vex ultrasonic sensors Parameters e pingChannel The digital output channel that sends the pulse to initiate the sensor sending the ping e echoChannel The digital input channel that receives the echo The length of time that the echo is high represents the round trip time of the ping and the distance e units The units returned in either kInches or kMillimeters class Un
113. en backup value will be returned Parameters e key the key e backup the value to return if none exists in the table Returns either the value in the table or the backup Raises ValueError if value cannot be converted to integer static get Instance Returns the preferences instance Returns the preferences instance getInt key backup Returns the int at the given key If this table does not have a value for that position then the given backup value will be returned Parameters e key the key e backup the value to return if none exists in the table Returns either the value in the table or the backup Raises ValueError if value cannot be converted to integer getKeys Returns a list of the keys getString key backup Returns the string at the given key If this table does not have a value for that position then the given backup value will be returned Parameters 78 Chapter 1 Contents RobotPy WPILib Documentation Release master e key the key e backup the value to return if none exists in the table Returns either the value in the table or the backup has key key Python style contains key keys Python style get list of keys put key value Puts the given value into the given key position Parameters e key the key e value the value putBoolean key value Puts the given float into the preferences table The key may not have any whitespace nor an eguals sign This
114. end the message every period milliseconds CANJaguar set outputValue syncGroup 0 Sets the output set point value The scale and the units depend on the mode the Jaguar is in In percentVbus Mode the outputValue is from 1 0 to 1 0 same as PWM Jaguar In voltage Mode the output Value is in volts In current Mode the outputValue is in amps In speed mode the outputValue is in rotations minute In position Mode the outputValue is in rotations Parameters e outputValue The set point to sent to the motor controller e syncGroup The update group to add this set to pending UpdateSyncGroup If 0 default update immediately CANJaguar setCurrentModeEncoder codesPerRev p i d Enable controlling the motor current with a PID loop and enable speed sensing from a non quadrature encoder After calling this you must call enableControl to enable the device 30 Chapter 1 Contents RobotPy WPILib Documentation Release master Parameters e p The proportional gain of the Jaguar s PID controller e i The integral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller CANJaguar setCurrentModePID p i d Enable controlling the motor current with a PID loop After calling this you must call enableControl to enable the device Parameters e p The proportional gain of the Jaguar s PID controller e i The int
115. enoid method 99 get wpilib talon Talon method 102 get wpilib talonsrx TalonSRX method 103 get wpilib timer Timer method 104 get wpilib victor Victor method 108 get wpilib victorsp VictorSP method 108 getAcceleration wpilib adxl345_i2c ADXL345_I2C method 15 getAcceleration Wwpilib adx1345 spi ADXL345 SPI method 16 getAcceleration wpilib analogaccelerometer AnalogAccelerometer method 17 140 Index RobotPy WPILib Documentation Release master getAccelerations wpilib adx1345 i2c ADXL345 I2C method 15 getAccelerations wpilib adx1345 spi ADXL345 SPI method 16 getAccumulatorCount wpilib analoginput AnalogInput method 18 getAccumulatorOutput wpilib analoginput AnalogInput method 18 getAccumulatorValue wpilib analoginput AnalogInput method 18 getAllQ wpilib solenoidbase SolenoidBase method 100 getAlliance wpilib driverstation DriverStation method 53 getAnalogInPosition wpilib cantalon CANTalon method 37 getAnalogInRaw wpilib cantalon CANTalon method 37 getAnalogInVelocity wpilib cantalon CANTalon method 37 getAnalogTriggerForRouting getBumper wpilib joystick Joystick method 68 getBusVoltage wpilib canjaguar CANJaguar method 28 getBus Voltage wpilib cantalon CANTalon method 37 getButton wpilib joystick Joystick method 68 getButtonCount wpilib joystick Joystick method 68 getCente
116. ent Kf float or int the feed forward term source A function or an object that implements PIDSource Called to get values output A function or an object that implements P TDOut put Receives the output per centage period float or int the loop time for doing calculations This particularly effects calcula tions of the integral and differential terms The default is 50ms AbsoluteTolerance_onTarget value PercentageTolerance onTarget percentage calculate Read the input calculate the output accordingly and write to the output This should only be called by the PIDTask and is created during initialization disable Stop running the PIDController this sets the output to zero before stopping enable Begin running the PIDController free Free the PID object get Return the current PID result This is always centered on zero and constrained the the max and min outs Returns the latest calculated output getD Get the Differential coefficient Returns differential coefficient 74 Chapter 1 Contents RobotPy WPILib Documentation Release master getError Returns the current difference of the input from the setpoint Returns the current error getF Get the Feed forward coefficient Returns feed forward coefficient getI Get the Integral coefficient Returns integral coefficient getP Get the Proportional coefficient Returns proportional coefficie
117. ent position getSetpoint Returns the setpoint Returns the setpoint onTarget Return True if the error is within the percentage of the total input range determined by setAbsoluteToler ance or setPercentTolerance This assumes that the maximum and minimum input were set using setInput Returns True if the error is less than the tolerance returnPIDInput Returns the input for the pid loop 118 Chapter 1 Contents RobotPy WPILib Documentation Release master It returns the input for the pid loop so if this command was based off of a gyro then it should return the angle of the gyro All subclasses of PIDSubsystem must override this method This method will be called in a different thread then the Scheduler thread Returns the value the pid loop should use as input setAbsoluteTolerance 1 Set the absolute error which is considered tolerable for use with OnTarget Parameters t The absolute tolerance same range as the PIDInput values setInputRange minimumInput maximumInput Sets the maximum and minimum values expected from the input Parameters e minimumInput the minimum value expected from the input e maximumiInput the maximum value expected from the output setOutputRange minimumOutput maximumOutput Sets the maximum and minimum values to write Parameters e minimumOutput the minimum value to write to the output e maximumOutput the maximum value to write to the output setPerc
118. entTolerance p Set the percentage error which is considered tolerable for use with OnTarget Parameters p The percentage tolerance value of 15 0 15 percent setSetpoint setpoint Sets the setpoint to the given value If set Range was called then the given setpoint will be trimmed to fit within the range Parameters setpoint the new setpoint setSetpointRelative deltaSetpoint Adds the given value to the setpoint If set Range was used then the bounds will still be honored by this method Parameters deltaSetpoint the change in the setpoint usePIDOutput output Uses the value that the pid loop calculated The calculated value is the output parameter This method is a good time to set motor values maybe something along the lines of driveline tankDrive output output All subclasses of PIDSubsystem should override this method This method will be called in a different thread then the Scheduler thread Parameters output the value the pid loop calculated 1 5 5 PrintCommand class wpilib command PrintCommand message Bases woilib command Command A PrintCommand is a command which prints out a string when it is initialized and then immediately finishes 1 5 wpilib command Package 119 RobotPy WPILib Documentation Release master It is useful if you want a CommandGroup to print out a string when it reaches a certain point Instantiates a PrintCommand which will print the given message w
119. equirements txt 1 7 4 install python3 installer py install PACKAGE PACKAGE J Copies python packages over to the roboRIO and installs them If the package already has been installed it will be reinstalled You can also use a requirements txt file to specify which packages should be downloaded python3 installer py download r requirements txt Warning The install command will only install packages that have been downloaded using the download command or packages that are on the robot s pypi cache Warning If your robot does not have a python3 interpeter installed this command will fail Run the install robotpy command first 1 8 Implementation Details This page contains various design implementation notes that are useful to people that are peering at the internals of WPILib HAL We will try to keep this document up to date 1 8 1 Design Goals The python implementation of WPILib HAL is derived from the Java implementation of WPILib In particular we strive to keep the python implementation of WPILib as close to the spirit of the original WPILib java libraries as we can only adding language specific features where it makes sense Things that you won t find in the original WPILib can be found in the impl package If you have a suggestion for things to add to WPILib we suggest adding it to the robotpy ext package which is a separate package for high guality code of things that should be in WPILib
120. er Returns The speed of the motor in RPM based on the configured feedback CANJaguar getTemperature Get the internal temperature of the Jaguar Returns The temperature of the Jaguar in degrees Celsius CANJaguar kApproxBusVoltage 12 0 CANJaguar kBusVoltageFault 4 CANJaguar kControllerRate 1000 CANJaguar kCurrentFault 1 CANJaguar kForwardLimit 1 CANJaguar kFullMessageIDMask 536870848 1 3 wpilib Package 29 RobotPy WPILib Documentation Release master CANJagu CANJagu CANJagu CANJagu CANJagu CANJagu CANJagu CANJagu CANJagu kGateDriverFault 8 kMaxMessageDataSize 8 kReceiveStatusAttempts 50 kReverseLimit 2 kSendMessagePeriod 20 kTemperatureFault 2 kTrustedMessages 33685760 33685824 33686976 33687040 33687872 33687936 33689024 336890 pidWrite output requestMessage messagelD period 0 Request a message from the Jaguar but don t wait for it to arrive Parameters e messageID The message to request e periodic If positive tell Network Communications to request the message every pe riod milliseconds CANJaguar sendMessage messagelD data period 0 Send a message to the Jaguar Parameters e messageID The messagelD to be used on the CAN bus device number is added inter nally e data The up to 8 bytes of data to be sent with the message e period If positive tell Network Communications to s
121. er Bases woilib SensorBase SolenoidBase class is the common base class for the Solenoid and DoubleSolenoid classes Constructor Parameters moduleNumber The PCM CAN ID all_allocated 1 3 wpilib Package 99 RobotPy WPILib Documentation Release master all mutex all ports f clearAl1lPCMStickyFaults Clear ALL sticky faults inside the PCM that Solenoid is wired to If a sticky fault is set then it will be persistently cleared Compressor drive maybe momentarily dis able while flages are being cleared Care should be taken to not call this too frequently otherwise normal compressor functionality may be prevented If no sticky faults are set then this call will have no effect getAll Read all 8 solenoids from the module used by this solenoid as a single byte Returns The current value of all 8 solenoids on this module getPCMSolenoidBlackList Reads complete solenoid blacklist for all 8 solenoids as a single byte If a solenoid is shorted it is added to the blacklist and disabled until power cycle or until faults are cleared See clearAl1lPCMStickyFaults Returns The solenoid blacklist of all 8 solenoids on the module getPCMSolenoidVoltageFault Returns True if PCM is in fault state The common highside solenoid voltage rail is too low most likely a solenoid channel has been shorted getPCMSolenoidVoltageStickyFault Returns True if PCM Sticky fault is set The common highside so
122. er via an AnalogInput Analog potentiometers read in an analog voltage that corresponds to a position The position is in whichever units you choose by way of the scaling and offset constants passed to the constructor AnalogPotentiometer constructor Use the fullRange and offset values so that the output produces meaningful values I E you have a 270 degree potentiometer and you want the output to be degrees with the halfway point as 0 degrees The fullRange value is 270 0 degrees and the offset is 135 0 since the halfway point after scaling is 135 degrees Parameters e channel int or AnalogInput The analog channel this potentiometer is plugged into fullRange float The scaling to multiply the fraction by to get a meaningful unit Defaults to 1 0 if unspecified offset float The offset to add to the scaled value for controlling the zero value Defaults to 0 0 if unspecified free get Get the current reading of the potentiometer Returns The current position of the potentiometer Return type float pidGet Implement the PIDSource interface 1 3 wpilib Package 21 RobotPy WPILib Documentation Release master Returns The current reading Return type float 1 3 9 AnalogTrigger class woilib AnalogTrigger channel Bases builtins object Converts an analog signal into a digital signal An analog trigger is a way to convert an analog signal into a digital signal using resources buil
123. erated type The button type will be looked up in the list of buttons and then read Parameters button Joystick ButtonType The type of button to read Returns The state of the button Return type bool Joystick getButtonCount For the current joystick return the number of buttons rtype int Joystick getDirectionDegrees Get the direction of the vector formed by the joystick and its origin in degrees Returns The direction of the vector in degrees Return type float Joystick getDirectionRadians Get the direction of the vector formed by the joystick and its origin in radians Returns The direction of the vector in radians Return type float Joystick getMagnitude Get the magnitude of the direction vector formed by the joystick s current position relative to its origin 68 Chapter 1 Contents RobotPy WPILib Documentation Release master Returns The magnitude of the direction vector Return type float Joystick getPOV pov 0 Get the state of a POV on the joystick Parameters pov int which POV default is 0 Returns The angle of the POV in degrees or 1 if the POV is not pressed Return type float Joystick getPOVCount For the current joystick return the number of POVs Return type int Joystick getRawAxis axis Get the value of the axis Parameters axis int The axis to read starting at 0 Returns The value of the axis Return type float Joystick getRawButton button Get
124. eriodic code for autonomous mode should go here Users should override this method for code which will be called periodically at a regular rate while the robot is in autonomous mode disabledInit Initialization code for disabled mode should go here Users should override this method for initialization code which will be called each time the robot enters disabled mode disabledPeriodic Periodic code for disabled mode should go here Users should override this method for code which will be called periodically at a regular rate while the robot is in disabled mode logger lt logging Logger object at 0x7f2574e50f98 gt A python logging object that you can use to send messages to the log It is recommended to use this instead of print statements nextPeriodReady Determine if the appropriate next periodic function should be called Call the periodic functions whenever a packet is received from the Driver Station or about every 20ms Return type bool prestart Don t immediately say that the robot s ready to be enabled see below robotInit Robot wide initialization code should go here Users should override this method for default Robot wide initialization which will be called when the robot is first powered on It will be called exactly 1 time Note It is simpler to override this function instead of defining a constructor for your robot class 1 3 wpilib Package 65 RobotPy WPILib Documentation Release
125. error to Driver Station and also prints error to sys stderr Optionally appends stack trace to error message Parameters printTrace If True append stack trace to error string 1 3 wpilib Package 55 RobotPy WPILib Documentation Release master DriverStation task Provides the service routine for the DS polling thread DriverStation waitForData timeout None Wait for new data or for timeout which ever comes first If timeout is None wait for new data only Parameters timeout The maximum time in milliseconds to wait 1 3 22 Encoder class woilib Encoder args kwargs Bases woilib SensorBase Reads from quadrature encoders Quadrature encoders are devices that count shaft rotation and can sense direction The output of the QuadEn coder class is an integer that can count either up or down and can go negative for reverse direction counting When creating QuadEncoders a direction is supplied that changes the sense of the output to make code more readable if the encoder is mounted such that forward movement generates negative values Quadrature encoders have two digital outputs an A Channel and a B Channel that are out of phase with each other to allow the FPGA to do direction sensing All encoders will immediately start counting reset them if you need them to be zeroed before use Instance variables eaSource The A phase of the quad encoder bSource The B phase of the quad encoder eindexSource The
126. ers may be able to be reached on robotpy channel on Freenode Note the channel is not very active but if you stick around long enough someone will probably answer your question think in terms of email response time 1 9 Support 131 RobotPy WPILib Documentation Release master 132 Chapter 1 Contents CHAPTER 2 Indices and tables e genindex e modindex e search 133 RobotPy WPILib Documentation Release master 134 Chapter 2 Indices and tables Python Module Index wpil wpil wpi lib adx Lib 10 lib impl dummycamera 13 345 120 14 wpil wpil ib adx1345_spi 16 wpil wpil ib analogaccelerometer 17 lib analoginput 18 ib analogoutput 21 wpil wpil ib analogpotentiometer 21 ib analogtrigger 22 wpil ib analogtriggeroutput 23 wpi lib bu tinaccelerometer 24 H wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil wpil ib bu lib bu ib bu lib bu lib bu ib bu lib ca ib can tons 109 tons button 109 internalbutton 110 joystickbutton 110 networkbutton 110 tons trigger 111 aguar 25 alon 34 and 111 and command 112 and commandgroup 115 and pidcommand 116 and pidsubsystem 118 a a a a a a CONS CONS CONS Dp JGR Gr GG oer gk SA Lib com Lib com ib com
127. etrieved by calling the get method with a key that is egual to the original key Parameters e key str the key e value str the value table None 98 Chapter 1 Contents RobotPy WPILib Documentation Release master tablesToData 1 3 49 Solenoid class woilib Solenoid args kwargs Bases woilib SolenoidBase Solenoid class for running high voltage Digital Output The Solenoid class is typically used for pneumatics solenoids but could be used for any device within the current spec of the PCM Constructor Arguments can be supplied as positional or keyword Acceptable positional argument combinations are echannel emoduleNumber channel Alternatively the above names can be used as keyword arguments Parameters e moduleNumber int The CAN ID of the PCM the solenoid is attached to e channel int The channel on the PCM to control 0 7 free Mark the solenoid as freed get Read the current value of the solenoid Returns The current value of the solenoid Return type bool isBlackListed Check if the solenoid is blacklisted If a solenoid is shorted it is added to the blacklist and disabled until power cycle or until faults are cleared See clearAl1PCMStickyFaults Returns If solenoid is disabled due to short set on Set the value of a solenoid Parameters on bool Turn the solenoid output off or on 1 3 50 SolenoidBase class woilib SolenoidBase moduleNumb
128. from the driver station Returns Has new data arrived over the network since the last time this function was called Return type bool isOperatorControl Determine if the robot is currently in Operator Control mode Returns True if the robot is currently operating in Tele Op mode as determined by the field controls Return type bool static isReal Returns If the robot is running in the real world Return type bool static isSimulation Returns If the robot is running in simulation Return type bool isTest Determine if the robot is currently in Test mode Returns True if the robot is currently operating in Test mode as determined by the driver station Return type bool static main robot_cls Starting point for the applications prestart This hook is called right before startCompetition By default tell the DS that the robot is now ready to be enabled If you don t want the robot to be enabled yet you can override this method to do noth ing If you do so you will need to call hal HALNetworkCommunicationObserveUserProgramStarting from your code when you are ready for the robot to be enabled startCompetition Provide an alternate main loop via startCompetition 86 Chapter 1 Contents RobotPy WPILib Documentation Release master 1 3 40 RobotDrive class woilib RobotDrive args kwargs Bases woilib MotorSafety Operations on a robot drivetrain based on a definition of the motor c
129. from the gyro less than this amount from the center is considered stationary Setting a deadband will decrease the amount of drift when the gyro isn t rotating but will make it less accurate Parameters volts float The size of the deadband in volts setPIDSourceParameter pidSource Set which parameter of the gyro you are using as a process control variable The Gyro class supports the rate and angle parameters Parameters pidSource PIDSource PIDSourceParameter An enum to select the pa rameter setSensitivity voltsPerDegreePerSecond Set the gyro sensitivity This takes the number of volts degree second sensitivity of the gyro and uses it in subsequent calculations to allow the code to work with multiple gyros This value is typically found in the gyro datasheet Parameters voltsPerDegreePerSecond float The sensitivity in Volts degree second 1 3 25 I2C class wpilib I2C port deviceAddress Bases builtins object I2C bus interface class This class is intended to be used by sensor and other I2C device drivers It probably should not be used directly Constructor Parameters e port The I2C port the device is connected to 1 3 wpilib Package 61 RobotPy WPILib Documentation Release master e deviceAddress The address of the device on the I2C bus class Port Bases builtins object kMXP 1 kOnboard 0 I2C addressOnly Attempt to address a device on the I2C bus This allows yo
130. gTrigger method 23 setForwardSoftLimit wpilib cantalon CANTalon method 40 setFPS wpilib _imp dummycamera USBCamera method 12 13 setGlobalSampleRate wpilib analoginput AnalogInput static method 20 setl wpilib canjaguar CANJaguar method 31 setI wpilib cantalon CANTalon method 40 setImage wpilib _impl dummycamera CameraServer method 13 14 setIndexSource wpilib encoder Encoder method 59 setLeftRightMotorOutputs wpilib robotdrive RobotDrive method 90 setLimitsRaw wpilib analogtrigger AnalogTrigger method 23 setLimitsVoltage wpilib analogtrigger AnalogTrigger method 23 setLSBFirst wpilib spi SPI method 101 setMaxOutput wpilib robotdrive RobotDrive method 90 setMaxPeriod wpilib counter Counter method 47 setMaxPeriod wpilib encoder Encoder method 59 setMaxPeriod wpilib interfaces counterbase CounterBase method 125 setMinRate wpilib encoder Encoder method 59 setMSBFirst wpilib spi SPI method 101 setOutput wpilib joystick Joystick method 70 setOutputRange wpilib command pidsubsystem PIDSubsystem method 119 setOutputRange wpilib pidcontroller PIDController method 75 setOutputs wpilib joystick Joystick method 71 setOversampleBits wpilib analoginput AnalogInput method 20 setP wpilib canjaguar CAN Jaguar method 31 setP wpilib cantalon CANTalon method 40 setParent wpilib command comm
131. gger AnalogTrigger getTriggerState Return the TriggerState output of the analog trigger True if above upper limit False if below lower limit If in Hysteresis maintain previous state Returns The TriggerState output of the analog trigger AnalogTrigger port 22 Chapter 1 Contents RobotPy WPILib Documentation Release master AnalogTrigger setAveraged useAveragedValue Configure the analog trigger to use the averaged vs raw values If the value is true then the averaged value is selected for the analog trigger otherwise the immediate value is used Parameters useAveraged Value True to use an averaged value False otherwise AnalogTrigger setFiltered useFilteredValue Configure the analog trigger to use a filtered value The analog trigger will operate with a 3 point average rejection filter This is designed to help with 360 degree pot applications for the period where the pot crosses through zero Parameters useFiltered Value True to use a filterd value False otherwise AnalogTrigger setLimitsRaw lower upper Set the upper and lower limits of the analog trigger The limits are given in ADC codes If oversampling is used the units must be scaled appropriately Parameters lower the lower raw limit e upper the upper raw limit AnalogTrigger setLimitsVoltage lower upper Set the upper and lower limits of the analog trigger The limits are given as floating point voltage values Paramete
132. guar setPID p i d Set the P I and D constants for the closed loop modes Parameters 1 3 wpilib Package 31 RobotPy WPILib Documentation Release master e p The proportional gain of the Jaguar s PID controller e i The integral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller CANJaguar setPercentMode Enable controlling the motor voltage as a percentage of the bus voltage without any position or speed feedback After calling this you must call enableControl to enable the device CANJaguar setPercentModeEncoder codesPerRev Enable controlling the motor voltage as a percentage of the bus voltage and enable speed sensing from a non quadrature encoder After calling this you must call enableControl to enable the device Parameters codesPerRev The counts per revolution on the encoder CANJaguar setPercentModePotentiometer Enable controlling the motor voltage as a percentage of the bus voltage and enable position sensing from a potentiometer and no speed feedback After calling this you must call enableControl to enable the device Parameters tag The constant link CANJaguar kPotentiometer CANJaguar setPercentModeQuadEncoder codesPerRev Enable controlling the motor voltage as a percentage of the bus voltage and enable position and speed sensing from a quadrature encoder After calling this you must call enableControl to enable
133. hboard static method 97 getEnabled3 V3 wpilib controllerpower ControllerPower static method 43 getEnabled5 V wpilib controllerpower ControllerPower static method 43 getEnabled6V wpilib controllerpower ControllerPower static method 43 getEncodingScale wpilib encoder Encoder method 58 getEncPosition wpilib cantalon CANTalon method 37 getEncVelocity wpilib cantalon CANTalon method 38 getError wpilib pidcontroller PIDController method 74 getExpiration method 73 getF wpilib cantalon CANTalon method 38 getF wpilib pidcontroller PIDController method 75 wpilib motorsafety MotorSafety static method 43 getFaultCount5 V wpilib controllerpower ControllerPower static method 43 getFaultCount6V wpilib controllerpower ControllerPower static method 43 getFaultForLim wpilib cantalon CANTalon method 38 wpilib cantalon CANTalon method 38 getFaultHardwareFailure wpilib cantalon CANTalon method 38 getFaultOverTemp wpilib cantalon CANTalon method 38 getFaultRevLim wpilib cantalon CANTalon method 38 getFaultRevSoftLimQ wpilib cantalon CANTalon method 38 getFaults wpilib canjaguar CANJaguar method 28 getFaultUnderVoltage wpilib cantalon CANTalon method 38 getFirmwareVersion wpilib canjaguar CANJaguar method 28 getFirmwareVersion wpilib cantalon CANTalon method 38 getFloat wpilib preferences Preferences method
134. he robot should be disabled False otherwise DriverStation isEnabled Gets a value indicating whether the Driver Station reguires the robot to be enabled Returns True if the robot is enabled False otherwise DriverStation isFMSAttached Is the driver station attached to a Field Management System Returns True if the robot is competing on a field being controlled by a Field Management Sys tem DriverStation isNewControlData Has a new control packet from the driver station arrived since the last time this function was called Returns True if the control data has been updated since the last call DriverStation isOperatorControl Gets a value indicating whether the Driver Station reguires the robot to be running in operator controlled mode Returns True if operator controlled mode should be enabled False otherwise DriverStation isSysActive Gets a value indicating whether the FPGA outputs are enabled The outputs may be disabled if the robot is disabled or e stopped the watdhog has expired or if the roboRIO browns out Returns True if the FPGA outputs are enabled DriverStation isTest Gets a value indicating whether the Driver Station requires the robot to be running in test mode Returns True if test mode should be enabled False otherwise DriverStation kJoystickPorts 6 The number of joystick ports DriverStation release Kill the thread static DriverStation reportError error printTrace Report
135. hen it is run Parameters message the message to print initialize isFinished 1 5 6 Scheduler class wpilib command Scheduler Bases woilib Sendable The Scheduler is a singleton which holds the top level running commands It is in charge of both calling the command s run method and to make sure that there are no two commands with conflicting requirements running It is fine if teams wish to take control of the Scheduler themselves all that needs to be done is to call Sched uler getInstance run often to have Commands function correctly However this is already done for you if you use the CommandBased Robot template See also Command Instantiates a Scheduler add command Adds the command to the Scheduler This will not add the Command immediately but will instead wait for the proper time in the run loop before doing so The command returns immediately and does nothing if given null Adding a Command to the Scheduler involves the Scheduler removing any Command which has shared requirements Parameters command the command to add addButton button Adds a button to the Scheduler The Scheduler will poll the button during its run Parameters button the button to add disable Disable the command scheduler enable Enable the command scheduler static getInstance Returns the Scheduler creating it if one does not exist Returns the Scheduler getName getType register
136. hod 116 wpilib command command Command method 113 execute execute wpilib command commandgroup CommandGroup method 116 F feed wpilib motorsafety MotorSafety method 73 Feedback wpilib cantalon CANTalon StatusFrameRate attribute 36 FILE_NAME wpilib preferences Preferences attribute 77 firstTime wpilib livewindow Live Window attribute 72 flush outputs wpilib joystick Joystick method 67 Follower Wwpilib cantalon CANTalon ControlMode at tribute 35 free wpilib analoginput AnalogInput method 18 free wpilib analogoutput AnalogOutput method 21 free wpilib analogpotentiometer AnalogPotentiometer method 21 free wpilib analogtrigger AnalogTrigger method 22 free wpilib analogtriggeroutput AnalogTriggerOutput method 24 free wpilib canjaguar CANJaguar method 27 free wpilib cantalon CANTalon method 37 free wpilib counter Counter method 46 free wpilib digitaloutput DigitalOutput method 50 free wpilib digitalsource DigitalSource method 51 free wpilib doublesolenoid DoubleSolenoid method 52 free wpilib encoder Encoder method 57 free wpilib gyro Gyro method 60 free wpilib pidcontroller PID Controller method 74 free wpilib pwm PWM method 81 free wpilib relay Relay method 84 free wpilib resource Resource method 85 free wpilib robotbase RobotBase method 85 free wpilib robotdrive RobotDrive method 8
137. ib interfaces controller module 124 wpilib interfaces counterbase module 124 wpilib interfaces generichid module 125 wpilib interfaces namedsendable module 127 wpilib interfaces pidoutput module 127 wpilib interfaces pidsource module 127 wpilib interfaces potentiometer module 127 ijib interfaces speedcontroller module 127 wpilib interruptablesensorbase module 63 wpilib iterativerobot module 64 wpilib jaguar module 66 wpilib joystick module 67 wpilib livewindow module 71 wpilib livewindowsendable module 72 wpilib motorsafety module 73 wpilib pidcontroller module 74 wpilib powerdistributionpanel module 76 wpilib preferences module 77 wpilib pwm module 80 wpilib relay module 83 wpilib resource module 84 wpilib robotbase module 85 wpilib robotdrive module 87 wpilib robotstate module 91 wpilib safepwm module 91 156 Index RobotPy WPILib Documentation Release master wpilib samplerobot module 91 wpilib sendable module 93 wpilib sendablechooser module 93 wpilib sensorbase module 94 wpilib servo module 95 wpilib smartdashboard module 96 wpilib solenoid module 99 wpilib solenoidbase module 99 wpilib spi module 100 wpilib talon module 102 wpilib talonsrx module 102 wpilib timer module 103 wpilib ultrasonic module 105 wpilib utility module 107 wpilib victor module 107 wpilib victorsp module 108 write wp
138. ib iterativerobot IterativeRobot method 66 test wpilib samplerobot SampleRobot method 92 testInit wpilib iterativerobot IterativeRobot method 66 testPeriodic wpilib iterativerobot IterativeRobot method 66 Timer class in wpilib timer 103 timeSincelnitialized wpilib command command Command method 115 wpilib buttons trigger Trigger method 111 toggleWhenPressed method 109 transaction wpilib i2c I2C method 62 transaction wpilib spi SPI method 101 Trigger class in wpilib buttons trigger 111 U Ultrasonic class in wpilib ultrasonic 105 Ultrasonic Unit class in wpilib ultrasonic 105 ultrasonicChecker wpilib ultrasonic Ultrasonic static method 106 wpilib buttons button Button updateDutyCycle wpilib digitaloutput DigitalOutput method 51 updatePeriodicStatus wpilib canjaguar CANJaguar method 34 updateSettings wpilib impl dummycamera USB Camera method 12 14 updateSyncGroup wpilib canjaguar CANJaguar static method 34 updateValues Wwpilib livewindow LiveWindow static method 72 USBCamera class in wpilib impl dummycamera 11 13 USBCamera WhiteBalance class in wpilib _impl dummycamera 11 13 SwitchInputsOnly wpilib canjaguar CA NJaguar LimitMode sepIDOutput wpilib command pidcommand PIDCommand attribute 25 T table wpilib smartdashboard SmartDashboard attribute 98 method 117 usePIDOutput wpilib command
139. ib smartdashboard SmartDashboard static method 98 PWM class in wpilib pwm 80 PWM PeriodMuttiplier class in wpilib pwm 81 pwmGenerator wpilib digitaloutput DigitalOutput attribute 50 Q QuadEncoder wpilib cantalon CANTalon FeedbackDevice attribute 36 QuadEncoder wpilib cantalon CANTalon StatusFrameRate attribute 36 R read wpilib i2c I2C method 62 read wpilib preferences Preferences method 80 read wpilib spi SPI method 101 readFallingTimestamp wpilib interruptablesensorbase InterruptableSenso method 64 readOnly wpilib i2c I2C method 62 readRisingTimestamp wpilib interruptablesensorbase InterruptableSensor method 64 Red Wpilib driverstation DriverStation Alliance at tribute 53 registerSubsystem wpilib command scheduler Scheduler method 120 Relay class in wpilib relay 83 Relay Direction class in wpilib relay 83 Relay Value class in wpilib relay 83 relayChannels wpilib relay Relay attribute 84 release wpilib driverstation DriverStation method 55 remove wpilib command scheduler Scheduler method 120 remove wpilib preferences Preferences method 80 removeAll wpilib command scheduler Scheduler method 121 removed wpilib command command Command method 114 reportError wpilib driverstation DriverStation static method 55 reguestInterrupts wpilib interruptablesensorbase InterruptableSensorBase method 64 requestMessage
140. ick ButtonType Bases builtins object Represents a digital button on the Joystick kNumButton 2 kTop 1 kTrigger 0 class Joystick RumbleType Bases builtins object Represents a rumble output on the Joystick kLeftRumble_val 0 kRightRumble_val 1 Joystick flush_outputs Flush all joystick HID amp rumble output values to the HAL 1 3 wpilib Package 67 RobotPy WPILib Documentation Release master Joystick getAxis axis For the current joystick return the axis determined by the argument This is for cases where the joystick axis is returned programmatically otherwise one of the previous functions would be preferable for example get X Parameters axis Joystick AxisType The axis to read Returns The value of the axis Return type float Joystick getAxisChannel axis Get the channel currently associated with the specified axis Parameters axis int The axis to look up the channel for Returns The channel for the axis Return type int Joystick getAxisCount For the current joystick return the number of axis Joystick getBumper hand None This is not supported for the Joystick This method is only here to complete the GenericHID interface Parameters hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface Returns The state of the bumper always False Return type bool Joystick getButton button Get buttons based on an enum
141. ified by calling requires normally in the constructor CommandGroups can also execute commands in parallel simply by adding them using addParallel See also Command Subsystem Creates a new CommandGroup with the given name Parameters name the name for this command group optional If None the name of this com mand will be set to its class name class Entry command state timeout Bases builtins object BRANCH_CHILD 2 BRANCH_PEER 1 IN_SEQUENCE 0 isTimedOut CommandGroup addParallel command timeout None Adds a new child Command to the group with an optional timeout The Command will be started after all the previously added Commands Once the Command is started it will run until it finishes is interrupted or the time expires if a timeout is provided whichever is sooner Note that the given Command will have no knowledge that it is on a timer Instead of waiting for the child to finish a CommandGroup will have it run at the same time as the subsequent Commands The child will run until either it finishes the timeout expires a new child with 1 5 wpilib command Package 115 RobotPy WPILib Documentation Release master conflicting reguirements is started or the main seguence runs a Command with conflicting reguirements In the latter two cases the child will be canceled even if it says it can t be interrupted Note that any reguirements the given Command has will be added to the group
142. ightOutput Set the speed of the right and left motors This is used once an appropriate drive setup function is called such as twoWheelDrive The motors are set to leftSpeed and rightSpeed and includes flipping the direction of one side for opposing motors Parameters e leftOutput The speed to send to the left side of the robot e rightOutput The speed to send to the right side of the robot RobotDrive setMaxOutput maxOutput Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus Parameters maxOutput Multiplied with the output percentage computed by the drive func tions RobotDrive setSensitivity sensitivity Set the turning sensitivity This only impacts the drive entry point Parameters sensitivity Effectively sets the turning sensitivity or turn radius for a given value RobotDrive stopMotor RobotDrive tankDrive args kwargs Provide tank steering using the stored robot configuration Either two joysticks with optional specified axis or two raw values may be passed positionally along with an optional squaredInputs boolean The valid positional combinations are eleftStick rightStick eleftStick rightStick sguaredInputs eleftStick leftAxis rightStick rightAxis eleftStick leftAxis rightStick rightAxis squaredInputs eleft Value rightValue eleft Value rightValue squaredInputs Alternatively the above names can be used
143. ilib command scheduler Scheduler method 120 enable wpilib interfaces controller Controller method 124 enable wpilib pidcontroller PIDController method 74 wpilib digitaloutput DigitalOutput enableBrakeMode wpilib cantalon CANTalon method 36 enableControl wpilib canjaguar CANJaguar method 21 enableControl wpilib cantalon CANTalon method 36 enabled wpilib compressor Compressor method 41 enableDeadbandElimination wpilib pwm PWM method 81 enableDirectionSensing wpilib geartooth GearTooth method 60 enableForwardSoftLimit wpilib cantalon CANTalon method 37 enableInterrupts wpilib interruptablesensorbase InterruptableSensorBase method 63 Index 139 RobotPy WPILib Documentation Release master enableLimitSwitch wpilib cantalon CANTalon method 37 enablePWM wpilib digitaloutput DigitalOutput method 50 enableReverseSoftLimit wpilib cantalon CANTalon method 37 EncFalling wpilib cantalon CANTalon Feedback Device attribute 36 Encoder class in wpilib encoder 56 encoder wpilib encoder Encoder attribute 57 Encoder EncodingType class in wpilib encoder 57 Encoder IndexingType class in wpilib encoder 57 Encoder PIDSourceParameter class in wpilib encoder 57 EncRising wpilib cantalon CANTalon FeedbackDevice attribute 36 end wpilib command command Command method 113 end wpilib command commandgroup CommandGroup met
144. ilib i2c I2C method 63 write wpilib spi SPI method 101 writeBulk wpilib i2c I2C method 63 Index 157
145. ilib victorsp VictorSP method 109 ping wpilib ultrasonic Ultrasonic method 106 port wpilib analogtrigger AnalogTrigger attribute 22 port wpilib digitalsource DigitalSource attribute 51 port wpilib pwm PWM attribute 82 port wpilib relay Relay attribute 84 Position wpilib canjaguar CANJaguar ControlMode at tribute 25 Position wpilib cantalon CANTalon ControlMode attribute 35 Potentiometer class in wpilib interfaces potentiometer 127 PowerDistributionPanel class in wpilib powerdistributionpanel 76 Preferences class in wpilib preferences 77 prestart wpilib iterativerobot IterativeRobot method 65 prestart wpilib robotbase RobotBase method 86 PrintCommand class in wpilib command printcommand 119 pulse wpilib digitaloutput DigitalOutput method 50 put wpilib preferences Preferences method 79 putBoolean wpilib preferences Preferences method 79 putBoolean wpilib smartdashboard SmartDashboard static method 97 putData wpilib smartdashboard SmartDashboard static method 98 putDouble wpilib smartdashboard SmartDashboard static method 98 putFloat wpilib preferences Preferences method 79 putInt wpilib preferences Preferences method 79 putIntQ wpilib smartdashboard SmartDashboard static method 98 putNumber wpilib smartdashboard SmartDashboard static method 98 putString wpilib preferences Preferences method 79 putString wpil
146. image it If you choose to install packages manually via pip keep in mind that when powered off your RoboRIO does not keep track of the correct date and as a result pip may fail with an SSL related error message To set the date you can either e Set the date via the web interface e You can login to your roboRIO via SSH and set the date via the date command date s 2015 01 03 00 00 00 Each of the commands supports various options which you can read about by invoking the help command 1 7 1 install robotpy python3 installer py install robotpy This will copy the appropriate RobotPy components to the robot and install them If the components are already installed on the robot then they will be reinstalled 128 Chapter 1 Contents RobotPy WPILib Documentation Release master 1 7 2 download robotpy python3 installer py download robotpy This will update the cached RobotPy packages to the newest versions available 1 7 3 download python3 installer py download PACKAGE PACKAGE Specify python package s to download similar to what you would pass the pip install command This command does not install files on the robot and must be executed from a computer with internet access You can run this command multiple times and files will not be removed from the download cache You can also use a requirements txt file to specify which packages should be downloaded python3 installer py download r r
147. imitOK wpilib canjaguar CANJaguar method 29 getSamplesToAverage wpilib counter Counter method 46 getSamplesToAverage wpilib encoder Encoder method 58 getSelected wpilib sendablechooser SendableChooser method 94 getSensorPosition wpilib cantalon CANTalon method 38 getSensorVelocity wpilib cantalon CANTalon method 38 getServoAngleRange wpilib servo Servo method 96 getSetpoint wpilib cantalon CANTalon method 38 getStickButton wpilib driverstation DriverStation method 54 getStickButtonCount wpilib driverstation DriverStation method 54 getStickButtons wpilib driverstation DriverStation method 54 getStickPOV wpilib driverstation DriverStation method 54 getStickPOVCount wpilib driverstation DriverStation method 54 getStickyFaultForLim wpilib cantalon CANTalon method 39 getStickyFaultForSoftLim wpilib cantalon CANTalon method 39 getStickyFaultOverTemp wpilib cantalon CANTalon method 39 getStickyFaultRevLim wpilib cantalon CANTalon method 39 getStickyFaultRevSoftLim wpilib cantalon CANTalon method 39 getStickyFaultUnderVoltage wpilib cantalon CANTalon method 39 getStopped wpilib counter Counter method 46 getStopped wpilib encoder Encoder method 58 getStopped wpilib interfaces counterbase CounterBase method 125 getString wpilib preferences Preferences method 78 getString wpilib smartdashboard SmartDashboa
148. in the forward direction 28 Chapter 1 Contents RobotPy WPILib Documentation Release master CANJaguar getHardwareVersion Get the version of the Jaguar hardware Returns The hardware version 1 Jaguar 2 Black Jaguar CANJaguar getiI Get the Integral gain of the controller Returns The integral gain CANJaguar getMessage messageID messageMask Get a previously reguested message Jaguar always generates a message with the same message ID when replying Parameters messageID The messageID to read from the CAN bus device number is added internally Returns The up to 8 bytes of data that was received with the message CANJaguar getOutputCurrent Get the current through the motor terminals of the Jaguar Returns The output current in Amps CANJaguar getOutputVoltage Get the voltage being output from the motor terminals of the Jaguar Returns The output voltage in Volts CANJaguar getP Get the Proportional gain of the controller Returns The proportional gain CANJaguar getPosition Get the position of the encoder or potentiometer Returns The position of the motor in rotations based on the configured feedback See configPotentiometerTurns and configEncoderCodesPerRev CANJaguar getReverseLimitoOkK Get the status of the reverse limit switch Returns True if the motor is allowed to turn in the reverse direction CANJaguar getSpeed Get the speed of the encod
149. index source available on some encoders Encoder constructor Construct a Encoder given a and b channels and optionally an index channel The encoder will start counting immediately The a b and optional index channel arguments may be either channel numbers or DigitalSource sources There may also be a boolean reverseDirection and an encodingType according to the following list eaSource bSource eaSource bSource reverseDirection eaSource bSource reverseDirection encodingType eaSource bSource indexSource reverseDirection eaSource bSource indexSource eaChannel bChannel eaChannel bChannel reverseDirection eaChannel bChannel reverseDirection encodingType eaChannel bChannel indexChannel reverseDirection eaChannel bChannel indexChannel For positional arguments if the passed object has a getChannelForRouting function it is assumed to be a DigitalSource Alternatively sources and or channels may be passed as keyword arguments The behavior of specifying both a source and a number for the same channel is undefined as is passing both a positional and a keyword argument for the same channel 56 Chapter 1 Contents RobotPy WPILib Documentation Release master In addition keyword parameters may be provided for reverseDirection and inputType Parameters aSource The source that should be used for the a channel bSource The source that should be used for the b channel indexSource The sou
150. ing system e Understand everything at all levels by making the full source code of the library available You can study and modify the algorithms used by the gyro class for oversampling and integration of the input signal or just ask the class for the current robot heading You can work at any level wpilib impl CameraServerl wpilib impl USBCameral name wpilib ADXL345 12C port range ADXL345 accelerometer device via i2c wpilib ADXL345 SP I port range ADXL345 accelerometer device via spi wpilib AnalogAccelerometer channel Analog Accelerometer wpilib AnalogInput channel Analog input wpilib AnalogOutput channel Analog output wpilib AnalogPotentiometer channel Reads a potentiometer via an AnalogInput wpilib AnalogTrigger channel Converts an analog signal into a digital signal wpilib AnalogTriggerOutput Represents a specific output from an AnalogTrigger wpilib BuiltInAccelerometer range Built in accelerometer device wpilib CANJaguar deviceNumber Texas Instruments Jaguar Speed Controller as a CAN device wpilib CANTalon deviceNumberl Talon SRX device as a CAN device wpilib Compressor pemld Operates the PCM Pneumatics compressor module wpilib ControllerPower Provides access to power levels on the RoboRIO wpilib Counter args kwargs Counts the number of ticks on a DigitalInput channel wpilib DigitalInput channel Reads a digital input wpilib DigitalOutput channel Writes to a digital output
151. ion Release master 2 Contents CHAPTER 1 Contents 1 1 Getting Started Welcome to RobotPy RobotPy is a community of FIRST mentors and students dedicated to developing python related projects for the FIRST Robotics Competition RobotPy WPILib is a set of libraries that are used on your roboRIO to enable you to use Python as your main pro gramming language for FIRST Robotics robot development It includes support for all components that are supported by WPILib s Java implementation The following instructions tell you how to install RobotPy on your robot If you want to run your python code on your computer of course you do then you need to install our python development support tools which is a separate project of ours called pyfrc For more information check out the pyfrc documentation site Note Once you ve got robotpy installed on your robot check out Anatomy of a robot to learn how to write robot code using python and RobotPy 1 1 1 Automated installation RobotPy is truly cross platform and can be installed from Windows most Linux distributions and from Mac OSX also Here s how you do it e Download RobotPy from github e Make sure Python 3 4 is installed Unzip the RobotPy zipfile somewhere on your computer not on the RoboRIO and there should be an installer py there Open up a command line change directory to the installer location and run this Windows py installer py install robotpy
152. it Bases builtins object The units to return when PIDGet is called kInches 0 kMillimeters 1 Ultrasonic automaticEnabled False Automatic round robin mode Ultrasonic getDistanceUnits Get the current DistanceUnit that is used for the PIDSource interface Returns The type of DistanceUnit that is being used Ultrasonic getRangeInches Get the range in inches from the ultrasonic sensor Returns Range in inches of the target returned from the ultrasonic sensor If there is no valid value yet i e at least one measurement hasn t completed then return 0 Return type float Ultrasonic getRangeMM Get the range in millimeters from the ultrasonic sensor Returns Range in millimeters of the target returned by the ultrasonic sensor If there is no valid value yet i e at least one measurement hasn t complted then return 0 Return type float Ultrasonic instances 0 1 3 wpilib Package 105 RobotPy WPILib Documentation Release master static Ultrasonic isAutomaticMode Ultrasonic isEnabled Is the ultrasonic enabled Returns True if the ultrasonic is enabled Ultrasonic isRangeValid Check if there is a valid range measurement The ranges are accumulated in a counter that will increment on each edge of the echo return signal If the count is not at least 2 then the range has not yet been measured and is invalid Returns True if the range is valid Return type bool Ultrasonic kMaxUltrasoni
153. it will not necessarily do so immediately and may in fact be canceled before initialize is even called startRunning This is used internally to mark that the command has been started The lifecycle of a command is startRunning is called 114 Chapter 1 Contents RobotPy WPILib Documentation Release master erun is called multiple times potentially removed is called It is very important that start Running and removed be called in order or some assumptions of the code will be broken startTiming Called to indicate that the timer should start This is called right before initialize is inside the run method timeSinceInitialized Returns the time since this command was initialized in seconds This function will work even if there is no specified timeout Returns the time since this command was initialized in seconds willRunWhenDisabled Returns whether or not this Command will run when the robot is disabled or if it will cancel itself 1 5 2 CommandGroup class wpilib command CommandGroup name None Bases woilib command Command A CommandGroup is a list of commands which are executed in sequence Commands in a CommandGroup are added using the addSequent ial method and are called sequentially CommandGroups are themselves Commands and can be given to other CommandGroups CommandGroups will carry all of the requirements of their subcommands Additional requirements can be spec
154. iverStation getStickButtonCount stick Gets the number of buttons on a joystick Parameters stick The joystick port number Returns The number of buttons on the indicated joystick DriverStation getStickButtons stick The state of all the buttons on the joystick Parameters stick The joystick port number Returns The state of all buttons as a bit array DriverStation getStickPOV stick pov Get the state of a POV on the joystick Parameters e stick The joystick port number e pov which POV Returns The angle of the POV in degrees or 1 if the POV is not pressed DriverStation getStickPOVCount stick Returns the number of POVs on a given joystick port Parameters stick The joystick port number 54 Chapter 1 Contents RobotPy WPILib Documentation Release master Returns The number of POVs on the indicated joystick DriverStation isAutonomous Gets a value indicating whether the Driver Station reguires the robot to be running in autonomous mode Returns True if autonomous mode should be enabled False otherwise DriverStation isBrownedOut Check if the system is browned out Returns True if the system is browned out DriverStation isDSAttached Is the driver station attached to the robot Returns True if the robot is being controlled by a driver station DriverStation isDisabled Gets a value indicating whether the Driver Station reguires the robot to be disabled Returns True if t
155. k Return type float Joystick getX hand None Get the X value of the joystick This depends on the mapping of the joystick connected to the current port Parameters hand Unused Returns The X value of the joystick Return type float Joystick getY hand None Get the Y value of the joystick This depends on the mapping of the joystick connected to the current port Parameters hand Unused Returns The Y value of the joystick Return type float Joystick getZ hand None Get the Z value of the joystick This depends on the mapping of the joystick connected to the current port Parameters hand Unused Returns The Z value of the joystick Return type float Joystick kDefaultThrottleAxis 3 Joystick kDefaultTopButton 2 Joystick kDefaultTriggerButton 1 Joystick kDefaultTwistAxis 2 Joystick kDefaultXAxis 0 Joystick kDefaultYAxis 1 Joystick kDefaultZAxis 2 Joystick setAxisChannel axis channel Set the channel associated with a specified axis Parameters e axis int The axis to set the channel for e channel int The channel to set the axis to 70 Chapter 1 Contents RobotPy WPILib Documentation Release master Joystick setOutput outputNumber value Set a single HID output value for the joystick Parameters e outputNumber The index of the output to set 1 32 e value The value to set the output to Joystick setOutputs value Set all HID output values for
156. k2G wpilib builtinaccelerometer BuiltInAccelerometer RangArcadeRatioCurve Reported attribute 24 wpilib robotdrive RobotDrive attribute k2G wpilib interfaces accelerometer Accelerometer Range 88 attribute 124 kArcadeStandard_Reported k2X wpilib counter Counter EncodingType attribute 45 wpilib robotdrive RobotDrive attribute k2X wpilib encoder Encoder EncodingType attribute 88 37 kAverageBits wpilib gyro Gyro attribute 61 k2X wpilib interfaces counterbase CounterBase EncodingTkpoth wpilib relay Relay Direction attribute 83 attribute 125 kBusVoltageFault wpilib canjaguar CANJaguar at k2X wpilib pwm PWM PeriodMultiplier attribute 81 tribute 29 k4G wpilib adx1345 i2c ADXL345 I2C Range at kCalibrationSampleTime wpilib gyro Gyro attribute 61 tribute 15 kControllerRate wpilib canjaguar CANJaguar attribute k4G wpilib adx1345 spi ADXL345 SPI Range at 29 tribute 16 kCurrentFault wpilib canjaguar CANJaguar attribute 29 k4G wpilib builtinaccelerometer BuiltInAccelerometer RangDataFormat FullRes wpilib adx1345 i2c ADXL345 I2C attribute 24 attribute 15 k4G wpilib interfaces accelerometer Accelerometer Range kDataFormat FullRes wpilib adx1345 spi ADXL345 SPI attribute 124 attribute 17 k4X wpilib counter Counter EncodingType attribute 45 kDataFormat IntInvert wpilib adx1345 12c ADXL345 IC k4X wpilib encoder Encoder EncodingType attribute attribute 15 57 kDataFormat IntInvert wpilib adx1345 spi ADX
157. lenoid voltage rail is too low most likely a solenoid channel has been shorted set value mask Set the value of a solenoid Parameters e value The value you want to set on the module e mask The channels you want to be affected 1 3 51 SPI class woilib SPI port Bases builtins object Represents a SPI bus port Constructor Parameters port the physical SPI port class Port Bases builtins object kMXP 4 kOnboardCS0 0 kOnboardCS1 1 100 Chapter 1 Contents RobotPy WPILib Documentation Release master kOnboardCS2 2 kOnboardCs3 3 SPI devices 0 SPI read initiate size Read a word from the receive FIFO Waits for the current transfer to complete if the receive FIFO is empty If the receive FIFO is empty there is no active transfer and initiate is False errors Parameters e initiate If True this function pushes 0 into the transmit buffer and initiates a transfer If False this function assumes that data is already in the receive FIFO from a previous write e size Number of bytes to read Returns received data bytes SPI setChipSelectActiveHigh Configure the chip select line to be active high SPI setChipSelectActiveLow Configure the chip select line to be active low SPI setClockActiveHigh Configure the clock output line to be active high This is sometimes called clock polarity low or clock idle low SPI setClockActiveLow Configure the clock
158. lerometer 17 static method 71 AnalogEncoder wpilib cantalon CANTalon FeedbackDevice addActuatorModuleChannel attribute 36 7 wpilib livewindow LiveWindow static AnalogInput class in wpilib analoginput 18 method 71 AnalogOutput class in wpilib analogoutput 21 addButton wpilib command scheduler Scheduler AnalogPot wpilib cantalon CANTalon Feedback Device method 120 attribute 36 addDefault wpilib sendablechooser SendableChooser AnalogPotentiometer class in method 93 wpilib analogpotentiometer 21 addObject wpilib sendablechooser SendableChooser AnalogTempVbat wpilib cantalon CANTalon StatusFrameRate method 93 attribute 36 addParallel wpilib command commandgroup CommandGripos Trigger class in wpilib analogtrigger 22 method 115 AnalogTrigger AnalogTriggerType class in addressOnly wpilib i2c I2C method 62 wpilib analogtrigger 22 l addSensor wpilib livewindow LiveWindow static AnalogTriggerOutput class 1n method 72 wpilib analogtriggeroutput 23 addSensorChannel wpilib livewindow LiveWindow AnalogTriggerOutput AnalogTriggerType class in static method 72 wpilib analogtriggeroutput 24 addSeguential wpilib command commandgroup CommanaS amp Prive wpilib robotdrive RobotDrive method 87 method 116 automaticEnabled wpilib ultrasonic Ultrasonic attribute ADXL345 I2C class in wpilib adx1345_i2c 14 105 7 ADXL345 I2C Axes class in wpilib adx1345_i2c 15 autonomous wpilib sampler
159. lerometer model There are constants defined for various models Parameters zero float The zero G voltage 1 3 6 Analoginput class woilib AnalogInput channel Bases woilib SensorBase Analog input Each analog channel is read from hardware as a 12 bit number representing OV to 5V Connected to each analog channel is an averaging and oversampling engine This engine accumulates the specified by setAverageBits and setOversampleBits number of samples before returning a new value This is not a sliding window average The only difference between the oversampled samples and the averaged samples is that the oversampled samples are simply accumulated effectively increasing the resolution while the averaged samples are divided by the number of samples to retain the resolution but get more stable values Construct an analog channel param channel The channel number to represent 0 3 are on board 4 7 are on the MXP port channels lt wpilib resource Resource object at 0x7f2574ed5f98 gt free getAccumulatorCount Read the number of accumulated values Read the count of the accumulated values since the accumulator was last reset Returns The number of times samples from the channel were accumulated getAccumulatorOutput Read the accumulated value and the number of accumulated values atomically This function reads the value and count from the FPGA atomically This can be used for averaging Returns tuple of value
160. lib canjaguar CANJaguar method 27 disable wpilib cantalon CANTalon method 36 disable wpilib command pidsubsystem PIDSubsystem method 118 disable wpilib command scheduler Scheduler method 120 attribute wpilib sensorbase SensorBase disable wpilib interfaces controller Controller method 124 disable wpilib interfaces speedcontroller SpeedController method 127 disable wpilib pidcontroller PIDController method 74 disable wpilib safepwm SafePWM method 91 disableControl wpilib canjaguar CANJaguar method 27 disableControl wpilib cantalon CANTalon method 36 Disabled wpilib cantalon CANTalon ControlMode at tribute 35 disabled wpilib samplerobot SampleRobot method 92 disabledInit wpilib iterativerobot IterativeRobot method 65 disabledPeriodic wpilib iterativerobot IterativeRobot method 65 disableInterrupts wpilib interruptablesensorbase InterruptableSensorBase method 63 disablePWM method 50 disableSoftPositionLimits wpilib canjaguar CANJaguar method 27 doesRequire wpilib command command Command method 113 DoubleSolenoid class in wpilib doublesolenoid 51 DoubleSolenoid Value class in wpilib doublesolenoid 52 drive wpilib robotdrive RobotDrive method 88 DriverStation class in wpilib driverstation 52 DriverStation Alliance class in wpilib driverstation 53 E enable wpilib command pidsubsystem PIDSubsystem method 118 enable wp
161. lib canjaguar CANJaguar method 29 getPosition wpilib cantalon CANTalon method 38 getPosition wpilib command pidcommand PIDCommand method 117 wpilib cantalon CANTalon getPosition wpilib command pidsubsystem PIDSubsystem method 118 getName wpilib interfaces namedsendable NamedSendabketPosition wpilib pwm PWM method 81 method 127 getPositiveScaleFactor wpilib pwm PWM method 81 Index 143 RobotPy WPILib Documentation Release master getPOV wpilib interfaces generichid GenericHID method 125 getPOV wpilib joystick Joystick method 69 getPOVCount wpilib joystick Joystick method 69 getPressureS witch Value wpilib compressor Compressor 42 getQuality wpilib impl dummycamera CameraServer method 12 14 getRangelInches wpilib ultrasonic Ultrasonic method 105 getRangeMM Wpilib ultrasonic Ultrasonic method 105 getRate wpilib counter Counter method 46 getRate wpilib encoder Encoder method 58 getRate wpilib gyro Gyro method 60 getRaw wpilib encoder Encoder method 58 getRaw wpilib pwm PWM method 82 getRawAxis wpilib interfaces generichid GenericHID method 126 getRawAxis wpilib joystick Joystick method 69 getRawButton wpilib interfaces generichid GenericHID method 126 getRawButton wpilib joystick Joystick method 69 getReguirements wpilib command command Command method 113 method getReverseL
162. lize data that needs to be initialized when your robot first starts Examples of this data includes e Variables that are used in multiple functions e Creating various wpilib objects for devices and sensors e Creating instances of other objects for your robot In python the constructor for an object is the __init__ function Instead of defining a constructor for your main robot object you can override robotInit instead If you do decide that you want to override __init__ then you must call super __init__ in your __init__ method or an exception will be thrown Adding motors and sensors Everything that interacts with the robot hardware directly must use the wpilib library to do so Starting in 2015 full documentation for the python version of WPILib is published online Check out the API documentation wp ilib for details on all the objects available in WPILib Note You should only create instances of your motors and other WPILib hardware devices Gyros Joysticks Sensors etc either during or after robotInit is called on your main robot object If you don t there are a lot of things that will fail Creating individual devices Let s say you wanted to create an object that interacted with a Jaguar motor controller via PWM First you would read through the table wpilib and see that there is a Jaguar object Looking further you can see that the constructor takes a single argument that indicates which PWM port to connect
163. lling position you can add additional limits on top of the limit switch inputs that are based on the position feedback If the position limit is reached or the switch is opened that direction will be disabled Parameters e forwardLimitPosition The position that if exceeded will disable the forward direction e reverseLimitPosition The position that if exceeded will disable the reverse direction CANJaguar disable Common interface for disabling a motor Deprecated since version 2015 Use disableControl instead CANJaguar disableControl Disable the closed loop controller Stop driving the output based on the feedback CANJaguar disableSoftPositionLimits Disable Soft Position Limits if previously enabled lt br gt Soft Position Limits are disabled by default CANJaguar enableControl encoderInitialPosition 0 0 Enable the closed loop controller Start actually controlling the output based on the feedback If starting a position controller with an encoder reference use the encoderInitialPosition parameter to initialize the encoder state Parameters encoderInitialPosition Encoder position to set if position with encoder reference default of 0 0 Ignored otherwise CANJaguar free Cancel periodic messages to the Jaguar effectively disabling it No other methods should be called after this is called 1 3 wpilib Package 27 RobotPy WPILib Documentation Release master CANJaguar get
164. ls 0 1 free Delete free the accumulator and the analog components used for the gyro getAngle Return the actual angle in degrees that the robot is currently facing The angle is based on the current accumulator value corrected by the oversampling rate the gyro type and the A D calibration values The angle is continuous that is it will continue from 360 to 361 degrees This allows algorithms that wouldn t want to see a discontinuity in the gyro output as it sweeps past from 360 to 0 on the second time around Returns The current heading of the robot in degrees This heading is based on integration of the returned rate from the gyro Return type float 60 Chapter 1 Contents RobotPy WPILib Documentation Release master getRate Return the rate of rotation of the gyro The rate is based on the most recent reading of the gyro analog value Returns the current rate in degrees per second Return type float kAverageBits 0 kCalibrationSampleTime 5 0 kDefaultVoltsPerDegreePerSecond 0 007 kOversampleBits 10 kSamplesPerSecond 50 0 pidGet Get the output of the gyro for use with PIDControllers Returns the current angle according to the gyro Return type float reset Reset the gyro Resets the gyro to a heading of zero This can be used if there is significant drift in the gyro and it needs to be recalibrated after it has been running setDeadband volts Set the size of the neutral zone Any voltage
165. ly and hasn t timed out Return type float isSafetyEnabled Return the state of the motor safety enabled flag Return if the motor safety is currently enabled for this device Returns True if motor safety is enforced for this device Return type bool setExpiration expirationTime Set the expiration time for the corresponding motor safety object Parameters expirationTime float The timeout value in seconds setSafetyEnabled enabled Enable disable motor safety for this device Turn on and off the motor safety option for this PWM object Parameters enabled bool True if motor safety is enforced for this object 1 3 wpilib Package 73 RobotPy WPILib Documentation Release master 1 3 33 PIDController class woilib PIDController args kwargs Bases woilib LiveWindowSendable Can be used to control devices via a PID Control Loop Creates a separate thread which reads the given PIDSource and takes care of the integral calculations as well as writing the given PIDOutput Allocate a PID object with the given constants for P I D and F Arguments can be structured as follows Kp Ki Kd Kf PIDSource PIDOutput period Kp Ki Kd PIDSource PIDOutput period Kp Ki Kd PIDSource PIDOutput Kp Ki Kd Kf PIDSource PIDOutput Parameters Kp float or int the proportional coefficient Ki float or int the integral coefficient Kd float or int the derivative coeffici
166. mandftime This will wait until the game clock reaches some value then continue to the ne 1 5 1 Command class woilib command Command name None timeout None Bases woilib Sendable The Command class is at the very core of the entire command framework Every command can be started with a call to start Once a command is started it will call initialize and then will repeatedly call execute until isFinished returns True Once it does end will be called However if at any point while it is running cancel is called then the command will be stopped and interrupted will be called If a command uses a Subsystem then it should specify that it does so by calling the requires method in its constructor Note that a Command may have multiple requirements and requires should be called for each one If a command is running and a new command with shared requirements is started then one of two things will happen If the active command is interruptible then cancel will be called and the command will be removed to make way for the new one If the active command is not interruptible the other one will not even be started and the active one will continue functioning See also Subsystem CommandGroup Creates a new command Parameters e name The name for this command if unspecified or None The name of this command will be set to its class name timeout The time in seconds before this command times out
167. method 24 getY Wwpilib interfaces accelerometer Accelerometer method 124 getY wpilib interfaces generichid GenericHID method 126 getY wpilib joystick Joystick method 70 getZ wpilib adx1345 i2c ADXL345 I2C method 15 getZ wpilib adx1345 spi ADXL345 SPI method 17 getZ wpilib builtinaccelerometer BuiltInAccelerometer method 25 getZ wpilib interfaces accelerometer Accelerometer method 124 getZ wpilib interfaces generichid GenericHID method 126 getZ wpilib joystick Joystick method 70 grab wpilib buttons trigger Trigger method 111 Gyro class in wpilib gyro 60 H handle wpilib cantalon CANTalon attribute 39 has_key wpilib preferences Preferences method 79 hasPeriodPassed wpilib timer Timer method 104 helpers wpilib motorsafety MotorSafety attribute 73 holonomicDrive wpilib robotdrive RobotDrive method 88 InAutonomous wpilib driverstation DriverStation method 53 53 initAccumulator wpilib analoginput AnalogInput method 20 initDefaultCommand wpilib command subsystem Subsystem method 122 initialize wpilib command command Command method 113 initialize wpilib command commandgroup CommandGroup method 116 initialize wpilib command printcommand PrintCommand method 120 initialize wpilib command startcommand StartCommand method 121 initializeHardwareConfiguration wpilib robotbase RobotBase 85 initializeLiv
168. mperes Return type float getTemperature Query the temperature of the PDP Returns The temperature of the PDP in degrees Celsius Return type float getTotalCurrent Query the current of all monitored PDP channels 0 15 76 Chapter 1 Contents RobotPy WPILib Documentation Release master Returns The total current drawn from the PDP channels in Amperes Return type float getTotalEnergy Query the total energy drawn from the monitored PDP channels Returns The total energy drawn from the PDP channels in Joules Return type float getTotalPower Query the total power drawn from the monitored PDP channels Returns The total power drawn from the PDP channels in Watts Return type float getVoltage Query the voltage of the PDP Returns The voltage of the PDP in volts Return type float resetTotalEnergy Reset the total energy to 0 1 3 35 Preferences class wpilib Preferences Bases builtins object Provides a relatively simple way to save important values to the RoboRIO to access the next time the RoboRIO is booted This class loads and saves from a file inside the RoboRIO The user can not access the file directly but may modify values at specific fields which will then be saved to the file when save is called This class is thread safe This will also interact with net worktables NetworkTable by creating a table called Preferences with all the key value pairs To save using NetworkTable simply
169. n of the Talon The upper 14 bits tracks the overflows and underflows continuous sensor CANTalon getAnalogInRaw Get the current analog in position regardless of whether it is the current feedback device returns The ADC 0 1023 on analog pin of the Talon CANTalon getAnalogInVelocity Get the current encoder velocity regardless of whether it is the current feedback device Returns The current speed of the analog in device CANTalon getBrakeEnableDuringNeutral Returns True if break is enabled during neutral False if coast CANTalon getBusVoltage Returns The voltage at the battery terminals of the Talon in Volts CANTalon getCloseLoopRampRate Get the closed loop ramp rate for the current profile Limits the rate at which the throttle will change Only affects position and speed closed loop modes Returns rampRate Maximum change in voltage in volts sec See setProfile For selecting a certain profile CANTalon getClosedLoopError Get the current difference between the setpoint and the sensor value Returns The error in whatever units are appropriate CANTalon getControlMode CANTalon getD CANTalon getDescription CANTalon getDevicelD 1 3 wpilib Package 37 RobotPy WPILib Documentation Release master CANTalon getEncPosition Get the current encoder position regardless of whether it is the current feedback device Returns The current position of the encoder
170. n what code you claim to be executing for diagnostic purposes only Parameters entering If True starting autonomous code if False leaving autonomous code DriverStation InDisabled entering Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only Parameters entering If True starting disabled code if False leaving disabled code DriverStation InOperatorControl entering Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only Parameters entering If True starting teleop code if False leaving teleop code DriverStation InTest entering Only to be used to tell the Driver Station what code you claim to be executing for diagnostic purposes only Parameters entering If True starting test code if False leaving test code DriverStation getAlliance Get the current alliance from the FMS Returns The current alliance Return type DriverStation Alliance DriverStation getBatteryVoltage Read the battery voltage Returns The battery voltage in Volts DriverStation getData Copy data from the DS task for the user If no new data exists it will just be returned otherwise the data will be copied from the DS polling loop static DriverStation getInstance Gets the global instance of the DriverStation Returns DriverStation DriverStation getLocation Gets the location of the team s driver station con
171. nModeQuadEncoder wpilib canjaguar CANJaguar method 32 setPositionReference wpilib canjaguar CANJaguar method 32 setPressed wpilib buttons internalbutton InternalButton method 110 setProfile wpilib cantalon CANTalon method 41 setPulseLengthMode wpilib counter Counter method 48 setPWMRate method 50 setQuality wpilib _impl dummycamera CameraServer method 13 14 setRange wpilib adx1345 i2c ADXL345 I2C method 16 setRange wpilib adx1345 spi ADXL345 SPI method 17 wpilib digitaloutput DigitalOutput setRange wpilib builtinaccelerometer BuiltInAccelerometsetTimeout method 25 setRange wpilib interfaces accelerometer Accelerometer setTolerance method 124 setRaw wpilib pwm PWM method 83 setReverseDirection wpilib counter Counter method 48 setReverseDirection wpilib encoder Encoder method 59 setReverseSoftLimit wpilib cantalon CANTalon method 41 setRumble wpilib joystick Joystick method 71 setRunWhenDisabled wpilib command command CommaedUpSourceEdge wpilib interruptablesensorbase InterruptableSensorBas method 114 setSafetyEnabled method 73 setSampleDataOnFalling wpilib spi SPI method 101 setSampleDataOnRising wpilib spi SPI method 101 setSamplesToAverage wpilib counter Counter method wpilib motorsafety MotorSafety 48 setSamplesToAverage wpilib encoder Encoder method 59 setSemiPeriodMode wpilib c
172. nd in the PIDCont roller set speed syncGroup 0 Set the PWM value The PWM value is set using a range of 1 0 to 1 0 appropriately scaling the value for the FPGA Parameters e speed float The speed to set Value should be between 1 0 and 1 0 66 Chapter 1 Contents RobotPy WPILib Documentation Release master e syncGroup The update group to add this set to pending updateSyncGroup If 0 update immediately 1 3 29 Joystick class woilib Joystick port numAxisTypes None numButtonTypes None Bases builtins object Handle input from standard Joysticks connected to the Driver Station This class handles standard input that comes from the Driver Station Each time a value is requested the most recent value is returned There is a single class instance for each joystick and the mapping of ports to hardware buttons depends on the code in the driver station Construct an instance of a joystick The joystick index is the usb port on the drivers station This constructor is intended for use by subclasses to configure the number of constants for axes and buttons Parameters e port int The port on the driver station that the joystick is plugged into e numAxisTypes int The number of axis types e numButtonTypes int The number of button types class AxisType Bases builtins object Represents an analog axis on a joystick kNumAxis 5 kThrottle 4 kTwist 3 kx 0 ky 1 kZ 2 class Joyst
173. nds since boot reguestInterrupts handler None Request one of the 8 interrupts asynchronously on this digital input Parameters handler optional The function that will be called whenever there is an interrupt on this device Request interrupts in synchronous mode where the user program interrupt handler will be called when an interrupt occurs The default is interrupt on rising edges only If not specified the user program will have to explicitly wait for the interrupt to occur using waitForInterrupt set UpSourceEdge risingEdge fallingEdge Set which edge to trigger interrupts on Parameters e risingEdge True to interrupt on rising edge e fallingEdge True to interrupt on falling edge waitForInterrupt timeout ignorePrevious True In synchronous mode wait for the defined interrupt to occur You should NOT attempt to read the sensor from another thread while waiting for an interrupt This is not threadsafe and can cause memory corruption Parameters timeout Timeout in seconds e ignorePrevious If True default ignore interrupts that happened before waitForInter rupt was called 1 3 27 IterativeRobot class wpilib IterativeRobot Bases woilib RobotBase IterativeRobot implements a specific type of Robot Program framework extending the Robot Base class The IterativeRobot class is intended to be subclassed by a user creating a robot program This class is intended to implement the old style def
174. ne The name of this command will be set to its class name timeout The time in seconds before this command times out Default is no timeout See isTimedOut class woilib command WaitUntilCommand time 1 6 wpilib interfaces Package isFinished Bases woilib command Command This will wait until the game clock reaches some value then continue to the next command This package contains objects that can be used to determine the requirements of various interfaces used in WPILib Generally the python version of WPILib does not require that you inherit from any of these interfaces but instead will allow you to use custom objects as long as they have the same methods wpilib in Accelerometer Interface for 3 axis accelerometers wpilib in Co An interface for controllers wpilib in CounterBase Interface for counting the number of ticks on a digital input channel wpilib in Ge GenericHID Interface wpilib in NamedSendabl The interface for sendable objects that gives the sendable a default name in the Sr wpilib in JPI This interface allows PIDController to write its results to its output wpilib in 2 PI This interface allows for PIDCont roller to automatically read from this objec wpilib in Potentiometer wpilib in SpeedController Interface for speed controlling devices 1 6 1 Accelerometer class wpilib interfaces Accelerometer Bases builtins object Interface for 3 axis accelerometers
175. nsitivity on an down counting source Set the down source to either detect rising edges or falling edges Parameters e risingEdge bool True to count rising edge e fallingEdge bool True to count falling edge Counter setExternalDirectionMode Set external direction mode on this counter Counts are sourced on the Up counter input The Down counter input represents the direction to count Counter setMaxPeriod maxPeriod Set the maximum period where the device is still considered moving Sets the maximum period where 1 3 wpilib Package 47 RobotPy WPILib Documentation Release master the device is considered moving This value is used to determine the stopped state of the counter using the get Stopped method Parameters maxPeriod float or int The maximum period where the counted device is con sidered moving in seconds Counter setPIDSourceParameter pidSource Set which parameter of the encoder you are using as a process control variable The counter class supports the rate and distance parameters Parameters pidSource Counter PIDSourceParameter An enum to select the pa rameter Counter setPulseLengthMode threshold Configure the counter to count in up or down based on the length of the input pulse This mode is most useful for direction sensitive gear tooth sensors Parameters threshold float int The pulse length beyond which the counter counts the op posite direction Uni
176. nt getSetpoint Returns the current setpoint of the PID Controller Returns the current setpoint instances 0 isEnable Return True if PIDController is enabled kDefaultPeriod 0 05 onTarget Return True if the error is within the percentage of the total input range determined by setTolerance This assumes that the maximum and minimum input were set using set Input Returns True if the error is less than the tolerance reset Reset the previous error the integral term and disable the controller setAbsoluteTolerance absvalue Set the absolute error which is considered tolerable for use with onTarget Parameters absvalue absolute error which is tolerable in the units of the input object setContinuous continuous True Set the PID controller to consider the input to be continuous Rather then using the max and min in as constraints it considers them to be the same point and automatically calculates the shortest route to the setpoint Parameters continuous Set to True turns on continuous False turns off continuous setInputRange minimumInput maximumInput Sets the maximum and minimum values expected from the input Parameters e minimumInput the minimum percentage expected from the input e maximumiInput the maximum percentage expected from the output setOutputRange minimumOutput maximumOutput Sets the minimum and maximum values to write Parameters 1 3 wpilib Package 75
177. ntCommand wpilib command subsystem SubsysteetFaultCount3 V3 wpilib controllerpower ControllerPower method 122 getDQ wpilib canjaguar CANJaguar method 28 getD wpilib cantalon CANTalon method 37 getD wpilib pidcontroller PID Controller method 74 getData wpilib driverstation DriverStation method 53 getData wpilib smartdashboard SmartDashboard static method 97 getDefaultCommand wpilib command subsystem SubsystgatrFaultForSoftLim method 122 getDefaultSolenoidModule wpilib sensorbase SensorBase static method 95 getDescription wpilib canjaguar CANJaguar method 28 getDescription wpilib cantalon CANTalon method 37 getDescription wpilib robotdrive RobotDrive method 88 getDescription wpilib safepwm SafePWM method 91 getDeviceIDQ wpilib canjaguar CANJaguar method 28 getDeviceIDQ wpilib cantalon CANTalon method 37 getDeviceNumber wpilib canjaguar CANJaguar method 28 getDirection wpilib counter Counter method 46 getDirection wpilib encoder Encoder method 58 getDirection wpilib interfaces counterbase CounterBase method 125 getDirectionDegrees wpilib joystick Joystick method 68 getDirectionRadians wpilib joystick Joystick method 68 getDistance wpilib counter Counter method 46 getDistance wpilib encoder Encoder method 58 getDistanceUnits wpilib ultrasonic Ultrasonic method 105 getDouble wpilib smartdashboard SmartDas
178. number to be used for the underlying PWM object 0 9 are on board 10 19 are on the MXP port disable getDescription stopMotor Stop the motor associated with this PWM object This is called by the MotorSafety object when it has a timeout for this PWM and needs to stop it from running 1 3 43 SampleRobot class wwilib SampleRobot Bases woilib RobotBase A simple robot base class that knows the standard FRC competition states disabled autonomous or operator controlled 1 3 wpilib Package 91 RobotPy WPILib Documentation Release master You can build a simple robot program off of this by overriding the robotinit disabled autonomous and operatorControl methods The startCompetition method will call these methods sometimes repeatedly depending on the state of the competition Alternatively you can override the robotMain method and manage all aspects of the robot yourself not recommended Warning While it may look like a good choice to use for your code if you re inexperienced don t Unless you know what you are doing complex code will be much more difficult under this system Use IterativeRobot or command based instead if you re new autonomous Autonomous should go here Users should add autonomous code to this method that should run while the field is in the autonomous period Called once each time the robot enters the autonomous state disabled Disabled should go here Users
179. obot SampleRobot ADXL345 I2C Range class in wpilib adx1345_i2c 15 method 92 ADXL345_SPI class in wpilib adx1345 spi 16 autonomousInit wpilib iterativerobot IterativeRobot ADXL345_SPI Axes class in wpilib adx1345 spi 16 method 65 ADXL345 SPI Range class in wpilib adx1345_spi 16 autonomousPeriodic wpilib iterativerobot IterativeRobot all_allocated wpilib solenoidbase SolenoidBase at method 65 tribute 99 137 RobotPy WPILib Documentation Release master B Blue wpilib driverstation DriverStation Alliance at tribute 53 Brake wpilib canjaguar CANJaguar NeutralMode at tribute 26 checkAnalogOutputChannel wpilib sensorbase SensorBase static method 94 checkDigitalChannel wpilib sensorbase SensorBase static method 94 BRANCH CHILD wpilib command commandgroup ComifiH8EKMAfp KOtry Wpilib motorsafety MotorSafety static attribute 115 BRANCH PEER wpilib command commandgroup Commaiher bP Ehaynel attribute 115 broadcast wpilib i2c I2C method 62 BuiltInAccelerometer class in wpilib builtinaccelerometer 24 BuiltInAccelerometer Range class in wpilib builtinaccelerometer 24 Button class in wpilib buttons button 109 C calculate wpilib pidcontroller PIDController method 74 CameraServer class in wpilib impl dummycamera 12 14 cancel wpilib command command Command method 112 method 73 wpilib sensorbase SensorBase static method 94 ch
180. obtain voltage current temperature power and energy from the CAN PD wpilib Preferences Provides a relatively simple way to save important values to the RoboRIO to acce wpilib PWM channel Raw interface to PWM generation in the FPGA wpilib Relay channelf direction Controls VEX Robotics Spike style relay outputs wpilib Resource size Tracks resources in the program wpilib RobotBase Implement a Robot Program framework wpilib RobotDrive args kwargs Operations on a robot drivetrain based on a definition of the motor configuration wpilib RobotState Provides an interface to determine the current operating state of the robot code wpilib SafePwM channel A raw PWM interface that implements the MotorSafety interface wpilib SampleRobotQ A simple robot base class that knows the standard FRC competition states disabl wpilib Sendable The base interface for objects that can be sent over the network wpilib SendableChooser A useful tool for presenting a selection of options to be displayed on wpilib SensorBase Base class for all sensors wpilib Servo channel Standard hobby style servo wpilib SmartDashboard The bridge between robot programs and the SmartDashboard on the laptop wpilib Solenoid args kwargs Solenoid class for running high voltage Digital Output wpilib SolenoidBase moduleNumber SolenoidBase class is the common base class for the Solenoid and DoubleSolenoi wpilib SP I port Represents a SPI bus port wpilib Talon channel Cross the
181. oid method 52 isRunning wpilib command command Command method 114 isSafetyEnabled wpilib motorsafety MotorSafety method 73 isSimulation wpilib robotbase RobotBase static method 86 isSysActive wpilib driverstation DriverStation method 55 isTest wpilib driverstation DriverStation method 55 isTest wpilib robotbase RobotBase method 86 isFinished wpilib command commandgroup CommandGrasfest wpilib robotstate RobotState static method 91 method 116 isFinished wpilib command printcommand PrintCommand isTimedOut wpilib command commandgroup CommandGroup Entry method 120 isFinished wpilib command startcommand StartCommand method 121 isTimedOut wpilib command command Command method 114 method 115 IterativeRobot class in wpilib iterativerobot 64 isFinished wpilib command waitcommand WaitCommand method 122 isFinished wpilib command waitforchildren WaitForChildygguar class in wpilib jaguar 66 method 123 Joystick class in wpilib joystick 67 isFinished wpilib command waituntilcommand WaitUntil gnynqad xisType class in wpilib joystick 67 method 123 isFMSAttached wpilib driverstation DriverStation method 55 isFwdLimitSwitchClosed wpilib cantalon CANTalon method 39 isFwdSolenoidBlackListed wpilib doublesolenoid DoubleSolenoid method 52 isInterruptible wpilib command command Command method 113 Joystick B
182. oid get Read the current value of the solenoid Returns The current value of the solenoid Return type DoubleSolenoid Value DoubleSolenoid isFwdSolenoidBlackListed Check if the forward solenoid is blacklisted If a solenoid is shorted it is added to the blacklist and disabled until power cycle or until faults are cleared See clearAl1PCMStickyFaults Returns If solenoid is disabled due to short DoubleSolenoid isRevSolenoidBlackListed Check if the reverse solenoid is blacklisted If a solenoid is shorted it is added to the blacklist and dis abled until power cycle or until faults are cleared See clearAl1PCMStickyFaults Returns If solenoid is disabled due to short DoubleSolenoid set value Set the value of a solenoid Parameters value DoubleSolenoid Value The value to set Off Forward Reverse 1 3 21 DriverStation class woilib DriverStation Bases builtins object Provide access to the network communication data to from the Driver Station 52 Chapter 1 Contents RobotPy WPILib Documentation Release master DriverStation constructor The single DriverStation instance is created statically with the instance static member variable you should never create a DriverStation instance class Alliance Bases builtins object The robot alliance that the robot is a part of Blue 1 Invalid 2 Red 0 DriverStation InAutonomous entering Only to be used to tell the Driver Statio
183. om the encoder Set this value based on the Pulses per Revolution and factor in any gearing reductions This distance can be in any units you like linear or angular Parameters distancePerPulse float The scale factor that will be used to convert pulses to useful units Counter setDownSource args kwargs Set the down counting source for the counter This function accepts either a digital channel index a DigitalSource or an AnalogTrigger as positional arguments source echannel eanalogTrigger eanalogTrigger triggerType For positional arguments if the passed object has a getChannelForRouting function it is assumed to be a DigitalSource If the passed object has a createOutput function it is assumed to be an AnalogTrigger Alternatively sources and or channels may be passed as keyword arguments The behavior of specifying both a source and a number for the same channel is undefined as is passing both a positional and a keyword argument for the same channel Parameters e channel int the DIO channel to use as the down source 0 9 are on board 10 25 are on the MXP e source DigitalInput The digital source to count e analogTrigger AnalogTrigger The analog trigger object that is used for the Up Source e triggerType AnalogTriggerType The analog trigger output that will trigger the counter Defaults to kState if not specified Counter setDownSourceEdge risingEdge fallingEdge Set the edge se
184. on of the device CANJaguar configMaxOutputVoltage voltage Configure the maximum voltage that the Jaguar will ever output This can be used to limit the maximum output voltage in all modes so that motors which cannot withstand full bus voltage can be used safely 26 Chapter 1 Contents RobotPy WPILib Documentation Release master Parameters voltage The maximum voltage output by the Jaguar CANJaguar configNeutralMode mode Configure what the controller does to the H Bridge when neutral not driving the output This allows you to override the jumper configuration for brake or coast Parameters mode Select to use the jumper setting or to override it to coast or brake see NeutralMode CANJaguar configPotentiometerTurns turns Configure the number of turns on the potentiometer There is no special support for continuous turn potentiometers Only integer numbers of turns are sup ported Parameters turns The number of turns of the potentiometer CANJaguar configReverseLimit reverseLimitPosition Set the position that if exceeded will disable the reverse direction Use configSoftPositionLimits to set this and the LimitMode automatically Parameters reverseLimitPosition The position that if exceeded will disable the reverse di rection CANJaguar configSoftPositionLimits forwardLimitPosition reverseLimitPosition Configure Soft Position Limits when in Position Controller mode When contro
185. onfiguration The robot drive class handles basic driving for a robot Currently 2 and 4 motor tank and mecanum drive trains are supported In the future other drive types like swerve might be implemented Motor channel numbers are passed supplied on creation of the class Those are used for either the drive function intended for hand created drive code such as autonomous or with the Tank Arcade functions intended to be used for Operator Control driving Constructor for RobotDrive Either 2 or 4 motors can be passed to the constructor to implement a two or four wheel drive system respectively When positional arguments are used these are the two accepted orders eleftMotor rightMotor efrontLeftMotor rearLeftMotor frontRightMotor rearRightMotor Alternatively the above names can be used as keyword arguments Either channel numbers or motor controllers can be passed determined by whether the passed object has a set function If channel numbers are passed the motorController keyword argument if present is the motor controller class to use if unspecified Talon is used class MotorType Bases builtins object The location of a motor on the robot for the purpose of driving kFrontLeft 0 Front left kFrontRight 1 Front right kRearLeft 2 Rear left kRearRight 3 Rear right RobotDrive arcadeDrive args kwargs Provide tank steering using the stored robot configuration Either one or two joysticks with optional s
186. ontroller used by this PIDCommand getPosition Returns the current position Returns the current position getSetpoint Returns the setpoint Returns the setpoint returnPIDInput Returns the input for the pid loop It returns the input for the pid loop so if this command was based off of a gyro then it should return the angle of the gyro All subclasses of PIDCommand must override this method This method will be called in a different thread then the Scheduler thread Returns the value the pid loop should use as input setSetpoint setpoint Sets the setpoint to the given value If set Range was called then the given setpoint will be trimmed to fit within the range Parameters setpoint the new setpoint setSetpointRelative deltaSetpoint Adds the given value to the setpoint If set Range was used then the bounds will still be honored by this method Parameters deltaSetpoint the change in the setpoint usePIDOutput output Uses the value that the pid loop calculated The calculated value is the output parameter This method is a good time to set motor values maybe something along the lines of driveline tankDrive output output All subclasses of PIDCommand should override this method This method will be called in a different thread then the Scheduler thread 1 5 wpilib command Package 117 RobotPy WPILib Documentation Release master Parameters output the value the pid loop c
187. oor 3000 kFixedOutdoor1 4000 kFixedOutdoor2 5000 USBCamera closeCamera USBCamera getBrightness Get the brightness as a percentage 0 100 USBCamera getImage image USBCamera getImageData data maxsize USBCamera kDefaultCameraName b cam0 USBCamera openCamera USBCamera setBrightness brightness Set the brightness as a percentage 0 100 USBCamera setExposureAuto Set the exposure to auto aperature USBCamera setExposureHoldCurrent Set the exposure to hold current USBCamera setExposureManual value Set the exposure to manual as a percentage 0 100 USBCamera setFPS fps USBCamera setSize width height 1 3 wpilib Package 13 RobotPy WPILib Documentation Release master USBCamera setWhiteBalanceAuto Set the white balance to auto USBCamera setWhiteBalanceHoldCurrent Set the white balance to hold current USBCamera setWhiteBalanceManual value Set the white balance to manual with specified color temperature USBCamera startCapture USBCamera stopCapture USBCamera updateSettings class wpilib impl CameraServer Bases builtins object static getInstance getOuality Get the guality of the compressed image sent to the dashboard Returns The guality from 0 to 100 isAutoCaptureStarted check if auto capture is started kPort 1180 kSize160x120 2 kSize320x240 1 kSize640x480 0 server None setImage image setOuality g
188. or Control methods will be called startCompetition Start a competition This code tracks the order of the field starting to ensure that everything happens in the right order Repeatedly run the correct method either Autonomous or OperatorControl when the robot is enabled After running the correct method wait for some state to change either the other mode starts or the robot is disabled Then go back and wait for the robot to be enabled again 92 Chapter 1 Contents RobotPy WPILib Documentation Release master test Test code should go here Users should add test code to this method that should run while the robot is in test mode 1 3 44 Sendable class wpilib Sendable Bases builtins object The base interface for objects that can be sent over the network through network tables 1 3 45 SendableChooser class wpilib SendableChooser Bases woilib Sendable A useful tool for presenting a selection of options to be displayed on the SmartDashboard For instance you may wish to be able to select between multiple autonomous modes You can do this by putting every possible Command you want to run as an autonomous into a SendableChooser and then put it into the SmartDashboard to have a list of options appear on the laptop Once autonomous starts simply ask the SendableChooser what the selected value is Example This shows the user two options on the SmartDashboard chooser wpilib SendableChooser chooser addO
189. osed loop profile to use and uses whatever PIDF gains and the such that are already there CANTalon setReverseSoftLimit reverseLimit CANTalon setSensorPosition pos CANTalon setStatusFrameRateMs stateFrame periodMs Change the periodMs of a TALON s status frame See StatusFrameRate enum for what s available CANTalon setVoltageRampRate rampRate Set the voltage ramp rate for the current profile Limits the rate at which the throttle will change Affects all modes Parameters rampRate Maximum change in voltage in volts sec CANTalon stopMotor Common interface for stopping a motor 1 3 14 Compressor class woilib Compressor pcmld None Bases woilib SensorBase Operates the PCM Pneumatics compressor module The PCM automatically will run in close loop mode by default whenever a Solenoid object is created For most cases the Compressor object does not need to be instantiated or used in a robot program This class is only required in cases where more detailed status or to enable disable closed loop control Note you cannot operate the compressor directly from this class as doing so would circumvent the safety provided in using the pressure switch and closed loop control You can only turn off closed loop control thereby stopping the compressor from operating Create an instance of the Compressor Parameters pemID The PCM CAN device ID Most robots that use PCM will have a single module Use this for
190. ot and channel like this Servo 0 2 for a servo object connected to the first digital module and PWM port 2 Parameters e moduleType A string that defines the module name in the label for the value e moduleNumber The number of the particular module type e channel The channel number the device is plugged into usually PWM 1 3 wpilib Package 71 RobotPy WPILib Documentation Release master e component The reference to the object being added static addSensor subsystem name component Add a Sensor associated with the subsystem and with call it by the given name Parameters e subsystem The subsystem this component is part of e name The name of this component e component A LiveWindowSendable component that represents a sensor static addSensorChannel moduleType channel component Add Sensor to LiveWindow The components are shown with the type and channel like this Gyro 0 for a gyro object connected to the first analog channel Parameters e moduleType A string indicating the type of the module used in the naming above e channel The channel number the device is connected to e component A reference to the object being added components firstTime True static initializeLiveWindowComponents Initialize all the LiveWindow elements the first time we enter LiveWindow mode By holding off creating the NetworkTable entries it allows them to be redefined before the first time in
191. ounter Counter method 48 setSensitivity wpilib analogaccelerometer AnalogAccelereat eltageRampRate method 18 setSensitivity wpilib gyro Gyro method 61 setSensitivity wpilib robotdrive RobotDrive method 90 setSensorPosition wpilib cantalon CANTalon method 41 setSetpoint wpilib command pidcommand PIDCommand method 117 setSetpointRelative wpilib command pidcommand PIDCommand method 117 setSetpointRelative wpilib command pidsubsystem PIDSubsystem method 119 wpilib impl dummycamera CameraServer method 13 14 wpilib impl dummycamera USBCamera method 12 13 setSpeed wpilib pwm PWM method 83 setSpeedModeEncoder wpilib canjaguar CANJaguar method 33 setSpeedModeQuadEncoder wpilib canjaguar CANJaguar method 33 setSize setSize setSpeedReference wpilib canjaguar CANJaguar method 33 setStatusFrameRateMs wpilib cantalon CANTalon method 41 wpilib command command Command method 114 wpilib pidcontroller PID Controller method 76 setUpdateWhenEmpty method 49 setUpDownCounterMode method 48 setupPeriodicStatus method 34 setUpSource wpilib counter Counter method 48 setUpSourceEdge wpilib counter Counter method 49 wpilib counter Counter wpilib counter Counter wpilib canjaguar CANJaguar method 64 setVoltage wpilib analogoutput AnalogOutput method 21 setVoltageMode method 33 setVoltageModeEncoder
192. output line to be active low This is sometimes called clock polarity high or clock idle high SPI setClockRate hz Configure the rate of the generated clock signal The default value is 500 000 Hz The maximum value is 4 000 000 Hz Parameters hz The clock rate in Hertz SPI setLSBFirst Configure the order that bits are sent and received on the wire to be least significant bit first SPI setMSBFirst Configure the order that bits are sent and received on the wire to be most significant bit first SPI setSampleDataOnFalling Configure that the data is stable on the falling edge and the data changes on the rising edge SPI setSampleDataOnRising Configure that the data is stable on the rising edge and the data changes on the falling edge SPI transaction dataToSend Perform a simultaneous read write transaction with the device Parameters dataToSend The data to be written out to the device Returns data received from the device SPI write dataToSend Write data to the slave device Blocks until there is space in the output FIFO 1 3 wpilib Package 101 RobotPy WPILib Documentation Release master If not running in output only mode also saves the data received on the MISO input during the transfer into the receive FIFO Parameters dataToSend Data to send bytes 1 3 52 Talon class woilib Talon channel Bases woilib SafePWM Cross the Road Electronics CTRE Talon and Talon SR Speed Controller
193. owSendable Built in accelerometer device This class allows access to the RoboRIO s internal accelerometer Constructor Parameters range Accelerometer Range The range the accelerometer will measure De faults to 8g if unspecified class Range Bases builtins object k16G 3 k2G 0 k4G 1 k8G 2 BuiltInAccelerometer getxX Returns The acceleration of the RoboRIO along the X axis in g forces Return type float BuiltInAccelerometer getY Returns The acceleration of the RoboRIO along the Y axis in g forces 24 Chapter 1 Contents RobotPy WPILib Documentation Release master Return type float BuiltInAccelerometer getZ Returns The acceleration of the RoboRIO along the Z axis in g forces Return type float BuiltInAccelerometer setRange range Set the measuring range of the accelerometer Parameters range Built InAccelerometer Range The maximum acceleration pos itive or negative that the accelerometer will measure 1 3 12 CANJaguar class wpilib CANJaguar deviceNumber Bases wpilib LiveWindowSendable wpilib MotorSafety Texas Instruments Jaguar Speed Controller as a CAN device Constructor for the CANJaguar device By default the device is configured in Percent mode The control mode can be changed by calling one of the control modes Parameters deviceNumber The address of the Jaguar on the CAN bus class Cont rolMode Bases builtins object Determines how the Jaguar is cont
194. oy command to show your program s console output by launching a netconsole listener Windows py robot py deploy nc Linux OSX python3 robot py deploy nc You can watch your robot code s output and see any problems by using the netconsole program you can either use NI s tool or pynetconsole You can use netconsole and the normal FRC tools to interact with the running robot code If you re having problems deploying code to the robot check out the troubleshooting section at http pyfrc readthedocs org en latest deploy html On the robot manual If you don t have or don t want to install pyfrc running code manually is pretty simple too 1 Make sure you have RobotPy installed on the robot 2 Use scp or sftp Filezilla is a great GUI product to use for this to copy your robot code to the RoboRIO 3 ssh into the RoboRIO and run your robot code manually python3 robot py run Your driver station should be able to connect to your code and it will be able to operate your robot Note This is good for running experimental code but it won t start the code when the robot starts up Use pyfrc to do that On your computer Once installed pyfrc provides a number of commands to interact with your robot code For example to launch the tk based simulator run the following command on your code Windows py robot py sim Linux OSX python3 robot py sim Check out the pyfrc documentation for more usage details 1 2
195. p from a non quadrature encoder After calling this you must call enableControl to enable the device Parameters e codesPerRev The counts per revolution on the encoder e p The proportional gain of the Jaguar s PID controller e i The integral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller CANJaguar setSpeedModeQuadEncoder codesPerRev p i d Enable controlling the speed with a feedback loop from a quadrature encoder After calling this you must call enableControl to enable the device Parameters e codesPerRev The counts per revolution on the encoder e p The proportional gain of the Jaguar s PID controller e i The integral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller CANJaguar setSpeedReference reference Set the reference source device for speed controller mode Choose encoder as the source of speed feedback when in speed control mode Parameters reference Specify a speed reference CANJaguar setVoltageMode Enable controlling the motor voltage without any position or speed feedback After calling this you must call enableControl to enable the device CANJaguar setVoltageModeEncoder codesPerRev Enable controlling the motor voltage with speed feedback from a non quadrature encoder and no position feedback lt br gt After calling this you must call enableControl to enable th
196. pecified axis or two raw values may be passed positionally along with an optional squaredInputs boolean The valid positional combinations are estick estick sguaredInputs emoveStick moveAxis rotateStick rotateAxis moveStick moveAxis rotateStick rotateAxis squaredInputs emoveValue rotate Value emoveValue rotateValue sguaredInputs 1 3 wpilib Package 87 RobotPy WPILib Documentation Release master Alternatively the above names can be used as keyword arguments The behavior of mixes of keyword arguments in other than the combinations above is undefined If specified positionally the value and joystick versions are disambiguated by looking for a getY function on the stick Parameters RobotDrive Drive the stick The joystick to use for Arcade single stick driving The Y axis will be selected for forwards backwards and the X axis will be selected for rotation rate moveStick The Joystick object that represents the forward backward direction moveAxis The axis on the moveStick object to use for forwards backwards typically Y_AXIS rotateStick The Joystick object that represents the rotation value rotateAxis The axis on the rotation object to use for the rotate right left typically X AXIS move Value The value to use for forwards backwards rotate Value The value to use for the rotate right left squaredInputs Setting this parameter to True decreases the sensitivit
197. pidsubsystem PIDSubsystem method 119 Utility class in wpilib utility 107 Index 155 RobotPy WPILib Documentation Release master V VALUE PREFIX attribute 77 VALUE SUFFIX attribute 77 verify wpilib canjaguar CANJaguar method 34 verifySensor wpilib i2c I2C method 62 Victor class in wpilib victor 107 VictorSP class in wpilib victorsp 108 Voltage wpilib canjaguar CANJaguar ControlMode at tribute 25 wpilib cantalon CANTalon ControlMode tribute 36 wpilib preferences Preferences wpilib preferences Preferences Voltage at W WaitCommand class in wpilib command waitcommand 122 WaitForChildren class in wpilib command waitforchildren 123 waitForData wpilib driverstation DriverStation method 56 wpilib buttons trigger module 111 wpilib canjaguar module 25 wpilib cantalon module 34 wpilib command module 111 wpilib command command module 112 wpilib command commandgroup module 115 wpilib command pidcommand module 116 wpilib command pidsubsystem module 118 wpilib command printcommand module 119 wpilib command scheduler module 120 wpilib command startcommand module 121 wpilib command subsystem module 121 wpilib command waitcommand module 122 wpilib command waitforchildren module 123 wpilib command waituntilcommand module 123 wpilib compressor module 41 wpilib controllerpower module 42 wpilib counter module 44
198. pilib canjaguar CANJaguar method 31 setCurrentModeQuadEncoder wpilib canjaguar CANJaguar method 31 setD wpilib canjaguar CANJaguar method 31 setD wpilib cantalon CANTalon method 40 setDeadband wpilib gyro Gyro method 61 setDefaultCommand wpilib command subsystem Subsystem method 122 wpilib canjaguar CANJaguar 152 Index RobotPy WPILib Documentation Release master setDefaultSolenoidModule wpilib sensorbase SensorBase static method 95 setDirection wpilib relay Relay method 84 setDistancePerPulse wpilib counter Counter method 47 setDistancePerPulse wpilib encoder Encoder method 59 setDistanceUnits wpilib ultrasonic Ultrasonic method 106 setDownSource wpilib counter Counter method 47 setDownSourceEdge wpilib counter Counter method 47 setEnabled wpilib livewindow LiveWindow method 72 setEnabled wpilib ultrasonic Ultrasonic method 106 setExpiration wpilib motorsafety MotorSafety method 73 static setExposureAuto wpilib impl dummycamera USB Camera method 12 13 setExposureHoldCurrent wpilib impl dummycamera USBCamera method 12 13 setExposureManual wpilib impl dummycamera USBCamera method 12 13 setExternalDirectionMode method 47 setF wpilib cantalon CANTalon method 40 setFeedbackDevicel wpilib cantalon CANTalon wpilib counter Counter method 40 setFiltered wpilib analogtrigger Analo
199. ption optionl 1 chooser addOption option2 2 wpilib SmartDashboard putData Choice chooser later ask to see what the user selected value chooser getSelected Instantiates a SendableChooser DEFAULT default OPTIONS options SELECTED selected addDefault name object Add the given object to the list of options and marks it as the default Functionally this is very close to addObject except that it will use this as the default option if none other is explicitly selected Parameters e name the name of the option e object the option addOb ject name object Adds the given object to the list of options On the SmartDashboard on the desktop the object will appear as the given name Parameters e name the name of the option 1 3 wpilib Package 93 RobotPy WPILib Documentation Release master e object the option getSelected Returns the object associated with the selected option If there is none selected it will return the default If there is none selected and no default then it will return None Returns the object associated with the selected option 1 3 46 SensorBase class wpilib SensorBase Bases woilib LiveWindowSendable Base class for all sensors Stores most recent status information as well as containing utility functions for checking channels and error processing static checkAnalogInputChannel channel Che
200. rPwm wpilib pwm PWM method 81 getChannel wpilib analoginput AnalogInput method 19 getChannel wpilib digitalinput DigitalInput method 49 getChannel wpilib digitaloutput DigitalOutput method 50 getChannel wpilib pwm PWM method 81 getChannelForRouting wpilib analogtriggeroutput AnalogTriggerOutput method 24 getChannelForRouting wpilib digitalsource DigitalS ource method 51 getChannelForRouting wpilib interruptablesensorbase InterruptableSenso method 63 wpilib analogtriggeroutput AnalogTriggerOutput getClosedLoopControl wpilib compressor Compressor method 24 getAnalogTriggerForRouting wpilib digitalinput DigitalInput 49 getAnalogTriggerForRouting wpilib digitalsource DigitalSource 51 getAnalogTriggerForRouting method method wpilib interruptablesensorbase InterruptableSensorBase method 63 getAngle wpilib gyro Gyro method 60 getAngle wpilib servo Servo method 96 getAverageBits wpilib analoginput AnalogInput method 19 getAverageValue wpilib analoginput AnalogInput method 19 getAverageVoltage wpilib analoginput AnalogInput method 19 getAxis wpilib joystick Joystick method 68 getAxisChannel wpilib joystick Joystick method 68 getAxisCount wpilib joystick Joystick method 68 getBatteryVoltage wpilib driverstation DriverStation method 53 getBoolean wpilib preferences Preferences method 78 getBoolean
201. rce that should be used for the index channel aChannel The digital input index that should be used for the a channel bChannel The digital input index that should be used for the b channel indexChannel The digital input index that should be used for the index channel reverseDirection Represents the orientation of the encoder and inverts the output values if necessary so forward represents positive values Defaults to False if unspecified encodingType Encoder EncodingType Either k1X k2X or k4X to indicate 1X 2X or 4X decoding If 4X is selected then an encoder FPGA object is used and the returned counts will be 4x the encoder spec d value since all rising and falling edges are counted If 1X or 2X are selected then a counter object will be used and the returned value will either exactly match the spec d count or be double 2x the spec d count Defaults to k4X if unspecified class EncodingType Bases builtins object The number of edges for the counterbase to increment or decrement on k1x 0 k2xX 1 k4X 2 class Encoder IndexingType Bases builtins object kResetOnFallingEdge 2 kResetOnRisingEdge 3 kResetWhileHigh 0 kResetWhileLow 1 class Encoder PIDSourceParameter Bases builtins object A description for the type of output value to provide toa PIDCont roller kAngle 2 kDistance 0 kRate 1 Encoder encoder Encoder free Encoder d
202. rd static method 97 getTemp wpilib cantalon CANTalon method 39 getTemperature wpilib canjaguar CANJaguar method 29 getTemperature wpilib powerdistributionpanel PowerDistributionPanel method 76 getThrottle wpilib interfaces generichid GenericHID method 126 getThrottle wpilib joystick Joystick method 69 getTop wpilib interfaces generichid GenericHID method 126 getTopQ wpilib joystick Joystick method 69 getSetpoint wpilib command pidcommand PIDCommandgetTotalCurrent wpilib powerdistributionpanel PowerDistributionPanel method 117 method 76 getSetpoint wpilib command pidsubsystem PIDSubsystengetTotalEnergy wpilib powerdistributionpanel PowerDistributionPanel method 118 getSetpoint wpilib pidcontroller PID Controller method 75 getSpeed wpilib canjaguar CANJaguar method 29 getSpeed wpilib cantalon CANTalon method 39 getSpeed wpilib pwm PWM method 82 getStickAxis wpilib driverstation DriverStation method 54 getStickAxisCount wpilib driverstation DriverStation method 54 method 77 getTotalPower wpilib powerdistributionpanel PowerDistributionPanel method 77 getTrigger wpilib interfaces generichid GenericHID method 126 getTrigger wpilib joystick Joystick method 69 getTriggerState wpilib analogtrigger AnalogTrigger method 22 getTwist wpilib interfaces generichid GenericHID method 126 getTwist wpilib joystick
203. return false Returns whether the time has expired lockChanges Prevents further changes from being made removed Called when the command has been removed This will call interrupted orend requires subsystem This method specifies that the given Subsystem is used by this command This method is crucial to the functioning of the Command System in general Note that the recommended way to call this method is in the constructor Parameters subsystem the Subsystem required run The run method is used internally to actually run the commands Returns whether or not the command should stay within the Scheduler setInterruptible interruptible Sets whether or not this command can be interrupted Parameters interruptible whether or not this command can be interrupted setParent parent Sets the parent of this command No actual change is made to the group Parameters parent the parent setRunWhenDisabled run Sets whether or not this link Command should run when the robot is disabled By default a command will not run when the robot is disabled and will in fact be canceled Parameters run whether or not this command should run when the robot is disabled setTimeout seconds Sets the timeout of this command Parameters seconds the timeout in seconds See isTimedOut start Starts up the command Gets the command ready to start Note that the command will eventually start however
204. riverStation method 55 isCanceled wpilib command command Command method 113 isControlEnabled wpilib cantalon CANTalon method 39 isDisabled wpilib driverstation DriverStation method 55 isDisabled wpilib robotbase RobotBase method 86 isDisabled wpilib robotstate RobotState static method 91 isDSAttached method 55 isEnable wpilib pidcontroller PIDController method 75 isEnabled wpilib driverstation DriverStation method 55 isEnabled wpilib robotbase RobotBase method 86 isEnabled wpilib robotstate RobotState static method 91 isEnabled wpilib ultrasonic Ultrasonic method 106 isFinished wpilib command command Command method 113 wpilib driverstation DriverStation isInterruptible wpilib command commandgroup CommandGroup method 116 isNewControlData Wwpilib driverstation DriverStation method 55 isNewDataAvailable wpilib robotbase RobotBase method 86 isOperatorControl Wpilib driverstation DriverStation method 55 isOperatorControl wpilib robotbase RobotBase method 86 isOperatorControl wpilib robotstate RobotState static method 91 isPulsing wpilib digitaloutput DigitalOutput method 50 isRangeValid Wpilib ultrasonic Ultrasonic method 106 isReal wpilib robotbase RobotBase static method 86 isRevLimitSwitchClosed wpilib cantalon CANTalon method 39 isRevSolenoidBlackListed wpilib doublesolenoid DoubleSolen
205. rolled used internally Current 1 PercentVbus 0 Position 3 Speed 2 Voltage 4 class CANJaguar LimitMode Bases builtins object Determines which sensor to use for position reference Limit switches will always be used to limit the rotation This can not be disabled SoftPositionLimits 1 Enables the soft position limits on the Jaguar These will be used in addition to the limit switches This does not disable the behavior of the limit switch input See configSoftPositionLimits SwitchInputsOnly 0 Disables the soft position limits and only uses the limit switches to limit rotation See getForwardLim itOK and getReverseLimitOK class CANJaguar Mode Bases builtins object Control Mode kEncoder 0 Sets an encoder as the speed reference only 1 3 wpilib Package 25 RobotPy WPILib Documentation Release master kPotentiometer 2 Sets a potentiometer as the position reference only kQuadEncoder 1 Sets a quadrature encoder as the position and speed reference class CANJaguar NeutralMode Bases builtins object Determines how the Jaguar behaves when sending a zero signal Brake 1 Stop the motor s rotation by applying a force Coast 2 Do not attempt to stop the motor Instead allow it to coast to a stop without applying resistance Jumper 0 Use the NeutralMode that is set by the jumper wire on the CAN device CANJaguar allocated lt wpilib resource Resource object at 0x7f2574ef7b70 g
206. rs e lower the lower voltage limit e upper the upper voltage limit 1 3 10 AnalogTriggerOutput class woilib AnalogTriggerOutput trigger outputType Bases builtins object Represents a specific output from an AnalogTrigger This class is used to get the current output value and also asa DigitalSource to provide routing of an output to digital subsystems on the FPGA such as Counter Encoder and class Interrupt The TriggerState output indicates the primary output value of the trigger If the analog signal is less than the lower limit the output is False If the analog value is greater than the upper limit then the output is True If the analog value is in between then the trigger output state maintains its most recent value The InWindow output indicates whether or not the analog signal is inside the range defined by the limits The RisingPulse and FallingPulse outputs detect an instantaneous transition from above the upper limit to below the lower limit and vise versa These pulses represent a rollover condition of a sensor and can be routed to an up down couter or to interrupts Because the outputs generate a pulse they cannot be read directly To help ensure that a rollover condition is not missed there is an average rejection filter available that operates on the upper 8 bits of a 12 bit number and selects the nearest outlyer of 3 samples This will reject a sample that is due to averaging or sampling errantly between
207. s at half speed self auto_loop_counter 1 else self robot_drive drive 0 0 Stop robot def teleopPeriodic self This function is called periodically during operator control self robot_drive arcadeDrive self stick def testPeriodic self This function is called periodically during test mode wpilib LiveWindow run af name main wpilib run MyRobot There are a few different python based robot samples available and you can find them at our github site Next Steps This is a good foundation for building your robot next you will probably want to know about Running Robot Code 1 2 2 Running Robot Code Now that you ve created your first Python robot program you probably want to know how to run the code 8 Chapter 1 Contents RobotPy WPILib Documentation Release master On the robot using pyfrc The easiest way to install code on the robot is to use pyfrc 1 Make sure you have RobotPy installed on the robot 2 Make sure you have pyfrc installed see the installation guide 3 Once that is done you can just run the following command and it will upload the code and start it immediately Windows py robot py deploy Linux OSX python3 robot py deploy Note that when you run this command like that you won t get any feedback from the robot whether your code actually worked or not If you want to see the feedback from your robot a really useful option is nc This will cause the depl
208. s singleton is first created remove key Remove a preference Parameters key the key save Saves the preferences to a file on the RoboRIO This should NOT be called often Too many writes can damage the RoboRIO s flash mem ory While it is ok to save once or twice a match this should never be called every run of IterativeRobot teleopPeriodic The actual writing of the file is done in a separate thread However any call to a get or put method will wait until the table is fully saved before continuing 1 3 36 PWM class wpilib PWM channel Bases woilib LiveWindowSendable Raw interface to PWM generation in the FPGA The values supplied as arguments for PWM outputs range from 1 0 to 1 0 They are mapped to the hardware dependent values in this case 0 2000 for the FPGA Changes are immediately sent to the FPGA and the update occurs at the next FPGA cycle There is no delay As of revision 0 1 10 of the FPGA the FPGA interprets the 0 2000 values as follows 2000 full forward 1999 to 1001 linear scaling from full forward to center 1000 center value 999 to 2 linear scaling from center to full reverse e minimum pulse width currently 5ms 0 disabled i e PWM output is held low kDefaultPwmPeriod is the 1x period 5 05 ms In hardware the period scaling is implemented as an output squelch to get longer periods for old devices 20ms periods 50 Hz are
209. se every py file is usable from other python programs you need to define a code block which checks for __main__ Inside your main block you tell WPILib to launch your robot s code using the following invocation if name main wpilib run MyRobot This simple invocation is sufficient for launching your robot code on the robot and also provides access to various RobotPy enabled extensions that may be available for testing your robot code such as pyfrc and robotpy frcsim 1 2 Programmer s Guide 7 RobotPy WPILib Documentation Release master Putting it all together If you combine all the pieces above you end up with something like this below taken from one of the samples in our github repository usr bin env python3 nu This is a good foundation to build your robot code on nu import wpilib class MyRobot wpilib IterativeRobot def robotInit self noe This function is called upon program startup and should be used for any initialization code nmmn self robot_drive wpilib RobotDrive 0 1 self stick wpilib Joystick 1 def autonomousInit self This function is run once each time the robot enters autonomous mode self auto_loop_counter 0 def autonomousPeriodic self This function is called periodically during autonomous Check if we ve completed 100 loops approximately 2 seconds if self auto_loop_counter lt 100 self robot_drive drive 0 5 0 Drive forward
210. setDistancePerPulse Encoder setPIDSourceParameter pidSource Set which parameter of the encoder you are using as a process control variable The encoder class supports the rate and distance parameters Parameters pidSource An enum to select the parameter Encoder setReverseDirection reverseDirection Set the direction sensing for this encoder This sets the direction sensing on the encoder so that it could count in the correct software direction regardless of the mounting Parameters reverseDirection True if the encoder direction should be reversed Encoder setSamplesToAverage samplesToAverage Set the Samples to Average which specifies the number of samples of the timer to average when calculating the period Perform averaging to account for mechanical imperfections or as oversampling to increase resolution TODO Should this raise an exception so that the user has to deal with giving an incorrect value Parameters samplesToAverage The number of samples to average from 1 to 127 1 3 wpilib Package 59 RobotPy WPILib Documentation Release master 1 3 23 GearTooth class woilib GearTooth channel directionSensitive False Bases woilib Counter Interface to the gear tooth sensor supplied by FIRST Currently there is no reverse sensing on the gear tooth sensor but in future versions we might implement the necessary timing in the FPGA to sense direction Construct a GearTooth sensor Parameters
211. sk of groups to generate synchronous output CANJaguar verify Check all unverified params and make sure they re egual to their local cached versions If a value isn t available it gets requested If a value doesn t match up it gets set again 1 3 13 CANTalon class woilib CANTalon deviceNumber controlPeriodMs 10 Bases woilib MotorSafety Talon SRX device as a CAN device 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 Likewise most control signals are sent periodically using the fire and forget CAN API 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 likel
212. st take a single argument it is an argparse parser which options can be added to Must have a run function which takes two arguments options and robot class It must also take arbitrary keyword arguments via the kwargs mechanism If it receives arguments that it does not recognize the entry point must ignore any such options If your command s run function is called it is your command s responsibility to execute the robot code if that is desired This sample command demonstrates how to do this class SampleCommand Help text shown to user def init self parser pass def run self options robot class xstatic_options runs the robot code main loop robot_class main robot_class To register your command as a robotpy extension you must add the following to your setup py setup invocation from setuptools import setup setup 130 Chapter 1 Contents RobotPy WPILib Documentation Release master entry points f robot py name of command package module CommandClassName J 1 9 Support The RobotPy project was started in 2010 and since then the community surrounding RobotPy has continued to grow If you have guestions about how to do something with RobotPy you can ask guestions in the following locations e RobotPy mailing list e ChiefDelphi Python Forums We have found that most problems users have are actually questions generic to WPILib based languages lik
213. t CANJaguar changeControlMode controlMode Used internally In order to set the control mode see the methods listed below Change the control mode of this Jaguar object After changing modes configure any PID constants or other settings needed and then EnableControl to actually change the mode on the Jaguar Parameters controlMode The new mode CANJaguar configEncoderCodesPerRev codesPerRev Configure how many codes per revolution are generated by your encoder Parameters codesPerRev The number of counts per revolution in 1X mode CANJaguar configFaultTime faultTime Configure how long the Jaguar waits in the case of a fault before resuming operation Faults include over temerature over current and bus under voltage The default is 3 0 seconds but can be reduced to as low as 0 5 seconds Parameters faultTime The time to wait before resuming operation in seconds CANJaguar configForwardLimit forwardLimitPosition Set the position that if exceeded will disable the forward direction Use configSoftPositionLimits to set this and the LimitMode automatically Parameters forwardLimitPosition The position that if exceeded will disable the forward direction CANJaguar configLimitMode mode Set the limit mode for position control mode lt br gt Use configSoftPositionLimits or disableSoftPositionLimits to set this auto matically Parameters mode The LimitMode to use to limit the rotati
214. t into the FPGA The resulting digital signal can then be used directly or fed into other digital components of the FPGA such as the counter or encoder modules The analog trigger module works by comparing analog signals to a voltage range set by the code The specific return types and meanings depend on the analog trigger mode in use Constructor for an analog trigger given a channel number or analog input Parameters channel the port index or AnalogInput to use for the analog trigger Treated as an AnalogInput if the provided object has a getChannel function class AnalogTriggerType Bases builtins object Defines the state in which the AnalogTrigger triggers kFallingPulse 3 kInWindow 0 kRisingPulse 2 kState 1 AnalogTrigger createOutput type Creates an AnalogTriggerOutput object Gets an output object that can be used for routing Caller is responsible for deleting the AnalogTriggerOutput object Parameters type An enum of the type of output object to create Returns An AnalogTriggerOutput object AnalogTrigger free Release the resources used by this object AnalogTrigger getInWindow Return the InWindow output of the analog trigger True if the analog input is between the upper and lower limits Returns The InWindow output of the analog trigger AnalogTrigger getIndex Return the index of the analog trigger This is the FPGA index of this analog trigger instance Returns The index of the analog tri
215. t the white balance to auto USBCamera setWhiteBalanceHoldCurrent Set the white balance to hold current USBCamera setWhiteBalanceManual value Set the white balance to manual with specified color temperature USBCamera startCapture USBCamera stopCapture USBCamera updateSettings class wpilib impl CameraServer Bases builtins object static getInstance getOuality Get the guality of the compressed image sent to the dashboard Returns The guality from 0 to 100 isAutoCaptureStarted check if auto capture is started kPort 1180 kSize160x120 2 kSize320x240 1 kSize640x480 0 12 Chapter 1 Contents RobotPy WPILib Documentation Release master server None setImage image setQuality quality Set the quality of the compressed image sent to the dashboard Parameters quality The quality of the JPEG image from 0 to 100 setSize size startAutomaticCapture camera Start automatically capturing images to send to the dashboard You should call this method to just see a camera feed on the dashboard without doing any vision processing on the roboRIO link setImage shouldn t be called after this is called Parameters camera The camera interface e g a USBCamera instance 1 3 2 USBCamera class woilib _impl USBCamera name None Bases builtins object class WhiteBalance Bases builtins object kFixedFlourescent2 5200 kFixedFluorescent1 5100 kFixedInd
216. ted getPressureSwitchValue Get the current pressure switch value Returns True if the pressure is low by reading the pressure switch that is plugged into the PCM Return type bool setClosedLoopControl on Set the PCM in closed loop control mode Parameters on bool If True sets the compressor to be in closed loop control mode otherwise normal operation of the compressor is disabled start Start the compressor running in closed loop control mode Use the method in cases where you would like to manually stop and start the compressor for applications such as conserving battery or making sure that the compressor motor doesn t start during critical operations stop Stop the compressor from running in closed loop control mode Use the method in cases where you would like to manually stop and start the compressor for applications such as conserving battery or making sure that the compressor motor doesn t start during critical operations 1 3 15 ControllerPower class woilib ControllerPower Bases builtins object Provides access to power levels on the RoboRIO 42 Chapter 1 Contents RobotPy WPILib Documentation Release master static getCurrent3V3 Get the current output of the 3 3V rail Returns The controller 3 3V rail output current value in Amps Return type float static getCurrent 5V Get the current output of the 5V rail Returns The controller 5V rail output current value in Amps Return
217. terface Parameters units The DistanceUnit that should be used Ultrasonic setEnabled enable Setif the ultrasonic is enabled Parameters enable bool set to True to enable the ultrasonic static Ultrasonic ultrasonicChecker Background task that goes through the list of ultrasonic sensors and pings each one in turn The counter is configured to read the timing of the returned echo pulse 106 Chapter 1 Contents RobotPy WPILib Documentation Release master Warning DANGER WILL ROBINSON DANGER WILL ROBINSON This code runs as a task and assumes that none of the ultrasonic sensors will change while it s running If one does then this will certainly break Make sure to disable automatic mode before changing anything with the sensors 1 3 56 Utility class wpilib Utility Bases builtins object Contains global utility functions static getFPGARevision Return the FPGA Revision number The format of the revision is 3 numbers The 12 most significant bits are the Major Revision the next 8 bits are the Minor Revision The 12 least significant bits are the Build Number Returns FPGA Revision number Return type int static getFPGATime Read the microsecond timer from the FPGA Returns The current time in microseconds according to the FPGA Return type int static get FPGAVersion Return the FPGA Version number Returns FPGA Version number Return type int static getUserButton Get the state
218. the safest setting in that this works for all devices 20ms periods seem to be desirable for Vex Motors 20ms periods are the specified period for HS 322HD servos but work reliably down to 10 0 ms starting at about 8 5ms the servo sometimes hums and get hot by 5 0ms the hum is nearly continuous 10ms periods work well for Victor 884 80 Chapter 1 Contents RobotPy WPILib Documentation Release master 5ms periods allows higher update rates for Luminary Micro Jaguar speed controllers Due to the shipping firmware on the Jaguar we can t run the update period less than 5 05 ms Allocate a PWM given a channel Parameters channel int The PWM channel number 0 9 are on board 10 19 are on the MXP port class PeriodMultiplier PWM PWM PWM PWM PW PW PW PW PW PW PW Bases builtins object Represents the amount to multiply the minimum servo pulse pwm period by k1x 1 k2xX 2 k4x 4 enableDeadbandElimination eliminateDeadband Optionally eliminate the deadband from a speed controller Parameters eliminateDeadband boo If True set the motor curve on the Jaguar to eliminate the deadband in the middle of the range Otherwise keep the full range without modifying any values free Free the PWM channel Free the resource associated with the PWM channel and set the value to 0 getCenterPwm getChannel Gets the channel number associated
219. the button value starting at button 1 The buttons are returned in a single 16 bit value with one bit representing the state of each button The appropriate button is returned as a boolean value Parameters button int The button number to be read starting at 1 Returns The state of the button Return type bool Joystick getThrottle Get the throttle value of the current joystick This depends on the mapping of the joystick connected to the current port Returns The Throttle value of the joystick Return type float Joystick getTop hand None Read the state of the top button on the joystick Look up which button has been assigned to the top and read its state Parameters hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface Returns The state of the top button Return type bool Joystick getTrigger hand None Read the state of the trigger on the joystick Look up which button has been assigned to the trigger and read its state Parameters hand This parameter is ignored for the Joystick class and is only here to complete the GenericHID interface 1 3 wpilib Package 69 RobotPy WPILib Documentation Release master Returns The state of the trigger Return type bool Joystick getTwist Get the twist value of the current joystick This depends on the mapping of the joystick connected to the current port Returns The Twist value of the joystic
220. the device 0 7 Returns Data received from the device I2C verifySensor registerAddress expected Verify that a device s registers contain expected values 62 Chapter 1 Contents RobotPy WPILib Documentation Release master Most devices will have a set of registers that contain a known value that can be used to identify them This allows an I2C device driver to easily verify that the device contains the expected value The device must support and be configured to use register auto increment Parameters e registerAddress The base register to start reading from the device e expected The values expected from the device Returns True if the sensor was verified to be connected I2C write registerAddress data Execute a write transaction with the device Write a single byte to a register on a device and wait until the transaction is complete Parameters e registerAddress The address of the register on the device to be written e data The byte to write to the register on the device Returns Transfer Aborted False for success True for aborted I2C writeBulk data Execute a write transaction with the device Write multiple bytes to a register on a device and wait until the transaction is complete Parameters data The data to write to the device Returns Transfer Aborted False for success True for aborted 1 3 26 InterruptableSensorBase class woilib InterruptableSensorBase Bases woilib SensorB
221. the device Parameters e tag The constant link CANJaguar kOuadEncoder e codesPerRev The counts per revolution on the encoder CANJaguar setPositionModePotentiometer p i d Enable controlling the position with a feedback loop using a potentiometer After calling this you must call enableControl to enable the device Parameters e p The proportional gain of the Jaguar s PID controller e i The integral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller CANJaguar setPositionModeQuadEncoder codesPerRev p i d Enable controlling the position with a feedback loop using an encoder After calling this you must call enableControl to enable the device Parameters e codesPerRev The counts per revolution on the encoder e p The proportional gain of the Jaguar s PID controller e i The integral gain of the Jaguar s PID controller e d The differential gain of the Jaguar s PID controller 32 Chapter 1 Contents RobotPy WPILib Documentation Release master CANJaguar setPositionReference reference Set the reference source device for position controller mode Choose between using and encoder and using a potentiometer as the source of position feedback when in position control mode Parameters reference Specify a position reference CANJaguar setSpeedModeEncoder codesPerRev p i d Enable controlling the speed with a feedback loo
222. the joystick Parameters value int The 32 bit output value 1 bit for each output Joystick setRumble type value Set the rumble output for the joystick The DS currently supports 2 rumble values left rumble and right rumble Parameters e type Joystick RumbleType Which rumble value to set e value float The normalized value Oto 1 to set the rumble to 1 3 30 LiveWindow class woilib LiveWindow Bases builtins object The public interface for putting sensors and actuators on the LiveWindow static addActuator subsystem name component Add an Actuator associated with the subsystem and with call it by the given name Parameters e subsystem The subsystem this component is part of e name The name of this component e component A LiveWindowSendable component that represents a actuator static addActuatorChannel moduleType channel component Add Actuator to LiveWindow The components are shown with the module type slot and channel like this Servo 0 2 for a servo object connected to the first digital module and PWM port 2 Parameters e moduleType A string that defines the module name in the label for the value e channel The channel number the device is plugged into usually PWM e component The reference to the object being added static addActuatorModuleChannel moduleType moduleNumber channel component Add Actuator to LiveWindow The components are shown with the module type sl
223. tied If you enable update when empty you will be notified of the stopped source and the event time will report 0 samples If you disable update when empty the most recent average will remain on the output until a new sample is acquired You will never see 0 samples output except when there have been no events since an FPGA reset and you will likely not see the stopped bit become true since it is updated at the end of an average and there are no samples to average Parameters enabled bool True to continue updating 1 3 17 Digitallnput class woilib DigitalInput channel Bases woilib DigitalSource Reads a digital input This class will read digital inputs and return the current value on the channel Other devices such as encoders gear tooth sensors etc that are implemented elsewhere will automatically allocate digital inputs and outputs as required This class is only for devices like switches etc that aren t implemented anywhere else Create an instance of a Digital Input class Creates a digital input given a channel Parameters channel int the DIO channel for the digital input 0 9 are on board 10 25 are on the MXP get Get the value from a digital input channel Retrieve the value of a single digital input channel from the FPGA Returns the state of the digital input Return type bool getAnalogTriggerForRouting getChannel Get the channel of the digital input 1 3 wpilib Package 49 RobotPy W
224. tribute 101 kOversampleBits wpilib gyro Gyro attribute 61 kPDPChannels wpilib sensorbase SensorBase attribute 95 kPingTime wpilib ultrasonic Ultrasonic attribute 106 kPort wpilib _impl dummycamera CameraServer at tribute 12 14 kPotentiometer wpilib canjaguar CANJaguar Mode at tribute 25 kRate wpilib counter Counter PIDSourceParameter at tribute 45 kRate wpilib encoder Encoder PIDSourceParameter at tribute 57 kRate wpilib interfaces pidsource PIDSource PIDSourceParameter attribute 127 kRearLeft wpilib robotdrive RobotDrive MotorType at tribute 87 kRearRight wpilib robotdrive RobotDrive MotorType at tribute 87 kReceiveStatusAttempts attribute 30 kRelayChannels wpilib sensorbase SensorBase tribute 95 kResetOnFallingEdge wpilib encoder Encoder IndexingType attribute 57 kResetOnRisingEdge wpilib encoder Encoder IndexingType attribute 57 kResetWhileHigh wpilib encoder Encoder IndexingType attribute 57 kResetWhileLow wpilib encoder Encoder IndexingType attribute 57 kReverse wpilib doublesolenoid DoubleSolenoid Value attribute 52 kReverse wpilib relay Relay Direction attribute 83 kReverse wpilib relay Relay Value attribute 84 wpilib canjaguar CANJaguar at kPowerCtl_AutoSleep wpilib adx1345_i2c ADXL345_I2C kReverseLimit wpilib canjaguar CANJaguar attribute attribute 16 kPowerCtl_AutoSleep wpilib adx1345 spi ADXL345 SPI kRight attribute
225. trols Returns The location of the team s driver station controls 1 2 or 3 DriverStation getMatchTime Return the approximate match time The FMS does not currently send the official match time to the robots but does send an approximate match time The value will count down the time remaining in the current period auto or teleop 1 3 wpilib Package 53 RobotPy WPILib Documentation Release master Warning This is not an official time so it cannot be used to argue with referees or guarantee that a function will trigger before a match ends The Practice Match function of the DS approximates the behaviour seen on the field Returns Time remaining in current match period auto or teleop in seconds DriverStation getStickAxis stick axis Get the value of the axis on ajoystick This depends on the mapping of the joystick connected to the specified port Parameters e stick The joystick port number e axis The analog axis value to read from the joystick Returns The value of the axis on the joystick DriverStation getStickAxisCount stick Returns the number of axes on a given joystick port Parameters stick The joystick port number Returns The number of axes on the indicated joystick DriverStation getStickButton stick button The state of a button on the joystick Parameters e stick The joystick port number e button The button number to be read Returns The state of the button Dr
226. ts are seconds Counter setReverseDirection reverseDirection Set the Counter to return reversed sensing on the direction This allows counters to change the direction they are counting in the case of 1X and 2X quadrature encoding only Any other counter mode isn t supported Parameters reverseDirection bool True if the value counted should be negated Counter setSamplesToAverage samplesToAverage Set the Samples to Average which specifies the number of samples of the timer to average when calculating the period Perform averaging to account for mechanical imperfections or as oversampling to increase resolution Parameters samplesToAverage int The number of samples to average from 1 to 127 Counter setSemiPeriodMode highSemiPeriod Set Semi period mode on this counter Counts up on both rising and falling edges Parameters highSemiPeriod bool True to count up on both rising and falling Counter setUpDownCounterMode Set standard up down counting mode on this counter Up and down counts are sourced independently from two inputs Counter setUpSource args kwargs Set the up counting source for the counter This function accepts either a digital channel index a DigitalSource or an AnalogTrigger as positional arguments source echannel sanalogTrigger sanalog Trigger triggerType For positional arguments if the passed object has a getChannelForRouting function it is assumed to be a DigitalSource
227. tton of a joystick to a score command This class represents a subclass of Trigger that is specifically aimed at buttons on an operator interface as a common use case of the more generalized Trigger objects This is a simple wrapper around Trigger with the method names renamed to fit the Button object use cancelWhenPressed command Cancel the command when the button is pressed Parameters command toggleWhenPressed command Toggles the command whenever the button is pressed on then off then on Parameters command 1 4 wpilib buttons Package 109 RobotPy WPILib Documentation Release master whenPressed command Starts the given command whenever the button is newly pressed Parameters command the command to start whenReleased command Starts the command when the button is released Parameters command the command to start whileHeld command Constantly starts the given command while the button is held Command start will be called repeatedly while the button is held and will be canceled when the button is released Parameters command the command to start 1 4 2 InternalButton class woilib buttons InternalButton inverted False Bases woilib buttons Button This class is intended to be used within a program The programmer can manually set its value Includes a setting for whether or not it should invert its value Creates an InternalButton which is inverted depending on the inp
228. ty protocol The helper object has the code to actually do the timing and call the motors stop method when the timeout expires The motor object is expected to call the feed method whenever the motors value is updated The constructor for a MotorSafety object The helper object is constructed for every object that wants to imple ment the Motor Safety protocol The helper object has the code to actually do the timing and call the motors stop method when the timeout expires The motor object is expected to call the feed method whenever the motors value is updated DEFAULT_SAFETY_EXPIRATION 0 1 check Check if this motor has exceeded its timeout This method is called periodically to determine if this motor has exceeded its timeout value If it has the stop method is called and the motor is shut down until its value is updated again static checkMotors Check the motors to see if any have timed out This static method is called periodically to poll all the motors and stop any that have timed out feed Feed the motor safety object Resets the timer on this object that is used to do the timeouts getExpiration Retrieve the timeout value for the corresponding motor safety object Returns the timeout value in seconds Return type float helpers lt _weakrefset WeakSet object at 0x7 2574f00668 gt isAlive Determine of the motor is still operating or has timed out Returns True if the motor is still operating normal
229. type float Counter getRate Get the current rate of the Counter Read the current rate of the counter accounting for the distance per pulse value The default value for distance per pulse 1 yields units of pulses per second Returns The rate in units sec Return type float Counter getSamplesToAverage Get the Samples to Average which specifies the number of samples of the timer to average when calculating the period Perform averaging to account for mechanical imperfections or as oversampling to increase resolution Returns The number of samples being averaged from 1 to 127 Return type int Counter getStopped Determine if the clock is stopped Determine if the clocked input is stopped based on the MaxPeriod value set using the setMaxPeriod method If the clock exceeds the MaxPeriod then the device and counter are assumed to be stopped and it returns True Returns Returns True if the most recent counter period exceeds the MaxPeriod value set by SetMaxPeriod 46 Chapter 1 Contents RobotPy WPILib Documentation Release master Return type bool Counter pidGet Counter reset Reset the Counter to zero Set the counter value to zero This doesn t effect the running state of the counter just sets the current value to zero Counter setDistancePerPulse distancePerPulse Set the distance per pulse for this counter This sets the multiplier used to determine the distance driven based on the count value fr
230. u to figure out if there is a device on the I2C bus that responds to the address specified in the constructor Returns Transfer Aborted False for success True for aborted I2C broadcast registerAddress data Send a broadcast write to all devices on the I2C bus Warning This is not currently implemented Parameters e registerAddress The register to write on all devices on the bus e data The value to write to the devices I2C read registerAddress count Execute a read transaction with the device Read 1 to 7 bytes from a device Most I2C devices will auto increment the register pointer internally allowing you to read up to 7 consecutive registers on a device in a single transaction Parameters e registerAddress The register to read first in the transaction e count The number of bytes to read in the transaction 1 7 Returns The data read from the device I2C readOnly count Execute a read only transaction with the device Read 1 to 7 bytes from a device This method does not write any data to prompt the device Parameters count The number of bytes to read in the transaction 1 7 Returns The data read from the device I2C transaction dataToSend receiveSize Generic transaction This is a lower level interface to the I2C hardware giving you more control over each transaction Parameters e dataToSend Data to send as part of the transaction e receiveSize Number of bytes to read from
231. uality Set the guality of the compressed image sent to the dashboard Parameters guality The guality of the JPEG image from 0 to 100 setSize size startAutomaticCapture camera Start automatically capturing images to send to the dashboard You should call this method to just see a camera feed on the dashboard without doing any vision processing on the roboRIO link setImage shouldn t be called after this is called Parameters camera The camera interface e g a USBCamera instance 1 3 3 ADXL345 I2C class wwilib ADXL345 I2C port range Bases woilib SensorBase ADXL345 accelerometer device via i2c Constructor Parameters 14 Chapter 1 Contents RobotPy WPILib Documentation Release master e port The I2C port the accelerometer is attached to e range The range or that the accelerometer will measure class Axes Bases builtins object kx 0 ky 2 kzZz 4 class ADXL345 I2C Range Bases builtins object k16G 3 k2G 0 k4G 1 k8G 2 ADXL345 I2C getAcceleration axis Get the acceleration of one axis in Gs Parameters axis The axis to read from Returns An object containing the acceleration measured on each axis of the ADXL345 in Gs ADXL345 I2C getAccelerations Get the acceleration of all axes in Gs Returns X Y Z tuple of acceleration measured on all axes of the ADXL345 in Gs ADXL345 I2C getX Get the x axis acceleration Returns The acceleration along the x axis
232. uler method 121 run wpilib livewindow Live Window static method 72 S SafePWM class in wpilib safepwm 91 SampleRobot class in wpilib samplerobot 91 save wpilib preferences Preferences method 80 SAVE FIELD wpilib preferences Preferences attribute 77 Scheduler class in wpilib command scheduler 120 SELECTED wpilib sendablechooser SendableChooser attribute 93 Sendable class in wpilib sendable 93 SendableChooser class in wpilib sendablechooser 93 sendMessage wpilib canjaguar CANJaguar method 30 SensorBase class in wpilib sensorbase 94 sensors wpilib livewindow LiveWindow attribute 72 sensors wpilib ultrasonic Ultrasonic attribute 106 server wpilib impl dummycamera CameraServer attribute 12 14 Servo class in wpilib servo 95 set wpilib canjaguar CANJaguar method 30 set wpilib cantalon CANTalon method 39 set wpilib digitaloutput DigitalOutput method 50 set wpilib doublesolenoid DoubleSolenoid method 52 set wpilib interfaces speedcontroller SpeedController method 128 set wpilib jaguar Jaguar method 66 set wpilib relay Relay method 84 set wpilib servo Servo method 96 set wpilib solenoid Solenoid method 99 set wpilib solenoidbase SolenoidBase method 100 set wpilib talon Talon method 102 set wpilib talonsrx TalonSRX method 103 set wpilib victor Victor method 108 setAbsoluteTolerance wpilib command pi
233. urrent Closed Loop profile Whenever the error is larger than the izone value the accumulated integration error is cleared so that high errors aren t racked up when at high errors An izone value of 0 means no difference from a standard PIDF loop Parameters izone Width of the integration zone See setProfile For selecting a certain profile CANTalon setP p Set the proportional value of the currently selected profile Parameters p Proportional constant for the currently selected PID profile See setProfile For selecting a certain profile CANTalon setPID p i d f 0 izone 0 closeLoopRampRate 0 profile None Sets control values for closed loop control Parameters e p Proportional constant e i Integration constant e d Differential constant e f Feedforward constant e izone Integration zone prevents accumulation of integration error with large errors Setting this to zero will ignore any izone stuff 40 Chapter 1 Contents RobotPy WPILib Documentation Release master e closeLoopRampRate Closed loop ramp rate Maximum change in voltage in volts sec e profile which profile to set the pid constants for You can have two profiles with values of 0 or 1 allowing you to keep a second set of values on hand in the talon In order to switch profiles without recalling setPID you must call setProfile CANTalon setPosition pos CANTalon setProfile profile Select which cl
234. ut Parameters inverted If False then this button is pressed when set to True otherwise it is pressed when set to False get setInverted inverted setPressed pressed 1 4 3 JoystickButton class woilib buttons JoystickButton joystick buttonNumber Bases woilib buttons Button Create a joystick button for triggering commands Parameters e joystick The GenericHID object that has the button e g Joystick KinectStick etc e buttonNumber The button number see GenericHID getRawButton get Gets the value of the joystick button Returns The value of the joystick button 1 4 4 NetworkButton class woilib buttons NetworkButton table field Bases woilib buttons Button 110 Chapter 1 Contents RobotPy WPILib Documentation Release master get 1 4 5 Trigger class woilib buttons Trigger Bases builtins object This class provides an easy way to link commands to inputs It is very easy to link a button to a command For instance you could link the trigger button of a joystick to a score command It is encouraged that teams write a subclass of Trigger if they want to have something unusual for instance if they want to react to the user holding a button while the robot is reading a certain sensor input For this they only have to write the get method to get the full functionality of the Trigger class cancelWhenActive command Cancels a command when the trigger becomes active
235. uttonType class in wpilib joystick 67 Joystick RumbleType class in wpilib joystick 67 JoystickButton class in wpilib buttons joystickbutton 110 Jumper wpilib canjaguar CANJaguar NeutralMode at tribute 26 K k16G wpilib adx1345 i2c ADXL345 I2C Range tribute 15 at 146 Index RobotPy WPILib Documentation Release master k16G wpilib adx1345 spi ADXL345 SPI Range at kAddress MultiByte wpilib adx1345 spi ADXL345 SPI tribute 16 attribute 17 k16G wpilib builtinaccelerometer BuiltInAccelerometer Rakgeddress Read wpilib adx1345 spi ADXL345 SPI at attribute 24 tribute 17 k16G wpilib interfaces accelerometer Accelerometer RangekAnalogInputChannels Wwpilib sensorbase SensorBase attribute 124 attribute 95 k1X wpilib counter Counter EncodingType attribute 45 kAnalogOutputChannels wpilib sensorbase SensorBase k1X wpilib encoder Encoder EncodingType attribute attribute 95 57 kAngle wpilib counter Counter PIDSourceParameter at k1X wpilib interfaces counterbase CounterBase EncodingType tribute 45 attribute 124 kAngle wpilib encoder Encoder PIDSourceParameter at k1X wpilib pwm PWM PeriodMultiplier attribute 81 tribute 57 k2G wpilib adx1345 i2c ADXL345 I2C Range at kAngle wpilib interfaces pidsource PIDSource PIDSourceParameter tribute 15 attribute 127 k2G wpilib adx1345 spi ADXL345 SPI Range at kApproxBusVoltage wpilib canjaguar CANJaguar tribute 16 attribute 29
236. verridden autonomous and operatorControl methods are called at the appropriate time as the match proceeds In the current imple mentation the Autonomous code will run to completion before the OperatorControl code could start In the future the Autonomous code might be spawned as a task then killed at the end of the Autonomous period User code should be placed in the constructor that runs before the Autonomous or Operator Control period starts The constructor will run to completion before Autonomous is entered Warning If you override __init__ in your robot class you must call the base class constructor This must be used to ensure that the communications code starts free Free the resources for a RobotBase class static initializeHardwareConfiguration Common initialization for all robot programs isAutonomous Determine if the robot is currently in Autonomous mode Returns True if the robot is currently operating Autonomously as determined by the field con trols 1 3 wpilib Package 85 RobotPy WPILib Documentation Release master Return type bool isDisabled Determine if the Robot is currently disabled Returns True if the Robot is currently disabled by the field controls Return type bool isEnabled Determine if the Robot is currently enabled Returns True if the Robot is currently enabled by the field controls Return type bool isNewDataAvailable Indicates if new data is available
237. wpilib digitalinput module 49 wpilib digitaloutput module 50 wpilib digitalsource module 51 waitForInterrupt wpilib interruptablesensorbase Interrupt RISB BPB Olenoid module 51 method 64 WaitUntilCommand class in wpilib command waituntilcommand 123 whenActive wpilib buttons trigger Trigger method einer wpilib buttons trigger Trigger method hen ih wpilib buttons button Button method sree ae wpilib buttons button Button method oie wpilib buttons trigger Trigger method 111 whileHeld wpilib buttons button Button method 110 willRunWhenDisabled wpilib command command Comm3R method 115 wpilib module 10 wpilib impl dummycamera module 11 13 wpilib adx1345_i2c module 14 wpilib adx1345 spi module 16 wpilib analogaccelerometer module 17 wpilib analoginput module 18 wpilib analogoutput module 21 wpilib analogpotentiometer module 21 wpilib analogtrigger module 22 wpilib analogtriggeroutput module 23 wpilib builtinaccelerometer module 24 wpilib buttons module 109 wpilib buttons button module 109 wpilib buttons internalbutton module 110 wpilib buttons joystickbutton module 110 wpilib buttons networkbutton module 110 wpilib driverstation module 52 wpilib encoder module 56 wpilib geartooth module 60 wpilib gyro module 60 wpilib i2c module 61 wpilib interfaces module 123 wpilib interfaces accelerometer module 123 wpil
238. y at lower speeds Defaults to True if unspecified drive outputMagnitude curve motors at speed and curve The speed and curve are 1 0 to 1 0 values where 0 0 represents stopped and not turning The algorithm for adding in the direction attempts to provide a constant turn radius for differing speeds This func tion will most likely be used in an autonomous routine Parameters e outputMagnitude The forward component of the output magnitude to send to the mo tors e curve The rate of turn constant for different forward speeds RobotDrive RobotDrive RobotDrive RobotDrive free getDescription getNumMotors holonomicDrive magnitude direction rotation Holonomic Drive method for Mecanum wheeled robots This is an alias to mecanumDrive_Polar for backward compatibility Parameters e magnitude The speed that the robot should drive in a given direction 1 0 1 0 e direction The direction the robot should drive The direction and magnitude are inde pendent of the rotation rate e rotation The rate of rotation for the robot that is completely independent of the magni tude or direction 1 0 1 0 RobotDrive kArcadeRatioCurve_Reported False RobotDrive kArcadeStandard_Reported False 88 Chapter 1 Contents RobotPy WPILib Documentation Release master RobotDrive RobotDrive RobotDrive RobotDrive RobotDrive RobotDrive Ro
239. y 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 OV gt 3 3V Use set FeedbackDevice 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 set SensorPosition 34 Chapter 1 Contents RobotPy WPILib Documentation Release master Analog Input and quadrature position and velocity are also explicitly reported in getEncPosition getEncVelocity getAnalogInPosition getAnalogInRaw getAnalogInVelocity 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 set FeedbackDevice 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
Download Pdf Manuals
Related Search
Related Contents
Keystation Pro 88 Guía de inicio rápido Garmin Software Version 0370.17 Cockpit Reference Guide User Instruction & Installation Manual FB280 Tungsten Halogen e/r motorola gm950 HDD-8263/8264 Installation Guide 一般的な自転車に比べ、速度も出やすく、走行距離も伸ばすことができ FRIDGE-FREEZER USER`S MANUAL TFP120A Verizon VZ4000 Network Card User Manual Bosch GGS 6 S Professional Copyright © All rights reserved.
Failed to retrieve file