|
class | Accelerometer |
| Interface for 3-axis accelerometers. More...
|
|
class | AddressableLED |
| A class for driving addressable LEDs, such as WS2812s 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 | 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...
|
|
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 | BuiltInAccelerometer |
| Built-in accelerometer. 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 | 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 | 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 pneumatics module. More...
|
|
class | ConditionalCommand |
| A ConditionalCommand is a Command that starts one of two commands. More...
|
|
class | ControlAffinePlantInversionFeedforward |
| Constructs a control-affine plant inversion model-based feedforward from given model dynamics. More...
|
|
class | Controller |
| Interface for Controllers. 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 | 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 | 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 | DifferentialDrivePoseEstimator |
| This class wraps an Unscented Kalman Filter 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 | DifferentialDriveWheelSpeeds |
| Represents the wheel speeds for a differential drive drivetrain. 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 | DMASample |
|
class | DMC60 |
| Digilent DMC 60 Motor Controller. 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 | EllipticalRegionConstraint |
| Enforces a particular constraint only within an elliptical region. More...
|
|
class | Encoder |
| Class to read quad encoders. 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 | Gyro |
| Interface for yaw rate gyros. More...
|
|
class | HeldButtonScheduler |
|
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 | InstantCommand |
| This command will execute once, then finish immediately afterward. More...
|
|
class | InternalButton |
| This Button is intended to be used within a program. 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 | JoystickButton |
| A Button} that gets its state from a GenericHID. More...
|
|
class | KalmanFilter |
|
class | KalmanFilter< 1, 1, 1 > |
|
class | KalmanFilter< 2, 1, 1 > |
|
class | KalmanFilterLatencyCompensator |
|
class | KilloughDrive |
| A class for driving Killough drive platforms. More...
|
|
class | LayoutType |
| Represents the type of a layout in Shuffleboard. More...
|
|
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 |
|
class | LinearQuadraticRegulator< 1, 1 > |
|
class | LinearQuadraticRegulator< 2, 1 > |
|
class | LinearQuadraticRegulator< 2, 2 > |
|
class | LinearSystem |
| A plant defined using state-space notation. More...
|
|
class | LinearSystemId |
|
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 | 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 | MecanumDrivePoseEstimator |
| This class wraps an Unscented Kalman Filter to fuse latency-compensated vision measurements with mecanum drive encoder velocity measurements. 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 |
| This base class runs a watchdog timer and calls the subclass's StopMotor() function if the timeout expires. More...
|
|
class | NetworkButton |
| A that uses a NetworkTable boolean field. More...
|
|
class | NidecBrushless |
| Nidec Brushless Motor. More...
|
|
class | Notifier |
|
class | PIDAnalogAccelerometer |
| Wrapper so that PIDSource is implemented for AnalogAccelerometer for old PIDController. More...
|
|
class | PIDAnalogGyro |
| Wrapper so that PIDSource is implemented for AnalogGyro for old PIDController. More...
|
|
class | PIDAnalogInput |
| Wrapper so that PIDSource is implemented for AnalogInput for old PIDController. More...
|
|
class | PIDAnalogPotentiometer |
| Wrapper so that PIDSource is implemented for AnalogPotentiometer for old PIDController. More...
|
|
class | PIDBase |
| Class implements a PID Control Loop. More...
|
|
class | PIDCommand |
| This class defines aCommand which interacts heavily with a PID loop. More...
|
|
class | PIDController |
| Class implements a PID Control Loop. More...
|
|
class | PIDEncoder |
| Wrapper so that PIDSource is implemented for Encoder for old PIDController. More...
|
|
class | PIDInterface |
| Interface for PID Control Loop. More...
|
|
class | PIDMotorController |
| Wrapper so that PIDOutput is implemented for MotorController for old PIDController. More...
|
|
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 | PIDUltrasonic |
| Wrapper so that PIDSource is implemented for Ultrasonic for old PIDController. More...
|
|
class | PneumaticHub |
|
class | PneumaticsBase |
|
class | PneumaticsControlModule |
|
class | Pose2d |
| Represents a 2d pose containing translational and rotational elements. More...
|
|
class | POVButton |
| A Button that gets its state from a POV on a GenericHID. 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 | PressedButtonScheduler |
|
class | PrintCommand |
| A PrintCommand is a command which prints out a string when it is initialized, and then immediately finishes. 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 | PWM |
| Class implements the PWM generation in the FPGA. More...
|
|
class | PWMMotorController |
| Common base class for all PWM Motor Controllers. More...
|
|
class | PWMSparkMax |
| REV Robotics SPARK MAX Motor Controller. 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 Smart Motor with PWM control. More...
|
|
class | PWMVictorSPX |
| Cross the Road Electronics (CTRE) Victor SPX Motor Controller with PWM control. 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 | RectangularRegionConstraint |
| Enforces a particular constraint only within a rectangular region. 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 | RobotDriveBase |
| Common base class for drive platforms. More...
|
|
class | RobotState |
|
class | Rotation2d |
| A rotation in a 2d coordinate frame represented a point on the unit circle (cosine and sine). More...
|
|
class | RuntimeError |
| Runtime error exception. More...
|
|
class | Scheduler |
| The Scheduler is a singleton which holds the top-level running commands. 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. More...
|
|
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 | 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 | 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. More...
|
|
class | SpeedController |
| Interface for speed controlling devices. More...
|
|
class | SpeedControllerGroup |
| Allows multiple SpeedController objects to be linked together. 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 | StartCommand |
| A PrintCommand is a command which prints out a string when it is initialized, and then immediately finishes. More...
|
|
class | Subsystem |
| This class defines a major component of the robot. 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 | SwerveDrivePoseEstimator |
| This class wraps an Unscented Kalman Filter to fuse latency-compensated vision measurements with swerve drive encoder velocity measurements. 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 and Talon SR Motor 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 | 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 | ToggleButtonScheduler |
|
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 |
|
class | Transform2d |
| Represents a transformation for a Pose2d. More...
|
|
class | Translation2d |
| Represents a translation in 2d space. More...
|
|
class | TrapezoidProfile |
| A trapezoid-shaped velocity profile. More...
|
|
class | Trigger |
| This class provides an easy way to link commands to inputs. More...
|
|
struct | Twist2d |
| A change in distance along 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...
|
|
struct | Vector2d |
| This is a 2D vector struct that supports basic vector operations. More...
|
|
class | Victor |
| Vex Robotics Victor 888 Motor Controller. More...
|
|
class | VictorSP |
| Vex Robotics Victor SP Motor 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 |
| A WaitCommand will wait for a certain amount of time before finishing. More...
|
|
class | WaitForChildren |
| This command will only finish if whatever CommandGroup it is in has no active children. More...
|
|
class | WaitUntilCommand |
| A WaitCommand will wait until a certain match time before finishing. 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 360 or Xbox One controllers connected to the Driver Station. More...
|
|
|
CameraServerShared * | GetCameraServerShared () |
|
WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Translation2d &state) |
|
WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Translation2d &state) |
|
WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Rotation2d &rotation) |
|
WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Rotation2d &rotation) |
|
WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Pose2d &pose) |
|
WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Pose2d &pose) |
|
WPILIB_DLLEXPORT double | ApplyDeadband (double value, double deadband) |
| Returns 0.0 if the given value is within the specified range around zero. More...
|
|
template<typename T > |
constexpr T | InputModulus (T input, T minimumInput, T maximumInput) |
| Returns modulus of input. More...
|
|
constexpr WPILIB_DLLEXPORT units::radian_t | AngleModulus (units::radian_t angle) |
| Wraps an angle to the range -pi to pi radians (-180 to 180 degrees). More...
|
|
template<int CovDim, int States> |
std::tuple< Eigen::Vector< double, CovDim >, Eigen::Matrix< double, CovDim, CovDim > > | UnscentedTransform (const Eigen::Matrix< double, CovDim, 2 *States+1 > &sigmas, const Eigen::Vector< double, 2 *States+1 > &Wm, const Eigen::Vector< double, 2 *States+1 > &Wc, std::function< Eigen::Vector< double, CovDim >(const Eigen::Matrix< double, CovDim, 2 *States+1 > &, const Eigen::Vector< double, 2 *States+1 > &)> meanFunc, std::function< Eigen::Vector< double, CovDim >(const Eigen::Vector< double, CovDim > &, const Eigen::Vector< double, CovDim > &)> residualFunc) |
| Computes unscented transform of a set of sigma points and weights. More...
|
|
template<int States> |
Eigen::Vector< double, States > | AngleResidual (const Eigen::Vector< double, States > &a, const Eigen::Vector< double, States > &b, int angleStateIdx) |
| Subtracts a and b while normalizing the resulting value in the selected row as if it were an angle. More...
|
|
template<int States> |
std::function< Eigen::Vector< double, States >(const Eigen::Vector< double, States > &, const Eigen::Vector< double, 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. More...
|
|
template<int States> |
Eigen::Vector< double, States > | AngleAdd (const Eigen::Vector< double, States > &a, const Eigen::Vector< double, States > &b, int angleStateIdx) |
| Adds a and b while normalizing the resulting value in the selected row as an angle. More...
|
|
template<int States> |
std::function< Eigen::Vector< double, States >(const Eigen::Vector< double, States > &, const Eigen::Vector< double, States > &)> | AngleAdd (int angleStateIdx) |
| Returns a function that adds two vectors while normalizing the resulting value in the selected row as an angle. More...
|
|
template<int CovDim, int States> |
Eigen::Vector< double, CovDim > | AngleMean (const Eigen::Matrix< double, CovDim, 2 *States+1 > &sigmas, const Eigen::Vector< double, 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. More...
|
|
template<int CovDim, int States> |
std::function< Eigen::Vector< double, CovDim >(const Eigen::Matrix< double, CovDim, 2 *States+1 > &, const Eigen::Vector< double, 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. More...
|
|
WPILIB_DLLEXPORT void | to_json (wpi::json &json, const Trajectory::State &state) |
|
WPILIB_DLLEXPORT void | from_json (const wpi::json &json, Trajectory::State &state) |
|
template<class... Wheels> |
| SwerveDriveKinematics (Translation2d, Wheels...) -> SwerveDriveKinematics< 1+sizeof...(Wheels)> |
|
template<int Rows, int Cols, typename... Ts, typename = std::enable_if_t<std::conjunction_v<std::is_same<double, Ts>...>>> |
Eigen::Matrix< double, Rows, Cols > | MakeMatrix (Ts... elems) |
| Creates a matrix from the given list of elements. More...
|
|
template<typename... Ts, typename = std::enable_if_t< std::conjunction_v<std::is_same<double, Ts>...>>> |
Eigen::Matrix< double, sizeof...(Ts), sizeof...(Ts)> | MakeCostMatrix (Ts... costs) |
| Creates a cost matrix from the given vector for use with LQR. More...
|
|
template<typename... Ts, typename = std::enable_if_t< std::conjunction_v<std::is_same<double, Ts>...>>> |
Eigen::Matrix< double, sizeof...(Ts), sizeof...(Ts)> | MakeCovMatrix (Ts... stdDevs) |
| Creates a covariance matrix from the given vector for use with Kalman filters. More...
|
|
template<size_t N> |
Eigen::Matrix< double, N, N > | MakeCostMatrix (const std::array< double, N > &costs) |
| Creates a cost matrix from the given vector for use with LQR. More...
|
|
template<size_t N> |
Eigen::Matrix< double, N, N > | MakeCovMatrix (const std::array< double, N > &stdDevs) |
| Creates a covariance matrix from the given vector for use with Kalman filters. More...
|
|
template<typename... Ts, typename = std::enable_if_t< std::conjunction_v<std::is_same<double, Ts>...>>> |
Eigen::Matrix< double, sizeof...(Ts), 1 > | MakeWhiteNoiseVector (Ts... stdDevs) |
|
template<int N> |
Eigen::Vector< double, N > | MakeWhiteNoiseVector (const std::array< double, N > &stdDevs) |
| Creates a vector of normally distributed white noise with the given noise intensities for each element. More...
|
|
WPILIB_DLLEXPORT Eigen::Vector< double, 3 > | PoseTo3dVector (const Pose2d &pose) |
| Converts a Pose2d into a vector of [x, y, theta]. More...
|
|
WPILIB_DLLEXPORT Eigen::Vector< double, 4 > | PoseTo4dVector (const Pose2d &pose) |
| Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)]. More...
|
|
template<int States, int Inputs> |
bool | IsStabilizable (const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, States, Inputs > &B) |
| Returns true if (A, B) is a stabilizable pair. More...
|
|
template<int States, int Outputs> |
bool | IsDetectable (const Eigen::Matrix< double, States, States > &A, const Eigen::Matrix< double, Outputs, States > &C) |
| Returns true if (A, C) is a detectable pair. More...
|
|
template<> |
WPILIB_DLLEXPORT bool | IsStabilizable< 1, 1 > (const Eigen::Matrix< double, 1, 1 > &A, const Eigen::Matrix< double, 1, 1 > &B) |
|
template<> |
WPILIB_DLLEXPORT bool | IsStabilizable< 2, 1 > (const Eigen::Matrix< double, 2, 2 > &A, const Eigen::Matrix< double, 2, 1 > &B) |
|
WPILIB_DLLEXPORT Eigen::Vector< double, 3 > | PoseToVector (const Pose2d &pose) |
| Converts a Pose2d into a vector of [x, y, theta]. More...
|
|
template<int Inputs> |
Eigen::Vector< double, Inputs > | ClampInputMaxMagnitude (const Eigen::Vector< double, Inputs > &u, const Eigen::Vector< double, Inputs > &umin, const Eigen::Vector< double, Inputs > &umax) |
| Clamps input vector between system's minimum and maximum allowable input. More...
|
|
template<int Inputs> |
Eigen::Vector< double, Inputs > | DesaturateInputVector (const Eigen::Vector< double, Inputs > &u, double maxMagnitude) |
| Renormalize all inputs if any exceeds the maximum magnitude. More...
|
|
template<int Rows, int Cols, typename F > |
auto | NumericalJacobian (F &&f, const Eigen::Vector< double, Cols > &x) |
| Returns numerical Jacobian with respect to x for f(x). More...
|
|
template<int Rows, int States, int Inputs, typename F , typename... Args> |
auto | NumericalJacobianX (F &&f, const Eigen::Vector< double, States > &x, const Eigen::Vector< double, Inputs > &u, Args &&... args) |
| Returns numerical Jacobian with respect to x for f(x, u, ...). More...
|
|
template<int Rows, int States, int Inputs, typename F , typename... Args> |
auto | NumericalJacobianU (F &&f, const Eigen::Vector< double, States > &x, const Eigen::Vector< double, Inputs > &u, Args &&... args) |
| Returns numerical Jacobian with respect to u for f(x, u, ...). More...
|
|
template<int States> |
void | DiscretizeA (const Eigen::Matrix< double, States, States > &contA, units::second_t dt, Eigen::Matrix< double, States, States > *discA) |
| Discretizes the given continuous A matrix. More...
|
|
template<int States, int Inputs> |
void | DiscretizeAB (const Eigen::Matrix< double, States, States > &contA, const Eigen::Matrix< double, States, Inputs > &contB, units::second_t dt, Eigen::Matrix< double, States, States > *discA, Eigen::Matrix< double, States, Inputs > *discB) |
| Discretizes the given continuous A and B matrices. More...
|
|
template<int States> |
void | DiscretizeAQ (const Eigen::Matrix< double, States, States > &contA, const Eigen::Matrix< double, States, States > &contQ, units::second_t dt, Eigen::Matrix< double, States, States > *discA, Eigen::Matrix< double, States, States > *discQ) |
| Discretizes the given continuous A and Q matrices. More...
|
|
template<int States> |
void | DiscretizeAQTaylor (const Eigen::Matrix< double, States, States > &contA, const Eigen::Matrix< double, States, States > &contQ, units::second_t dt, Eigen::Matrix< double, States, States > *discA, Eigen::Matrix< double, States, States > *discQ) |
| Discretizes the given continuous A and Q matrices. More...
|
|
template<int Outputs> |
Eigen::Matrix< double, Outputs, Outputs > | DiscretizeR (const Eigen::Matrix< double, Outputs, Outputs > &R, units::second_t dt) |
| Returns a discretized version of the provided continuous measurement noise covariance matrix. More...
|
|
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. More...
|
|
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. More...
|
|
template<typename F , typename T , typename U > |
T | RKF45 (F &&f, T x, U u, units::second_t dt, double maxError=1e-6) |
| Performs adaptive RKF45 integration of dx/dt = f(x, u) for dt, as described in https://en.wikipedia.org/wiki/Runge%E2%80%93Kutta%E2%80%93Fehlberg_method. More...
|
|
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. More...
|
|
bool | operator== (const Color &c1, const Color &c2) |
|
bool | operator!= (const Color &c1, const Color &c2) |
|
bool | operator== (const Color8Bit &c1, const Color8Bit &c2) |
|
int | RunHALInitialization () |
|
template<class Robot > |
int | StartRobot () |
|
std::string_view | ShuffleboardEventImportanceName (ShuffleboardEventImportance importance) |
|
const char * | GetErrorMessage (int32_t *code) |
| Gets error message string for an error code. More...
|
|
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). More...
|
|
template<typename S , typename... Args> |
void | ReportError (int32_t status, const char *fileName, int lineNumber, const char *funcName, const S &format, Args &&... args) |
| Reports an error to the driver station (using HAL_SendError). More...
|
|
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. More...
|
|
template<typename S , typename... Args> |
RuntimeError | MakeError (int32_t status, const char *fileName, int lineNumber, const char *funcName, const S &format, Args &&... args) |
|
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...
|
|
void | Wait (units::second_t seconds) |
| Pause the task for a specified time. More...
|
|
units::second_t | GetTime () |
| Gives real-time clock system time with nanosecond resolution. More...
|
|