|
| class | AddressableLED |
| | A class for driving addressable LEDs, such as WS2812B, WS2815, and NeoPixels. More...
|
| |
| class | ADIS16448_IMU |
| | Use DMA SPI to read rate, acceleration, and magnetometer data from the ADIS16448 IMU and return the robots heading relative to a starting position, AHRS, and instant measurements. More...
|
| |
| class | ADIS16470_IMU |
| | Use DMA SPI to read rate and acceleration data from the ADIS16470 IMU and return the robot's heading relative to a starting position and instant measurements. 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 | Alert |
| | Persistent alert to be sent via NetworkTables. More...
|
| |
| class | AnalogAccelerometer |
| | Handle operation of an analog accelerometer. More...
|
| |
| class | AnalogEncoder |
| | Class for supporting continuous analog encoders, such as the US Digital MA3. 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...
|
| |
| struct | AprilTag |
| | Represents an AprilTag's metadata. More...
|
| |
| class | AprilTagDetection |
| | A detection of an AprilTag tag. More...
|
| |
| class | AprilTagDetector |
| | An AprilTag detector engine. More...
|
| |
| class | AprilTagFieldLayout |
| | Class for representing a layout of AprilTags on a field and reading them from a JSON format. More...
|
| |
| struct | AprilTagPoseEstimate |
| | A pair of AprilTag pose estimates. More...
|
| |
| class | AprilTagPoseEstimator |
| | Pose estimators for AprilTag tags. More...
|
| |
| class | ArmFeedforward |
| | A helper class that computes feedforward outputs for a simple arm (modeled as a motor acting against the force of gravity on a beam suspended at an angle). More...
|
| |
| class | AsynchronousInterrupt |
| | Class for handling asynchronous interrupts using a callback thread. More...
|
| |
| class | BangBangController |
| | Implements a bang-bang controller, which outputs either 0 or 1 depending on whether the measurement is less than the setpoint. More...
|
| |
| class | BooleanEvent |
| | This class provides an easy way to link actions to active high logic signals. More...
|
| |
| class | BuiltInAccelerometer |
| | Built-in accelerometer. More...
|
| |
| 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...
|
| |
| struct | CANData |
| |
| struct | CANStatus |
| |
| class | CentripetalAccelerationConstraint |
| | A constraint on the maximum absolute centripetal acceleration allowed when traversing a trajectory. More...
|
| |
| struct | ChassisSpeeds |
| | Represents the speed of a robot chassis. More...
|
| |
| class | Color |
| | Represents colors that can be used with Addressable LEDs. More...
|
| |
| class | Color8Bit |
| | Represents colors that can be used with Addressable LEDs. More...
|
| |
| class | ComplexWidget |
| | A Shuffleboard widget that handles a Sendable object such as a motor controller or sensor. More...
|
| |
| class | Compressor |
| | Class for operating a compressor connected to a pneumatics module. More...
|
| |
| class | ControlAffinePlantInversionFeedforward |
| | Constructs a control-affine plant inversion model-based feedforward from given model dynamics. More...
|
| |
| class | CoordinateAxis |
| | A class representing a coordinate system axis within the NWU coordinate system. More...
|
| |
| class | CoordinateSystem |
| | A helper class that converts Pose3d objects between different standard coordinate frames. More...
|
| |
| 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 | ct_matrix |
| | Compile-time wrapper for Eigen::Matrix. More...
|
| |
| class | CubicHermiteSpline |
| | Represents a hermite spline of degree 3. More...
|
| |
| class | DataLogManager |
| | Centralized data log that provides automatic data log file management. More...
|
| |
| class | DCMotor |
| | Holds the constants for a DC motor. More...
|
| |
| class | Debouncer |
| | A simple debounce filter for boolean streams. 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 | DifferentialDriveAccelerationLimiter |
| | Filters the provided voltages to limit a differential drive's linear and angular acceleration. More...
|
| |
| class | DifferentialDriveFeedforward |
| | A helper class which computes the feedforward outputs for a differential drive drivetrain. More...
|
| |
| class | DifferentialDriveKinematics |
| | Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velocities for a differential drive. More...
|
| |
| class | DifferentialDriveKinematicsConstraint |
| | A class that enforces constraints on the differential drive kinematics. More...
|
| |
| class | DifferentialDriveOdometry |
| | Class for differential drive odometry. More...
|
| |
| class | DifferentialDriveOdometry3d |
| | Class for differential drive odometry. More...
|
| |
| class | DifferentialDrivePoseEstimator |
| | This class wraps Differential Drive Odometry to fuse latency-compensated vision measurements with differential drive encoder measurements. More...
|
| |
| class | DifferentialDrivePoseEstimator3d |
| | This class wraps Differential Drive Odometry to fuse latency-compensated vision measurements with differential drive encoder measurements. More...
|
| |
| class | DifferentialDriveVoltageConstraint |
| | A class that enforces constraints on differential drive voltage expenditure based on the motor dynamics and the drive kinematics. More...
|
| |
| struct | DifferentialDriveWheelPositions |
| | Represents the wheel positions for a differential drive drivetrain. More...
|
| |
| struct | DifferentialDriveWheelSpeeds |
| | Represents the wheel speeds for a differential drive drivetrain. More...
|
| |
| struct | DifferentialDriveWheelVoltages |
| | Motor voltages for a differential 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 | DMA |
| | Class for configuring Direct Memory Access (DMA) of FPGA inputs. More...
|
| |
| class | DMASample |
| | DMA sample. More...
|
| |
| class | DMC60 |
| | Digilent DMC 60 Motor Controller with PWM control. More...
|
| |
| class | DoubleSolenoid |
| | DoubleSolenoid class for running 2 channels of high voltage Digital Output on a pneumatics module. More...
|
| |
| class | DriverStation |
| | Provide access to the network communication data to / from the Driver Station. More...
|
| |
| class | DSControlWord |
| | A wrapper around Driver Station control word. More...
|
| |
| class | DutyCycle |
| | Class to read a duty cycle PWM input. More...
|
| |
| class | DutyCycleEncoder |
| | Class for supporting duty cycle/PWM encoders, such as the US Digital MA3 with PWM Output, the CTRE Mag Encoder, the Rev Hex Encoder, and the AM Mag Encoder. More...
|
| |
| class | ElevatorFeedforward |
| | A helper class that computes feedforward outputs for a simple elevator (modeled as a motor acting against the force of gravity). More...
|
| |
| class | Ellipse2d |
| | Represents a 2d ellipse space containing translational, rotational, and scaling components. More...
|
| |
| class | EllipticalRegionConstraint |
| | Enforces a particular constraint only within an elliptical region. More...
|
| |
| class | Encoder |
| | Class to read quad encoders. More...
|
| |
| class | EventLoop |
| | A declarative way to bind a set of actions to a loop and execute them when the loop is polled. More...
|
| |
| class | ExponentialProfile |
| | A Exponential-shaped velocity profile. More...
|
| |
| class | ExtendedKalmanFilter |
| | A Kalman filter combines predictions from a model and measurements to give an estimate of the true system state. More...
|
| |
| class | ExternalDirectionCounter |
| | Counter using external direction. More...
|
| |
| class | Field2d |
| | 2D representation of game field for dashboards. More...
|
| |
| class | FieldObject2d |
| | Game field object on a Field2d. More...
|
| |
| class | GenericHID |
| | Handle input from standard HID devices connected to the Driver Station. More...
|
| |
| class | HolonomicDriveController |
| | This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i.e. More...
|
| |
| class | I2C |
| | I2C bus interface class. More...
|
| |
| class | ImplicitModelFollower |
| | Contains the controller coefficients and logic for an implicit model follower. More...
|
| |
| class | IterativeRobotBase |
| | IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase class. More...
|
| |
| class | Jaguar |
| | Luminary Micro / Vex Robotics Jaguar Motor Controller with PWM control. More...
|
| |
| class | Joystick |
| | Handle input from standard Joysticks connected to the Driver Station. More...
|
| |
| class | KalmanFilter |
| | A Kalman filter combines predictions from a model and measurements to give an estimate of the true system state. More...
|
| |
| class | KalmanFilterLatencyCompensator |
| | This class incorporates time-delayed measurements into a Kalman filter's state estimate. More...
|
| |
| class | Kinematics |
| | Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds. More...
|
| |
| class | Koors40 |
| | AndyMark Koors40 Motor Controller with PWM control. More...
|
| |
| class | LayoutType |
| | Represents the type of a layout in Shuffleboard. More...
|
| |
| class | LEDPattern |
| |
| class | LinearFilter |
| | This class implements a linear, digital filter. More...
|
| |
| class | LinearPlantInversionFeedforward |
| | Constructs a plant inversion model-based feedforward from a LinearSystem. More...
|
| |
| class | LinearQuadraticRegulator |
| | Contains the controller coefficients and logic for a linear-quadratic regulator (LQR). More...
|
| |
| class | LinearSystem |
| | A plant defined using state-space notation. More...
|
| |
| class | LinearSystemId |
| | Linear system ID utility functions. More...
|
| |
| class | LinearSystemLoop |
| | Combines a controller, feedforward, and observer for controlling a mechanism with full state feedback. More...
|
| |
| class | LiveWindow |
| | The LiveWindow class is the public interface for putting sensors and actuators on the LiveWindow. More...
|
| |
| class | LTVDifferentialDriveController |
| | The linear time-varying differential drive controller has a similar form to the LQR, but the model used to compute the controller gain is the nonlinear differential drive model linearized around the drivetrain's current state. More...
|
| |
| class | LTVUnicycleController |
| | The linear time-varying unicycle controller has a similar form to the LQR, but the model used to compute the controller gain is the nonlinear unicycle model linearized around the drivetrain's current state. More...
|
| |
| class | MaxVelocityConstraint |
| | Represents a constraint that enforces a max velocity. More...
|
| |
| class | MecanumDrive |
| | A class for driving Mecanum drive platforms. More...
|
| |
| class | MecanumDriveKinematics |
| | Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds. More...
|
| |
| class | MecanumDriveKinematicsConstraint |
| | A class that enforces constraints on the mecanum drive kinematics. More...
|
| |
| class | MecanumDriveOdometry |
| | Class for mecanum drive odometry. More...
|
| |
| class | MecanumDriveOdometry3d |
| | Class for mecanum drive odometry. More...
|
| |
| class | MecanumDrivePoseEstimator |
| | This class wraps Mecanum Drive Odometry to fuse latency-compensated vision measurements with mecanum drive encoder velocity measurements. More...
|
| |
| class | MecanumDrivePoseEstimator3d |
| | This class wraps Mecanum Drive Odometry to fuse latency-compensated vision measurements with mecanum drive encoder velocity measurements. More...
|
| |
| struct | MecanumDriveWheelPositions |
| | Represents the wheel positions for a mecanum drive drivetrain. More...
|
| |
| struct | MecanumDriveWheelSpeeds |
| | Represents the wheel speeds for a mecanum drive drivetrain. More...
|
| |
| class | Mechanism2d |
| | Visual 2D representation of arms, elevators, and general mechanisms through a node-based API. More...
|
| |
| class | MechanismLigament2d |
| | Ligament node on a Mechanism2d. More...
|
| |
| class | MechanismObject2d |
| | Common base class for all Mechanism2d node types. More...
|
| |
| class | MechanismRoot2d |
| | Root Mechanism2d node. More...
|
| |
| class | MedianFilter |
| | A class that implements a moving-window median filter. More...
|
| |
| class | MerweScaledSigmaPoints |
| | Generates sigma points and weights according to Van der Merwe's 2004 dissertation[1] for the UnscentedKalmanFilter class. More...
|
| |
| class | MotorController |
| | Interface for motor controlling devices. More...
|
| |
| class | MotorControllerGroup |
| | Allows multiple MotorController objects to be linked together. More...
|
| |
| class | MotorSafety |
| | The Motor Safety feature acts as a watchdog timer for an individual motor. More...
|
| |
| class | NetworkBooleanEvent |
| | A Button that uses a NetworkTable boolean field. More...
|
| |
| class | NidecBrushless |
| | Nidec Brushless Motor. More...
|
| |
| class | Notifier |
| | Notifiers run a user-provided callback function on a separate thread. More...
|
| |
| class | Odometry |
| | Class for odometry. More...
|
| |
| class | Odometry3d |
| | Class for odometry. More...
|
| |
| class | OnBoardIO |
| | This class represents the onboard IO of the Romi reference robot. More...
|
| |
| class | PIDController |
| | Implements a PID control loop. More...
|
| |
| class | PneumaticHub |
| | Module class for controlling a REV Robotics Pneumatic Hub. More...
|
| |
| class | PneumaticsBase |
| | Base class for pneumatics devices. More...
|
| |
| class | PneumaticsControlModule |
| | Module class for controlling a Cross The Road Electronics Pneumatics Control Module. More...
|
| |
| class | Pose2d |
| | Represents a 2D pose containing translational and rotational elements. More...
|
| |
| class | Pose3d |
| | Represents a 3D pose containing translational and rotational elements. More...
|
| |
| class | PoseEstimator |
| | This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements. More...
|
| |
| class | PoseEstimator3d |
| | This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements. More...
|
| |
| class | PowerDistribution |
| | Class for getting voltage, current, temperature, power and energy from the CTRE Power Distribution Panel (PDP) or REV Power Distribution Hub (PDH). 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 | ProfiledPIDController |
| | Implements a PID control loop whose setpoint is constrained by a trapezoid profile. More...
|
| |
| class | PS4Controller |
| | Handle input from PS4 controllers connected to the Driver Station. More...
|
| |
| class | PS5Controller |
| | Handle input from PS5 controllers connected to the Driver Station. More...
|
| |
| class | PWM |
| | Class implements the PWM generation in the FPGA. More...
|
| |
| class | PWMMotorController |
| | Common base class for all PWM Motor Controllers. More...
|
| |
| class | PWMSparkFlex |
| | REV Robotics SPARK Flex Motor Controller with PWM control. More...
|
| |
| class | PWMSparkMax |
| | REV Robotics SPARK MAX Motor Controller with PWM control. More...
|
| |
| class | PWMTalonFX |
| | Cross the Road Electronics (CTRE) Talon FX Motor Controller with PWM control. More...
|
| |
| class | PWMTalonSRX |
| | Cross the Road Electronics (CTRE) Talon SRX Motor Controller with PWM control. More...
|
| |
| class | PWMVenom |
| | Playing with Fusion Venom Motor Controller with PWM control. More...
|
| |
| class | PWMVictorSPX |
| | Cross the Road Electronics (CTRE) Victor SPX Motor Controller with PWM control. More...
|
| |
| class | Quaternion |
| | Represents a quaternion. More...
|
| |
| class | QuinticHermiteSpline |
| | Represents a hermite spline of degree 5. More...
|
| |
| class | RamseteController |
| | Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to a desired pose along a two-dimensional trajectory. More...
|
| |
| class | Rectangle2d |
| | Represents a 2d rectangular space containing translational, rotational, and scaling components. More...
|
| |
| class | RectangularRegionConstraint |
| | Enforces a particular constraint only within a rectangular region. More...
|
| |
| class | Relay |
| | Class for Spike style relay outputs. More...
|
| |
| 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 | RobotDriveBase |
| | Common base class for drive platforms. More...
|
| |
| class | RobotState |
| | Robot state utility functions. More...
|
| |
| class | RomiGyro |
| | Use a rate gyro to return the robots heading relative to a starting position. More...
|
| |
| class | RomiMotor |
| | RomiMotor. More...
|
| |
| class | Rotation2d |
| | A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine). More...
|
| |
| class | Rotation3d |
| | A rotation in a 3D coordinate frame represented by a quaternion. More...
|
| |
| class | RuntimeError |
| | Runtime error exception. More...
|
| |
| class | ScopedTracer |
| | A class for keeping track of how much time it takes for different parts of code to execute. More...
|
| |
| class | SD540 |
| | Mindsensors SD540 Motor Controller with PWM control. More...
|
| |
| class | SendableBuilderImpl |
| | Implementation detail for SendableBuilder. More...
|
| |
| 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 | SharpIR |
| |
| class | SharpIRSim |
| | Simulation class for Sharp IR sensors. 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 | SimpleMotorFeedforward |
| | A helper class that computes feedforward voltages for a simple permanent-magnet DC motor. More...
|
| |
| class | SimpleWidget |
| | A Shuffleboard widget that handles a single data point such as a number or string. More...
|
| |
| class | SimulatedAnnealing |
| | An implementation of the Simulated Annealing stochastic nonlinear optimization method. More...
|
| |
| class | SlewRateLimiter |
| | A class that limits the rate of change of an input value. More...
|
| |
| class | SmartDashboard |
| |
| class | Solenoid |
| | Solenoid class for running high voltage Digital Output on a pneumatics module. More...
|
| |
| class | Spark |
| | REV Robotics SPARK Motor Controller with PWM control. More...
|
| |
| class | SPI |
| | SPI bus interface class. More...
|
| |
| class | Spline |
| | Represents a two-dimensional parametric spline that interpolates between two points. More...
|
| |
| class | SplineHelper |
| | Helper class that is used to generate cubic and quintic splines from user provided waypoints. More...
|
| |
| class | SplineParameterizer |
| | Class used to parameterize a spline by its arc length. More...
|
| |
| class | StadiaController |
| | Handle input from Stadia controllers connected to the Driver Station. More...
|
| |
| class | SteadyStateKalmanFilter |
| | A Kalman filter combines predictions from a model and measurements to give an estimate of the true system state. More...
|
| |
| class | SuppliedValueWidget |
| |
| class | SwerveDriveKinematics |
| | Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states (speed and angle). More...
|
| |
| class | SwerveDriveKinematicsConstraint |
| | A class that enforces constraints on the swerve drive kinematics. More...
|
| |
| class | SwerveDriveOdometry |
| | Class for swerve drive odometry. More...
|
| |
| class | SwerveDriveOdometry3d |
| | Class for swerve drive odometry. More...
|
| |
| class | SwerveDrivePoseEstimator |
| | This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve drive encoder distance measurements. More...
|
| |
| class | SwerveDrivePoseEstimator3d |
| | This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve drive encoder distance measurements. More...
|
| |
| struct | SwerveModulePosition |
| | Represents the position of one swerve module. More...
|
| |
| struct | SwerveModuleState |
| | Represents the state of one swerve module. More...
|
| |
| class | SynchronousInterrupt |
| | Class for handling synchronous (blocking) interrupts. More...
|
| |
| class | Tachometer |
| | Tachometer for getting rotational speed from a device. More...
|
| |
| class | Talon |
| | Cross the Road Electronics (CTRE) Talon Motor Controller with PWM control. More...
|
| |
| class | TimedRobot |
| | TimedRobot implements the IterativeRobotBase robot program framework. More...
|
| |
| class | TimeInterpolatableBuffer |
| | The TimeInterpolatableBuffer provides an easy way to estimate past measurements. More...
|
| |
| class | Timer |
| | A timer class. More...
|
| |
| class | TimesliceRobot |
| | TimesliceRobot extends the TimedRobot robot program framework to provide timeslice scheduling of periodic functions. More...
|
| |
| class | Tracer |
| | A class for keeping track of how much time it takes for different parts of code to execute. More...
|
| |
| class | Trajectory |
| | Represents a time-parameterized trajectory. More...
|
| |
| class | TrajectoryConfig |
| | Represents the configuration for generating a trajectory. More...
|
| |
| class | TrajectoryConstraint |
| | An interface for defining user-defined velocity and acceleration constraints while generating trajectories. More...
|
| |
| class | TrajectoryGenerator |
| | Helper class used to generate trajectories with various constraints. More...
|
| |
| class | TrajectoryParameterizer |
| | Class used to parameterize a trajectory by time. More...
|
| |
| class | TrajectoryUtil |
| | Trajectory utilities. More...
|
| |
| class | Transform2d |
| | Represents a transformation for a Pose2d in the pose's frame. More...
|
| |
| class | Transform3d |
| | Represents a transformation for a Pose3d in the pose's frame. More...
|
| |
| class | Translation2d |
| | Represents a translation in 2D space. More...
|
| |
| class | Translation3d |
| | Represents a translation in 3D space. More...
|
| |
| class | TrapezoidProfile |
| | A trapezoid-shaped velocity profile. More...
|
| |
| class | TravelingSalesman |
| | Given a list of poses, this class finds the shortest possible route that visits each pose exactly once and returns to the origin pose. More...
|
| |
| struct | Twist2d |
| | A change in distance along a 2D arc since the last pose update. More...
|
| |
| struct | Twist3d |
| | A change in distance along a 3D arc since the last pose update. More...
|
| |
| class | Ultrasonic |
| | Ultrasonic rangefinder class. More...
|
| |
| class | UnscentedKalmanFilter |
| | A Kalman filter combines predictions from a model and measurements to give an estimate of the true system state. More...
|
| |
| class | UpDownCounter |
| | Up Down Counter. More...
|
| |
| class | Victor |
| | Vex Robotics Victor 888 Motor Controller with PWM control. More...
|
| |
| class | VictorSP |
| | Vex Robotics Victor SP Motor Controller with PWM control. 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 | 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 controllers connected to the Driver Station. More...
|
| |
| class | XRPGyro |
| | Use a rate gyro to return the robots heading relative to a starting position. More...
|
| |
| class | XRPMotor |
| | XRPMotor. More...
|
| |
| class | XRPOnBoardIO |
| | This class represents the onboard IO of the XRP reference robot. More...
|
| |
| class | XRPRangefinder |
| | This class represents the ultrasonic rangefinder on an XRP robot. More...
|
| |
| class | XRPReflectanceSensor |
| | This class represents the reflectance sensor pair on an XRP robot. More...
|
| |
| class | XRPServo |
| | XRPServo. More...
|
| |
|
| constexpr auto | format_as (AddressableLED::ColorOrder order) |
| |
| template class | EXPORT_TEMPLATE_DECLARE (WPILIB_DLLEXPORT) KalmanFilter< 1 |
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Rotation3d &rotation) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Rotation3d &rotation) |
| |
| AprilTagDetector::Results | AprilTagDetect (AprilTagDetector &detector, cv::Mat &image) |
| |
| CameraServerShared * | GetCameraServerShared () |
| |
| const char * | GetErrorMessage (int32_t *code) |
| | Gets error message string for an error code.
|
| |
| void | ReportErrorV (int32_t status, const char *fileName, int lineNumber, const char *funcName, fmt::string_view format, fmt::format_args args) |
| | Reports an error to the driver station (using HAL_SendError).
|
| |
| template<typename... Args> |
| void | ReportError (int32_t status, const char *fileName, int lineNumber, const char *funcName, fmt::string_view format, Args &&... args) |
| | Reports an error to the driver station (using HAL_SendError).
|
| |
| RuntimeError | MakeErrorV (int32_t status, const char *fileName, int lineNumber, const char *funcName, fmt::string_view format, fmt::format_args args) |
| | Makes a runtime error exception object.
|
| |
| template<typename... Args> |
| RuntimeError | MakeError (int32_t status, const char *fileName, int lineNumber, const char *funcName, fmt::string_view format, Args &&... args) |
| |
| template<int CovDim, int States> |
| std::tuple< Vectord< CovDim >, Matrixd< CovDim, CovDim > > | SquareRootUnscentedTransform (const Matrixd< CovDim, 2 *States+1 > &sigmas, const Vectord< 2 *States+1 > &Wm, const Vectord< 2 *States+1 > &Wc, std::function< Vectord< CovDim >(const Matrixd< CovDim, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> meanFunc, std::function< Vectord< CovDim >(const Vectord< CovDim > &, const Vectord< CovDim > &)> residualFunc, const Matrixd< CovDim, CovDim > &squareRootR) |
| | Computes unscented transform of a set of sigma points and weights.
|
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Translation2d &state) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Translation2d &state) |
| |
| int | RunHALInitialization () |
| |
| template<class Robot > |
| int | StartRobot () |
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Pose2d &pose) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Pose2d &pose) |
| |
| std::string_view | ShuffleboardEventImportanceName (ShuffleboardEventImportance importance) |
| | Returns name of the given enum.
|
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Quaternion &quaternion) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Quaternion &quaternion) |
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Pose3d &pose) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Pose3d &pose) |
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const AprilTagFieldLayout &layout) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, AprilTagFieldLayout &layout) |
| |
| WPILIB_DLLEXPORT AprilTagFieldLayout | LoadAprilTagLayoutField (AprilTagField field) |
| | Loads an AprilTagFieldLayout from a predefined field.
|
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Trajectory::State &state) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Trajectory::State &state) |
| |
| WPILIB_DLLEXPORT constexpr frc::Pose3d | ObjectToRobotPose (const frc::Pose3d &objectInField, const frc::Transform3d &cameraToObject, const frc::Transform3d &robotToCamera) |
| | Returns the robot's pose in the field coordinate system given an object's field-relative pose, the transformation from the camera's pose to the object's pose (obtained via computer vision), and the transformation from the robot's pose to the camera's pose.
|
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const AprilTag &apriltag) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, AprilTag &apriltag) |
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Rotation2d &rotation) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Rotation2d &rotation) |
| |
| constexpr std::string_view | to_string (const DAREError &error) |
| | Converts the given DAREError enum to a string.
|
| |
| template<int States, int Inputs> |
| wpi::expected< Eigen::Matrix< double, States, States >, DAREError > | DARE (const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B, const Eigen::Matrix< double, States, States > &Q, const Eigen::Matrix< double, Inputs, Inputs > &R, bool checkPreconditions=true) |
| | Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:
|
| |
| template<int States, int Inputs> |
| wpi::expected< Eigen::Matrix< double, States, States >, DAREError > | DARE (const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B, const Eigen::Matrix< double, States, States > &Q, const Eigen::Matrix< double, Inputs, Inputs > &R, const Eigen::Matrix< double, States, Inputs > &N, bool checkPreconditions=true) |
| | Computes the unique stabilizing solution X to the discrete-time algebraic Riccati equation:
|
| |
template<typename Derived >
requires std::derived_from<Derived, Eigen::MatrixBase<Derived>> |
| | ct_matrix (const Derived &) -> ct_matrix< typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime > |
| |
| template<int States> |
| Vectord< States > | AngleResidual (const Vectord< States > &a, const Vectord< States > &b, int angleStateIdx) |
| | Subtracts a and b while normalizing the resulting value in the selected row as if it were an angle.
|
| |
| template<int States> |
| std::function< Vectord< States >(const Vectord< States > &, const Vectord< States > &)> | AngleResidual (int angleStateIdx) |
| | Returns a function that subtracts two vectors while normalizing the resulting value in the selected row as if it were an angle.
|
| |
| template<int States> |
| Vectord< States > | AngleAdd (const Vectord< States > &a, const Vectord< States > &b, int angleStateIdx) |
| | Adds a and b while normalizing the resulting value in the selected row as an angle.
|
| |
| template<int States> |
| std::function< Vectord< States >(const Vectord< States > &, const Vectord< States > &)> | AngleAdd (int angleStateIdx) |
| | Returns a function that adds two vectors while normalizing the resulting value in the selected row as an angle.
|
| |
| template<int CovDim, int States> |
| Vectord< CovDim > | AngleMean (const Matrixd< CovDim, 2 *States+1 > &sigmas, const Vectord< 2 *States+1 > &Wm, int angleStatesIdx) |
| | Computes the mean of sigmas with the weights Wm while computing a special angle mean for a select row.
|
| |
| template<int CovDim, int States> |
| std::function< Vectord< CovDim >(const Matrixd< CovDim, 2 *States+1 > &, const Vectord< 2 *States+1 > &)> | AngleMean (int angleStateIdx) |
| | Returns a function that computes the mean of sigmas with the weights Wm while computing a special angle mean for a select row.
|
| |
| template<int States> |
| void | DiscretizeA (const Matrixd< States, States > &contA, units::second_t dt, Matrixd< States, States > *discA) |
| | Discretizes the given continuous A matrix.
|
| |
| template<int States, int Inputs> |
| void | DiscretizeAB (const Matrixd< States, States > &contA, const Matrixd< States, Inputs > &contB, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, Inputs > *discB) |
| | Discretizes the given continuous A and B matrices.
|
| |
| template<int States> |
| void | DiscretizeAQ (const Matrixd< States, States > &contA, const Matrixd< States, States > &contQ, units::second_t dt, Matrixd< States, States > *discA, Matrixd< States, States > *discQ) |
| | Discretizes the given continuous A and Q matrices.
|
| |
| template<int Outputs> |
| Matrixd< Outputs, Outputs > | DiscretizeR (const Matrixd< Outputs, Outputs > &R, units::second_t dt) |
| | Returns a discretized version of the provided continuous measurement noise covariance matrix.
|
| |
| template<std::same_as< double >... Ts> |
| constexpr Matrixd< sizeof...(Ts), sizeof...(Ts)> | MakeCostMatrix (Ts... tolerances) |
| | Creates a cost matrix from the given vector for use with LQR.
|
| |
| template<std::same_as< double >... Ts> |
| constexpr Matrixd< sizeof...(Ts), sizeof...(Ts)> | MakeCovMatrix (Ts... stdDevs) |
| | Creates a covariance matrix from the given vector for use with Kalman filters.
|
| |
| template<size_t N> |
| constexpr Matrixd< N, N > | MakeCostMatrix (const std::array< double, N > &costs) |
| | Creates a cost matrix from the given vector for use with LQR.
|
| |
| template<size_t N> |
| constexpr Matrixd< N, N > | MakeCovMatrix (const std::array< double, N > &stdDevs) |
| | Creates a covariance matrix from the given vector for use with Kalman filters.
|
| |
| template<std::same_as< double >... Ts> |
| Vectord< sizeof...(Ts)> | MakeWhiteNoiseVector (Ts... stdDevs) |
| |
| template<int N> |
| Vectord< N > | MakeWhiteNoiseVector (const std::array< double, N > &stdDevs) |
| | Creates a vector of normally distributed white noise with the given noise intensities for each element.
|
| |
| WPILIB_DLLEXPORT constexpr Eigen::Vector3d | PoseTo3dVector (const Pose2d &pose) |
| | Converts a Pose2d into a vector of [x, y, theta].
|
| |
| WPILIB_DLLEXPORT constexpr Eigen::Vector4d | PoseTo4dVector (const Pose2d &pose) |
| | Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].
|
| |
| template<int States, int Inputs> |
| bool | IsStabilizable (const Matrixd< States, States > &A, const Matrixd< States, Inputs > &B) |
| | Returns true if (A, B) is a stabilizable pair.
|
| |
| template WPILIB_DLLEXPORT bool | IsStabilizable< 1, 1 > (const Matrixd< 1, 1 > &A, const Matrixd< 1, 1 > &B) |
| |
| template WPILIB_DLLEXPORT bool | IsStabilizable< 2, 1 > (const Matrixd< 2, 2 > &A, const Matrixd< 2, 1 > &B) |
| |
| template WPILIB_DLLEXPORT bool | IsStabilizable< Eigen::Dynamic, Eigen::Dynamic > (const Eigen::MatrixXd &A, const Eigen::MatrixXd &B) |
| |
| template<int States, int Outputs> |
| bool | IsDetectable (const Matrixd< States, States > &A, const Matrixd< Outputs, States > &C) |
| | Returns true if (A, C) is a detectable pair.
|
| |
| WPILIB_DLLEXPORT constexpr Eigen::Vector3d | PoseToVector (const Pose2d &pose) |
| | Converts a Pose2d into a vector of [x, y, theta].
|
| |
| template<int Inputs> |
| constexpr Vectord< Inputs > | ClampInputMaxMagnitude (const Vectord< Inputs > &u, const Vectord< Inputs > &umin, const Vectord< Inputs > &umax) |
| | Clamps input vector between system's minimum and maximum allowable input.
|
| |
| template<int Inputs> |
| Vectord< Inputs > | DesaturateInputVector (const Vectord< Inputs > &u, double maxMagnitude) |
| | Renormalize all inputs if any exceeds the maximum magnitude.
|
| |
| std::string | format_as (Alert::AlertType type) |
| |
| template<int Rows, int Cols, typename F > |
| auto | NumericalJacobian (F &&f, const Vectord< Cols > &x) |
| | Returns numerical Jacobian with respect to x for f(x).
|
| |
| template<int Rows, int States, int Inputs, typename F , typename... Args> |
| auto | NumericalJacobianX (F &&f, const Vectord< States > &x, const Vectord< Inputs > &u, Args &&... args) |
| | Returns numerical Jacobian with respect to x for f(x, u, ...).
|
| |
| template<int Rows, int States, int Inputs, typename F , typename... Args> |
| auto | NumericalJacobianU (F &&f, const Vectord< States > &x, const Vectord< Inputs > &u, Args &&... args) |
| | Returns numerical Jacobian with respect to u for f(x, u, ...).
|
| |
| WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Translation3d &state) |
| |
| WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Translation3d &state) |
| |
| template<typename ModuleTranslation , typename... ModuleTranslations> |
| | SwerveDriveKinematics (ModuleTranslation, ModuleTranslations...) -> SwerveDriveKinematics< 1+sizeof...(ModuleTranslations)> |
| |
template<typename T >
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T> |
| constexpr T | ApplyDeadband (T value, T deadband, T maxMagnitude=T{1.0}) |
| | Returns 0.0 if the given value is within the specified range around zero.
|
| |
| template<typename T > |
| constexpr T | InputModulus (T input, T minimumInput, T maximumInput) |
| | Returns modulus of input.
|
| |
template<typename T >
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T> |
| constexpr bool | IsNear (T expected, T actual, T tolerance) |
| | Checks if the given value matches an expected value within a certain tolerance.
|
| |
template<typename T >
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T> |
| constexpr bool | IsNear (T expected, T actual, T tolerance, T min, T max) |
| | Checks if the given value matches an expected value within a certain tolerance.
|
| |
| WPILIB_DLLEXPORT constexpr units::radian_t | AngleModulus (units::radian_t angle) |
| | Wraps an angle to the range -π to π radians (-180 to 180 degrees).
|
| |
| constexpr std::signed_integral auto | FloorDiv (std::signed_integral auto x, std::signed_integral auto y) |
| | Returns the largest (closest to positive infinity) int value that is less than or equal to the algebraic quotient.
|
| |
| constexpr std::signed_integral auto | FloorMod (std::signed_integral auto x, std::signed_integral auto y) |
| | Returns the floor modulus of the int arguments.
|
| |
| constexpr Translation2d | SlewRateLimit (const Translation2d ¤t, const Translation2d &next, units::second_t dt, units::meters_per_second_t maxVelocity) |
| | Limits translation velocity.
|
| |
| constexpr Translation3d | SlewRateLimit (const Translation3d ¤t, const Translation3d &next, units::second_t dt, units::meters_per_second_t maxVelocity) |
| | Limits translation velocity.
|
| |
| void | Wait (units::second_t seconds) |
| | Pause the task for a specified time.
|
| |
| units::second_t | GetTime () |
| | Gives real-time clock system time with nanosecond resolution.
|
| |
| int | GetThreadPriority (std::thread &thread, bool *isRealTime) |
| | Get the thread priority for the specified thread.
|
| |
| int | GetCurrentThreadPriority (bool *isRealTime) |
| | Get the thread priority for the current thread.
|
| |
| bool | SetThreadPriority (std::thread &thread, bool realTime, int priority) |
| | Sets the thread priority for the specified thread.
|
| |
| bool | SetCurrentThreadPriority (bool realTime, int priority) |
| | Sets the thread priority for the current thread.
|
| |
| template<typename F , typename T > |
| T | RK4 (F &&f, T x, units::second_t dt) |
| | Performs 4th order Runge-Kutta integration of dx/dt = f(x) for dt.
|
| |
| template<typename F , typename T , typename U > |
| T | RK4 (F &&f, T x, U u, units::second_t dt) |
| | Performs 4th order Runge-Kutta integration of dx/dt = f(x, u) for dt.
|
| |
| template<typename F , typename T > |
| T | RK4 (F &&f, units::second_t t, T y, units::second_t dt) |
| | Performs 4th order Runge-Kutta integration of dy/dt = f(t, y) for dt.
|
| |
| template<typename F , typename T , typename U > |
| T | RKDP (F &&f, T x, U u, units::second_t dt, double maxError=1e-6) |
| | Performs adaptive Dormand-Prince integration of dx/dt = f(x, u) for dt.
|
| |
| template<typename F , typename T > |
| T | RKDP (F &&f, units::second_t t, T y, units::second_t dt, double maxError=1e-6) |
| | Performs adaptive Dormand-Prince integration of dy/dt = f(t, y) for dt.
|
| |