WPILibC++  2019.2.1-23-g997d4fd
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Modules Pages
frc Namespace Reference

WPILib FRC namespace. More...

Namespaces

 filesystem
 WPILib FileSystem namespace.
 

Classes

class  Accelerometer
 Interface for 3-axis accelerometers. More...
 
class  ADXL345_I2C
 ADXL345 Accelerometer on I2C. More...
 
class  ADXL345_SPI
 ADXL345 Accelerometer on SPI. More...
 
class  ADXL362
 ADXL362 SPI Accelerometer. More...
 
class  ADXRS450_Gyro
 Use a rate gyro to return the robots heading relative to a starting position. More...
 
class  AnalogAccelerometer
 Handle operation of an analog accelerometer. More...
 
class  AnalogGyro
 Use a rate gyro to return the robots heading relative to a starting position. More...
 
class  AnalogInput
 Analog input class. More...
 
class  AnalogOutput
 MXP analog output class. More...
 
class  AnalogPotentiometer
 Class for reading analog potentiometers. More...
 
class  AnalogTrigger
 
class  AnalogTriggerOutput
 Class to represent a specific output from an analog trigger. More...
 
class  BuiltInAccelerometer
 Built-in accelerometer. More...
 
class  BuiltInLayouts
 The types of layouts bundled with Shuffleboard. More...
 
class  BuiltInWidgets
 The types of the widgets bundled with Shuffleboard. More...
 
class  Button
 This class provides an easy way to link commands to OI inputs. More...
 
class  ButtonScheduler
 
class  CameraServer
 Singleton class for creating and keeping camera servers. More...
 
class  CameraServerShared
 
class  CAN
 High level class for interfacing with CAN devices conforming to the standard CAN spec. More...
 
class  CancelButtonScheduler
 
struct  CANData
 
struct  CANStatus
 
class  circular_buffer
 This is a simple circular buffer so we don't need to "bucket brigade" copy old values. More...
 
class  Command
 The Command class is at the very core of the entire command framework. More...
 
class  CommandGroup
 A CommandGroup is a list of commands which are executed in sequence. More...
 
class  CommandGroupEntry
 
class  ComplexWidget
 A Shuffleboard widget that handles a Sendable object such as a speed controller or sensor. More...
 
class  Compressor
 Class for operating a compressor connected to a PCM (Pneumatic Control Module). More...
 
class  ConditionalCommand
 A ConditionalCommand is a Command that starts one of two commands. More...
 
class  Controller
 Interface for Controllers. More...
 
class  ControllerPower
 
class  Counter
 Class for counting the number of ticks on a digital input channel. More...
 
class  CounterBase
 Interface for counting the number of ticks on a digital input channel. More...
 
class  DifferentialDrive
 A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base, "tank drive", or West Coast Drive. More...
 
class  DigitalGlitchFilter
 Class to enable glitch filtering on a set of digital inputs. More...
 
class  DigitalInput
 Class to read a digital input. More...
 
class  DigitalOutput
 Class to write to digital outputs. More...
 
class  DigitalSource
 DigitalSource Interface. More...
 
class  DMC60
 Digilent DMC 60 Speed Controller. More...
 
class  DoubleSolenoid
 DoubleSolenoid class for running 2 channels of high voltage Digital Output (PCM). More...
 
class  DriverStation
 Provide access to the network communication data to / from the Driver Station. More...
 
class  Encoder
 Class to read quad encoders. More...
 
class  Error
 Error object represents a library error. More...
 
class  ErrorBase
 Base class for most objects. More...
 
class  Filter
 Interface for filters. More...
 
class  GamepadBase
 Gamepad Interface. More...
 
class  GearTooth
 Alias for counter class. More...
 
class  GenericHID
 GenericHID Interface. More...
 
class  Gyro
 Interface for yaw rate gyros. More...
 
class  GyroBase
 GyroBase is the common base class for Gyro implementations such as AnalogGyro. More...
 
class  HeldButtonScheduler
 
class  I2C
 I2C bus interface class. More...
 
class  InstantCommand
 This command will execute once, then finish immediately afterward. More...
 
class  InternalButton
 
class  InterruptableSensorBase
 
class  IterativeRobot
 IterativeRobot implements the IterativeRobotBase robot program framework. More...
 
class  IterativeRobotBase
 IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase class. More...
 
class  Jaguar
 Luminary Micro / Vex Robotics Jaguar Speed Controller with PWM control. More...
 
class  Joystick
 Handle input from standard Joysticks connected to the Driver Station. More...
 
class  JoystickBase
 Joystick Interface. More...
 
class  JoystickButton
 
class  KilloughDrive
 A class for driving Killough drive platforms. More...
 
class  LayoutType
 Represents the type of a layout in Shuffleboard. More...
 
class  LinearDigitalFilter
 This class implements a linear, digital filter. More...
 
class  LiveWindow
 The LiveWindow class is the public interface for putting sensors and actuators on the LiveWindow. More...
 
class  LiveWindowSendable
 Live Window Sendable is a special type of object sendable to the live window. More...
 
class  MecanumDrive
 A class for driving Mecanum drive platforms. More...
 
class  MotorSafety
 This base class runs a watchdog timer and calls the subclass's StopMotor() function if the timeout expires. More...
 
class  NamedSendable
 The interface for sendable objects that gives the sendable a default name in the Smart Dashboard. More...
 
class  NetworkButton
 
class  NidecBrushless
 Nidec Brushless Motor. More...
 
class  Notifier
 
struct  NullDeleter
 
class  PIDBase
 Class implements a PID Control Loop. More...
 
class  PIDCommand
 
class  PIDController
 Class implements a PID Control Loop. More...
 
class  PIDInterface
 
class  PIDOutput
 PIDOutput interface is a generic output for the PID class. More...
 
class  PIDSource
 PIDSource interface is a generic sensor source for the PID class. More...
 
class  PIDSubsystem
 This class is designed to handle the case where there is a Subsystem which uses a single PIDController almost constantly (for instance, an elevator which attempts to stay at a constant height). More...
 
class  Potentiometer
 Interface for potentiometers. More...
 
class  POVButton
 
class  PowerDistributionPanel
 Class for getting voltage, current, temperature, power and energy from the CAN PDP. More...
 
class  Preferences
 The preferences class provides a relatively simple way to save important values to the roboRIO to access the next time the roboRIO is booted. More...
 
class  PressedButtonScheduler
 
class  PrintCommand
 
class  PWM
 Class implements the PWM generation in the FPGA. More...
 
class  PWMSpeedController
 Common base class for all PWM Speed Controllers. More...
 
class  PWMTalonSRX
 Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM control. More...
 
class  PWMVictorSPX
 Cross the Road Electronics (CTRE) Victor SPX Speed Controller with PWM control. More...
 
class  Relay
 Class for Spike style relay outputs. More...
 
class  ReleasedButtonScheduler
 
class  Resource
 The Resource class is a convenient way to track allocated resources. More...
 
class  RobotBase
 Implement a Robot Program framework. More...
 
class  RobotController
 
class  RobotDrive
 Utility class for handling Robot drive based on a definition of the motor configuration. More...
 
class  RobotDriveBase
 Common base class for drive platforms. More...
 
class  RobotState
 
class  SampleRobot
 
class  Scheduler
 
class  SD540
 Mindsensors SD540 Speed Controller. More...
 
class  Sendable
 
class  SendableBase
 
class  SendableBuilder
 
class  SendableBuilderImpl
 
class  SendableCameraWrapper
 A wrapper to make video sources sendable and usable from Shuffleboard. More...
 
class  SendableChooser
 The SendableChooser class is a useful tool for presenting a selection of options to the SmartDashboard. More...
 
class  SendableChooserBase
 This class is a non-template base class for SendableChooser. More...
 
class  SensorUtil
 Stores most recent status information as well as containing utility functions for checking channels and error processing. More...
 
class  SerialPort
 Driver for the RS-232 serial port on the roboRIO. More...
 
class  Servo
 Standard hobby style servo. More...
 
class  Shuffleboard
 The Shuffleboard class provides a mechanism with which data can be added and laid out in the Shuffleboard dashboard application from a robot program. More...
 
class  ShuffleboardComponent
 A generic component in Shuffleboard. More...
 
class  ShuffleboardComponentBase
 A shim class to allow storing ShuffleboardComponents in arrays. More...
 
class  ShuffleboardContainer
 Common interface for objects that can contain shuffleboard components. More...
 
class  ShuffleboardLayout
 A layout in a Shuffleboard tab. More...
 
class  ShuffleboardRoot
 The root of the data placed in Shuffleboard. More...
 
class  ShuffleboardTab
 Represents a tab in the Shuffleboard dashboard. More...
 
class  ShuffleboardValue
 
class  ShuffleboardWidget
 Abstract superclass for widgets. More...
 
class  SimpleWidget
 A Shuffleboard widget that handles a single data point such as a number or string. More...
 
class  SmartDashboard
 
class  Solenoid
 Solenoid class for running high voltage Digital Output (PCM). More...
 
class  SolenoidBase
 SolenoidBase class is the common base class for the Solenoid and DoubleSolenoid classes. More...
 
class  Spark
 REV Robotics Speed Controller. More...
 
class  SpeedController
 Interface for speed controlling devices. More...
 
class  SpeedControllerGroup
 
class  SPI
 SPI bus interface class. More...
 
class  StartCommand
 
class  Subsystem
 
class  Talon
 Cross the Road Electronics (CTRE) Talon and Talon SR Speed Controller. More...
 
class  TimedCommand
 A TimedCommand will wait for a timeout before finishing. More...
 
class  TimedRobot
 TimedRobot implements the IterativeRobotBase robot program framework. More...
 
class  Timer
 Timer objects measure accumulated time in seconds. More...
 
class  ToggleButtonScheduler
 
class  Trigger
 This class provides an easy way to link commands to inputs. More...
 
class  Ultrasonic
 Ultrasonic rangefinder class. More...
 
struct  Vector2d
 This is a 2D vector struct that supports basic vector operations. More...
 
class  Victor
 Vex Robotics Victor 888 Speed Controller. More...
 
class  VictorSP
 Vex Robotics Victor SP Speed Controller. More...
 
class  VisionPipeline
 A vision pipeline is responsible for running a group of OpenCV algorithms to extract data from an image. More...
 
class  VisionRunner
 A vision runner is a convenient wrapper object to make it easy to run vision pipelines from robot code. More...
 
class  VisionRunnerBase
 Non-template base class for VisionRunner. More...
 
class  WaitCommand
 
class  WaitForChildren
 
class  WaitUntilCommand
 
class  Watchdog
 A class that's a wrapper around a watchdog timer. More...
 
class  WidgetType
 Represents the type of a widget in Shuffleboard. More...
 
class  XboxController
 Handle input from Xbox 360 or Xbox One controllers connected to the Driver Station. More...
 

Typedefs

using TimerEventHandler = std::function< void()>
 
using TimerInterruptHandler = void(*)(void *param)
 

Enumerations

enum  PIDSourceType { kDisplacement, kRate }
 
enum  AnalogTriggerType { kInWindow = 0, kState = 1, kRisingPulse = 2, kFallingPulse = 3 }
 
enum  ShuffleboardEventImportance {
  kTrivial, kLow, kNormal, kHigh,
  kCritical
}
 

Functions

void SetCameraServerShared (std::unique_ptr< CameraServerShared > shared)
 
CameraServerSharedGetCameraServerShared ()
 
int GetThreadPriority (std::thread &thread, bool *isRealTime)
 Get the thread priority for the specified thread. More...
 
int GetCurrentThreadPriority (bool *isRealTime)
 Get the thread priority for the current thread. More...
 
bool SetThreadPriority (std::thread &thread, bool realTime, int priority)
 Sets the thread priority for the specified thread. More...
 
bool SetCurrentThreadPriority (bool realTime, int priority)
 Sets the thread priority for the current thread. More...
 
wpi::StringRef ShuffleboardEventImportanceName (ShuffleboardEventImportance importance)
 
int RunHALInitialization ()
 
template<class Robot >
int StartRobot ()
 
void Wait (double seconds)
 Pause the task for a specified time. More...
 
double GetClock ()
 Return the FPGA system clock time in seconds. More...
 
double GetTime ()
 Gives real-time clock system time with nanosecond resolution. More...
 
int GetFPGAVersion ()
 Return the FPGA Version number. More...
 
int64_t GetFPGARevision ()
 Return the FPGA Revision number. More...
 
uint64_t GetFPGATime ()
 Read the microsecond-resolution timer on the FPGA. More...
 
bool GetUserButton ()
 Get the state of the "USER" button on the roboRIO. More...
 
std::string GetStackTrace (int offset)
 Get a stack trace, ignoring the first "offset" symbols. More...
 

Detailed Description

WPILib FRC namespace.

Function Documentation

double frc::GetClock ( )

Return the FPGA system clock time in seconds.

This is deprecated and just forwards to Timer::GetFPGATimestamp().

Returns
Robot running time in seconds.
int frc::GetCurrentThreadPriority ( bool *  isRealTime)

Get the thread priority for the current thread.

Parameters
isRealTimeSet to true if thread is realtime, otherwise false.
Returns
The current thread priority. Scaled 1-99.
int64_t frc::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.
Deprecated:
Use RobotController static class method
uint64_t frc::GetFPGATime ( )

Read the microsecond-resolution timer on the FPGA.

Returns
The current time in microseconds according to the FPGA (since FPGA reset).
Deprecated:
Use RobotController static class method
int frc::GetFPGAVersion ( )

Return the FPGA Version number.

For now, expect this to be competition year.

Returns
FPGA Version number.
Deprecated:
Use RobotController static class method
std::string frc::GetStackTrace ( int  offset)

Get a stack trace, ignoring the first "offset" symbols.

Parameters
offsetThe number of symbols at the top of the stack to ignore
int frc::GetThreadPriority ( std::thread &  thread,
bool *  isRealTime 
)

Get the thread priority for the specified thread.

Parameters
threadReference to the thread to get the priority for.
isRealTimeSet to true if thread is realtime, otherwise false.
Returns
The current thread priority. Scaled 1-99, with 1 being highest.
double frc::GetTime ( )

Gives real-time clock system time with nanosecond resolution.

Returns
The time, just in case you want the robot to start autonomous at 8pm on Saturday.
bool frc::GetUserButton ( )

Get the state of the "USER" button on the roboRIO.

Returns
True if the button is currently pressed down
Deprecated:
Use RobotController static class method
bool frc::SetCurrentThreadPriority ( bool  realTime,
int  priority 
)

Sets the thread priority for the current thread.

Parameters
realTimeSet to true to set a realtime priority, false for standard priority.
priorityPriority to set the thread to. Scaled 1-99, with 1 being highest. On RoboRIO, priority is ignored for non realtime setting.
Returns
The success state of setting the priority
bool frc::SetThreadPriority ( std::thread &  thread,
bool  realTime,
int  priority 
)

Sets the thread priority for the specified thread.

Parameters
threadReference to the thread to set the priority of.
realTimeSet to true to set a realtime priority, false for standard priority.
priorityPriority to set the thread to. Scaled 1-99, with 1 being highest. On RoboRIO, priority is ignored for non realtime setting.
Returns
The success state of setting the priority
void frc::Wait ( double  seconds)

Pause the task for a specified time.

Pause the execution of the program 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 task containing the wait will pause until the wait time is expired.

Parameters
secondsLength of time to pause, in seconds.