WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
frc Namespace Reference

Namespaces

namespace  detail
 
namespace  err
 
namespace  filesystem
 WPILib FileSystem namespace.
 
namespace  impl
 
namespace  internal
 
namespace  sim
 
namespace  sysid
 
namespace  warn
 

Classes

class  AddressableLED
 A class for driving addressable LEDs, such as WS2812B, WS2815, and NeoPixels. More...
 
class  ADXL345_I2C
 ADXL345 Accelerometer on I2C. 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  AnalogPotentiometer
 Class for reading analog potentiometers. 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  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  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  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  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  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  DigitalInput
 Class to read a digital input. More...
 
class  DigitalOutput
 Class to write to digital outputs. 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  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  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  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  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  OnboardIMU
 SystemCore onboard IMU. 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  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  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  S3SigmaPoints
 Generates sigma points and weights according to Papakonstantinou's paper[1] for the UnscentedKalmanFilter class. 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  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  SimpleMotorFeedforward
 A helper class that computes feedforward voltages for a simple permanent-magnet DC motor. 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  SparkMini
 REV Robotics SPARKMini Motor Controller with PWM control. 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  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  SystemServer
 
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  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  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  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...
 

Concepts

concept  EigenMatrixLike
 
concept  SigmaPoints
 

Typedefs

template<int Size>
using Vectord = Eigen::Vector<double, Size>
 
template<int Rows, int Cols, int Options = Eigen::AutoAlign | ((Rows == 1 && Cols != 1) ? Eigen::RowMajor : (Cols == 1 && Rows != 1) ? Eigen::ColMajor : EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION), int MaxRows = Rows, int MaxCols = Cols>
using Matrixd = Eigen::Matrix<double, Rows, Cols, Options, MaxRows, MaxCols>
 
template<int States, int Inputs, int Outputs>
using MerweUKF
 
template<typename Scalar , int Rows>
using ct_vector = ct_matrix<Scalar, Rows, 1>
 
template<typename Scalar , int Cols>
using ct_row_vector = ct_matrix<Scalar, 1, Cols>
 
using ct_matrix2d = ct_matrix<double, 2, 2>
 
using ct_matrix3d = ct_matrix<double, 3, 3>
 
using ct_vector2d = ct_vector<double, 2>
 
using ct_vector3d = ct_vector<double, 3>
 
template<int States, int Inputs, int Outputs>
using S3UKF
 

Enumerations

enum class  AprilTagField {
  k2022RapidReact , k2023ChargedUp , k2024Crescendo , k2025ReefscapeAndyMark ,
  k2025ReefscapeWelded , kDefaultField = k2025ReefscapeWelded , kNumFields
}
 Loadable AprilTag field layouts. More...
 
enum class  EdgeConfiguration { kRisingEdge = 0 , kFallingEdge = 1 }
 Edge configuration. More...
 
enum class  CompressorConfigType { Disabled = 0 , Digital = 1 , Analog = 2 , Hybrid = 3 }
 Compressor config type. More...
 
enum  RuntimeType { kRoboRIO , kRoboRIO2 , kSimulation , kSystemCore }
 Runtime type. More...
 
enum class  DAREError {
  QNotSymmetric , QNotPositiveSemidefinite , RNotSymmetric , RNotPositiveDefinite ,
  ABNotStabilizable , ACNotDetectable
}
 Errors the DARE solver can encounter. More...
 
enum class  PneumaticsModuleType { CTREPCM , REVPH }
 Pneumatics module type. More...
 

Functions

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)
 
CameraServerSharedGetCameraServerShared ()
 
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 NumSigmas>
std::tuple< Vectord< CovDim >, Matrixd< CovDim, CovDim > > SquareRootUnscentedTransform (const Matrixd< CovDim, NumSigmas > &sigmas, const Vectord< NumSigmas > &Wm, const Vectord< NumSigmas > &Wc, std::function< Vectord< CovDim >(const Matrixd< CovDim, NumSigmas > &, const Vectord< NumSigmas > &)> 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)
 
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 >, DAREErrorDARE (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 >, DAREErrorDARE (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 NumSigmas>
Vectord< CovDim > AngleMean (const Matrixd< CovDim, NumSigmas > &sigmas, const Vectord< NumSigmas > &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 NumSigmas>
std::function< Vectord< CovDim >(const Matrixd< CovDim, NumSigmas > &, const Vectord< NumSigmas > &)> 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.
 
WPILIB_DLLEXPORT Eigen::MatrixXd MakeCostMatrix (const std::span< const double > 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.
 
WPILIB_DLLEXPORT Eigen::MatrixXd MakeCovMatrix (const std::span< const double > 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 Eigen::VectorXd MakeWhiteNoiseVector (const std::span< const double > 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.
 
template WPILIB_DLLEXPORT bool IsDetectable< Eigen::Dynamic, Eigen::Dynamic > (const Eigen::MatrixXd &A, const Eigen::MatrixXd &C)
 
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 WPILIB_DLLEXPORT Eigen::VectorXd ClampInputMaxMagnitude< Eigen::Dynamic > (const Eigen::VectorXd &u, const Eigen::VectorXd &umin, const Eigen::VectorXd &umax)
 
template<int Inputs>
Vectord< Inputs > DesaturateInputVector (const Vectord< Inputs > &u, double maxMagnitude)
 Renormalize all inputs if any exceeds the maximum magnitude.
 
template WPILIB_DLLEXPORT Eigen::VectorXd DesaturateInputVector< Eigen::Dynamic > (const Eigen::VectorXd &u, double maxMagnitude)
 
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<typename F >
Eigen::MatrixXd NumericalJacobian (F &&f, const Eigen::VectorXd &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<typename F , typename... Args>
auto NumericalJacobianX (F &&f, const Eigen::VectorXd &x, const Eigen::VectorXd &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, ...).
 
template<typename F , typename... Args>
auto NumericalJacobianU (F &&f, const Eigen::VectorXd &x, const Eigen::VectorXd &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 >
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T>
constexpr T CopySignPow (T value, double exponent, T maxMagnitude=T{1.0})
 Raises the input to the power of the given exponent while preserving its sign.
 
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 &current, const Translation2d &next, units::second_t dt, units::meters_per_second_t maxVelocity)
 Limits translation velocity.
 
constexpr Translation3d SlewRateLimit (const Translation3d &current, 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 >
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 >
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 >
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 >
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 >
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.
 

Typedef Documentation

◆ ct_matrix2d

using frc::ct_matrix2d = ct_matrix<double, 2, 2>

◆ ct_matrix3d

using frc::ct_matrix3d = ct_matrix<double, 3, 3>

◆ ct_row_vector

template<typename Scalar , int Cols>
using frc::ct_row_vector = ct_matrix<Scalar, 1, Cols>

◆ ct_vector

template<typename Scalar , int Rows>
using frc::ct_vector = ct_matrix<Scalar, Rows, 1>

◆ ct_vector2d

using frc::ct_vector2d = ct_vector<double, 2>

◆ ct_vector3d

using frc::ct_vector3d = ct_vector<double, 3>

◆ Matrixd

template<int Rows, int Cols, int Options = Eigen::AutoAlign | ((Rows == 1 && Cols != 1) ? Eigen::RowMajor : (Cols == 1 && Rows != 1) ? Eigen::ColMajor : EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION), int MaxRows = Rows, int MaxCols = Cols>
using frc::Matrixd = Eigen::Matrix<double, Rows, Cols, Options, MaxRows, MaxCols>

◆ MerweUKF

template<int States, int Inputs, int Outputs>
using frc::MerweUKF
Initial value:
UnscentedKalmanFilter<States, Inputs, Outputs,
MerweScaledSigmaPoints<States>>

◆ S3UKF

template<int States, int Inputs, int Outputs>
using frc::S3UKF
Initial value:
UnscentedKalmanFilter<States, Inputs, Outputs, S3SigmaPoints<States>>

◆ Vectord

template<int Size>
using frc::Vectord = Eigen::Vector<double, Size>

Enumeration Type Documentation

◆ AprilTagField

enum class frc::AprilTagField
strong

Loadable AprilTag field layouts.

Enumerator
k2022RapidReact 

2022 Rapid React.

k2023ChargedUp 

2023 Charged Up.

k2024Crescendo 

2024 Crescendo.

k2025ReefscapeAndyMark 

2025 Reefscape AndyMark (see TU12).

k2025ReefscapeWelded 

2025 Reefscape Welded (see TU12).

kDefaultField 

Alias to the current game.

kNumFields 

◆ CompressorConfigType

enum class frc::CompressorConfigType
strong

Compressor config type.

Enumerator
Disabled 

Disabled.

Digital 

Digital.

Analog 

Analog.

Hybrid 

Hybrid.

◆ DAREError

enum class frc::DAREError
strong

Errors the DARE solver can encounter.

Enumerator
QNotSymmetric 

Q was not symmetric.

QNotPositiveSemidefinite 

Q was not positive semidefinite.

RNotSymmetric 

R was not symmetric.

RNotPositiveDefinite 

R was not positive definite.

ABNotStabilizable 

(A, B) pair was not stabilizable.

ACNotDetectable 

(A, C) pair where Q = CᵀC was not detectable.

◆ EdgeConfiguration

enum class frc::EdgeConfiguration
strong

Edge configuration.

Enumerator
kRisingEdge 

Rising edge configuration.

kFallingEdge 

Falling edge configuration.

◆ PneumaticsModuleType

enum class frc::PneumaticsModuleType
strong

Pneumatics module type.

Enumerator
CTREPCM 

CTRE PCM.

REVPH 

REV PH.

◆ RuntimeType

Runtime type.

Enumerator
kRoboRIO 

roboRIO 1.0.

kRoboRIO2 

roboRIO 2.0.

kSimulation 

Simulation runtime.

kSystemCore 

Function Documentation

◆ AngleAdd() [1/2]

template<int States>
Vectord< States > frc::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 Parameters
StatesNumber of states.
Parameters
aA vector to add with.
bA vector to add with.
angleStateIdxThe row containing angles to be normalized.

◆ AngleAdd() [2/2]

template<int States>
std::function< Vectord< States >(const Vectord< States > &, const Vectord< States > &)> frc::AngleAdd ( int angleStateIdx)

Returns a function that adds two vectors while normalizing the resulting value in the selected row as an angle.

Template Parameters
StatesNumber of states.
Parameters
angleStateIdxThe row containing angles to be normalized.

◆ AngleMean() [1/2]

template<int CovDim, int NumSigmas>
Vectord< CovDim > frc::AngleMean ( const Matrixd< CovDim, NumSigmas > & sigmas,
const Vectord< NumSigmas > & Wm,
int angleStatesIdx )

Computes the mean of sigmas with the weights Wm while computing a special angle mean for a select row.

Template Parameters
CovDimDimension of covariance of sigma points after passing through the transform.
NumSigmasNumber of sigma points.
Parameters
sigmasSigma points.
WmWeights for the mean.
angleStatesIdxThe row containing the angles.

◆ AngleMean() [2/2]

template<int CovDim, int NumSigmas>
std::function< Vectord< CovDim >(const Matrixd< CovDim, NumSigmas > &, const Vectord< NumSigmas > &)> frc::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 Parameters
CovDimDimension of covariance of sigma points after passing through the transform.
NumSigmasNumber of sigma points.
Parameters
angleStateIdxThe row containing the angles.

◆ AngleModulus()

WPILIB_DLLEXPORT constexpr units::radian_t frc::AngleModulus ( units::radian_t angle)
constexpr

Wraps an angle to the range -π to π radians (-180 to 180 degrees).

Parameters
angleAngle to wrap.

◆ AngleResidual() [1/2]

template<int States>
Vectord< States > frc::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 Parameters
StatesNumber of states.
Parameters
aA vector to subtract from.
bA vector to subtract with.
angleStateIdxThe row containing angles to be normalized.

◆ AngleResidual() [2/2]

template<int States>
std::function< Vectord< States >(const Vectord< States > &, const Vectord< States > &)> frc::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 Parameters
StatesNumber of states.
Parameters
angleStateIdxThe row containing angles to be normalized.

◆ ApplyDeadband()

template<typename T >
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T>
T frc::ApplyDeadband ( T value,
T deadband,
T maxMagnitude = T{1.0} )
constexpr

Returns 0.0 if the given value is within the specified range around zero.

The remaining range between the deadband and the maximum magnitude is scaled from 0.0 to the maximum magnitude.

Parameters
valueValue to clip.
deadbandRange around zero.
maxMagnitudeThe maximum magnitude of the input (defaults to 1). Can be infinite.
Returns
The value after the deadband is applied.

◆ AprilTagDetect()

AprilTagDetector::Results frc::AprilTagDetect ( AprilTagDetector & detector,
cv::Mat & image )
inline

◆ ClampInputMaxMagnitude()

template<int Inputs>
Vectord< Inputs > frc::ClampInputMaxMagnitude ( const Vectord< Inputs > & u,
const Vectord< Inputs > & umin,
const Vectord< Inputs > & umax )
constexpr

Clamps input vector between system's minimum and maximum allowable input.

Template Parameters
InputsNumber of inputs.
Parameters
uInput vector to clamp.
uminThe minimum input magnitude.
umaxThe maximum input magnitude.
Returns
Clamped input vector.

◆ ClampInputMaxMagnitude< Eigen::Dynamic >()

template WPILIB_DLLEXPORT Eigen::VectorXd frc::ClampInputMaxMagnitude< Eigen::Dynamic > ( const Eigen::VectorXd & u,
const Eigen::VectorXd & umin,
const Eigen::VectorXd & umax )
extern

◆ CopySignPow()

template<typename T >
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T>
T frc::CopySignPow ( T value,
double exponent,
T maxMagnitude = T{1.0} )
constexpr

Raises the input to the power of the given exponent while preserving its sign.

The function normalizes the input value to the range [0, 1] based on the maximum magnitude, raises it to the power of the exponent, then scales the result back to the original range and copying the sign. This keeps the value in the original range and gives consistent curve behavior regardless of the input value's scale.

This is useful for applying smoother or more aggressive control response curves (e.g. joystick input shaping).

Parameters
valueThe input value to transform.
exponentThe exponent to apply (e.g. 1.0 = linear, 2.0 = squared curve). Must be positive.
maxMagnitudeThe maximum expected absolute value of input. Must be positive.
Returns
The transformed value with the same sign and scaled to the input range.

◆ ct_matrix()

template<typename Derived >
requires std::derived_from<Derived, Eigen::MatrixBase<Derived>>
frc::ct_matrix ( const Derived & ) -> ct_matrix< typename Derived::Scalar, Derived::RowsAtCompileTime, Derived::ColsAtCompileTime >

◆ DARE() [1/2]

template<int States, int Inputs>
wpi::expected< Eigen::Matrix< double, States, States >, DAREError > frc::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:

AᵀXA − X − AᵀXB(BᵀXB + R)⁻¹BᵀXA + Q = 0

Template Parameters
StatesNumber of states.
InputsNumber of inputs.
Parameters
AThe system matrix.
BThe input matrix.
QThe state cost matrix.
RThe input cost matrix.
checkPreconditionsWhether to check preconditions (30% less time if user is sure precondtions are already met).
Returns
Solution to the DARE on success, or DAREError on failure.

◆ DARE() [2/2]

template<int States, int Inputs>
wpi::expected< Eigen::Matrix< double, States, States >, DAREError > frc::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:

AᵀXA − X − (AᵀXB + N)(BᵀXB + R)⁻¹(BᵀXA + Nᵀ) + Q = 0

This is equivalent to solving the original DARE:

A₂ᵀXA₂ − X − A₂ᵀXB(BᵀXB + R)⁻¹BᵀXA₂ + Q₂ = 0

where A₂ and Q₂ are a change of variables:

A₂ = A − BR⁻¹Nᵀ and Q₂ = Q − NR⁻¹Nᵀ

This overload of the DARE is useful for finding the control law uₖ that minimizes the following cost function subject to xₖ₊₁ = Axₖ + Buₖ.

    ∞ [xₖ]ᵀ[Q  N][xₖ]
J = Σ [uₖ] [Nᵀ R][uₖ] ΔT
   k=0

This is a more general form of the following. The linear-quadratic regulator is the feedback control law uₖ that minimizes the following cost function subject to xₖ₊₁ = Axₖ + Buₖ:

    ∞
J = Σ (xₖᵀQxₖ + uₖᵀRuₖ) ΔT
   k=0

This can be refactored as:

    ∞ [xₖ]ᵀ[Q 0][xₖ]
J = Σ [uₖ] [0 R][uₖ] ΔT
   k=0
Template Parameters
StatesNumber of states.
InputsNumber of inputs.
Parameters
AThe system matrix.
BThe input matrix.
QThe state cost matrix.
RThe input cost matrix.
NThe state-input cross cost matrix.
checkPreconditionsWhether to check preconditions (30% less time if user is sure precondtions are already met).
Returns
Solution to the DARE on success, or DAREError on failure.

◆ DesaturateInputVector()

template<int Inputs>
Vectord< Inputs > frc::DesaturateInputVector ( const Vectord< Inputs > & u,
double maxMagnitude )

Renormalize all inputs if any exceeds the maximum magnitude.

Useful for systems such as differential drivetrains.

Template Parameters
InputsNumber of inputs.
Parameters
uThe input vector.
maxMagnitudeThe maximum magnitude any input can have.
Returns
The normalizedInput

◆ DesaturateInputVector< Eigen::Dynamic >()

template WPILIB_DLLEXPORT Eigen::VectorXd frc::DesaturateInputVector< Eigen::Dynamic > ( const Eigen::VectorXd & u,
double maxMagnitude )
extern

◆ DiscretizeA()

template<int States>
void frc::DiscretizeA ( const Matrixd< States, States > & contA,
units::second_t dt,
Matrixd< States, States > * discA )

Discretizes the given continuous A matrix.

Template Parameters
StatesNumber of states.
Parameters
contAContinuous system matrix.
dtDiscretization timestep.
discAStorage for discrete system matrix.

◆ DiscretizeAB()

template<int States, int Inputs>
void frc::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 Parameters
StatesNumber of states.
InputsNumber of inputs.
Parameters
contAContinuous system matrix.
contBContinuous input matrix.
dtDiscretization timestep.
discAStorage for discrete system matrix.
discBStorage for discrete input matrix.

◆ DiscretizeAQ()

template<int States>
void frc::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 Parameters
StatesNumber of states.
Parameters
contAContinuous system matrix.
contQContinuous process noise covariance matrix.
dtDiscretization timestep.
discAStorage for discrete system matrix.
discQStorage for discrete process noise covariance matrix.

◆ DiscretizeR()

template<int Outputs>
Matrixd< Outputs, Outputs > frc::DiscretizeR ( const Matrixd< Outputs, Outputs > & R,
units::second_t dt )

Returns a discretized version of the provided continuous measurement noise covariance matrix.

Template Parameters
OutputsNumber of outputs.
Parameters
RContinuous measurement noise covariance matrix.
dtDiscretization timestep.

◆ EXPORT_TEMPLATE_DECLARE()

template class template class template class frc::EXPORT_TEMPLATE_DECLARE ( WPILIB_DLLEXPORT )
extern

◆ FloorDiv()

std::signed_integral auto frc::FloorDiv ( std::signed_integral auto x,
std::signed_integral auto y )
constexpr

Returns the largest (closest to positive infinity) int value that is less than or equal to the algebraic quotient.

Parameters
xthe dividend
ythe divisor
Returns
the largest (closest to positive infinity) int value that is less than or equal to the algebraic quotient.

◆ FloorMod()

std::signed_integral auto frc::FloorMod ( std::signed_integral auto x,
std::signed_integral auto y )
constexpr

Returns the floor modulus of the int arguments.

The floor modulus is r = x - (floorDiv(x, y) * y), has the same sign as the divisor y or is zero, and is in the range of -std::abs(y) < r < +std::abs(y).

Parameters
xthe dividend
ythe divisor
Returns
the floor modulus x - (floorDiv(x, y) * y)

◆ format_as() [1/2]

auto frc::format_as ( AddressableLED::ColorOrder order)
constexpr

◆ format_as() [2/2]

std::string frc::format_as ( Alert::AlertType type)

◆ from_json() [1/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
AprilTag & apriltag )

◆ from_json() [2/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
AprilTagFieldLayout & layout )

◆ from_json() [3/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
Pose2d & pose )

◆ from_json() [4/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
Pose3d & pose )

◆ from_json() [5/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
Quaternion & quaternion )

◆ from_json() [6/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
Rotation2d & rotation )

◆ from_json() [7/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
Rotation3d & rotation )

◆ from_json() [8/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
Trajectory::State & state )

◆ from_json() [9/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
Translation2d & state )

◆ from_json() [10/10]

WPILIB_DLLEXPORT void frc::from_json ( const wpi::json & json,
Translation3d & state )

◆ GetCameraServerShared()

CameraServerShared * frc::GetCameraServerShared ( )

◆ GetCurrentThreadPriority()

int frc::GetCurrentThreadPriority ( bool * isRealTime)

Get the thread priority for the current thread.

Parameters
isRealTimeSet to true if thread is real-time, otherwise false.
Returns
The current thread priority. For real-time, this is 1-99 with 99 being highest. For non-real-time, this is 0. See "man 7 sched" for details.

◆ GetErrorMessage()

const char * frc::GetErrorMessage ( int32_t * code)

Gets error message string for an error code.

◆ GetThreadPriority()

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 real-time, otherwise false.
Returns
The current thread priority. For real-time, this is 1-99 with 99 being highest. For non-real-time, this is 0. See "man 7 sched" for details.

◆ GetTime()

units::second_t 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.

◆ InputModulus()

template<typename T >
T frc::InputModulus ( T input,
T minimumInput,
T maximumInput )
constexpr

Returns modulus of input.

Parameters
inputInput value to wrap.
minimumInputThe minimum value expected from the input.
maximumInputThe maximum value expected from the input.

◆ IsDetectable()

template<int States, int Outputs>
bool frc::IsDetectable ( const Matrixd< States, States > & A,
const Matrixd< Outputs, States > & C )

Returns true if (A, C) is a detectable pair.

(A, C) is detectable if and only if the unobservable eigenvalues of A, if any, have absolute values less than one, where an eigenvalue is unobservable if rank([λI - A; C]) < n where n is the number of states.

Template Parameters
StatesNumber of states.
OutputsNumber of outputs.
Parameters
ASystem matrix.
COutput matrix.

◆ IsDetectable< Eigen::Dynamic, Eigen::Dynamic >()

template WPILIB_DLLEXPORT bool frc::IsDetectable< Eigen::Dynamic, Eigen::Dynamic > ( const Eigen::MatrixXd & A,
const Eigen::MatrixXd & C )
extern

◆ IsNear() [1/2]

template<typename T >
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T>
bool frc::IsNear ( T expected,
T actual,
T tolerance )
constexpr

Checks if the given value matches an expected value within a certain tolerance.

Parameters
expectedThe expected value
actualThe actual value
toleranceThe allowed difference between the actual and the expected value
Returns
Whether or not the actual value is within the allowed tolerance

◆ IsNear() [2/2]

template<typename T >
requires std::is_arithmetic_v<T> || units::traits::is_unit_t_v<T>
bool frc::IsNear ( T expected,
T actual,
T tolerance,
T min,
T max )
constexpr

Checks if the given value matches an expected value within a certain tolerance.

Supports continuous input for cases like absolute encoders.

Continuous input means that the min and max value are considered to be the same point, and tolerances can be checked across them. A common example would be for absolute encoders: calling isNear(2, 359, 5, 0, 360) returns true because 359 is 1 away from 360 (which is treated as the same as 0) and 2 is 2 away from 0, adding up to an error of 3 degrees, which is within the given tolerance of 5.

Parameters
expectedThe expected value
actualThe actual value
toleranceThe allowed difference between the actual and the expected value
minSmallest value before wrapping around to the largest value
maxLargest value before wrapping around to the smallest value
Returns
Whether or not the actual value is within the allowed tolerance

◆ IsStabilizable()

template<int States, int Inputs>
bool frc::IsStabilizable ( const Matrixd< States, States > & A,
const Matrixd< States, Inputs > & B )

Returns true if (A, B) is a stabilizable pair.

(A, B) is stabilizable if and only if the uncontrollable eigenvalues of A, if any, have absolute values less than one, where an eigenvalue is uncontrollable if rank([λI - A, B]) < n where n is the number of states.

Template Parameters
StatesNumber of states.
InputsNumber of inputs.
Parameters
ASystem matrix.
BInput matrix.

◆ IsStabilizable< 1, 1 >()

template WPILIB_DLLEXPORT bool frc::IsStabilizable< 1, 1 > ( const Matrixd< 1, 1 > & A,
const Matrixd< 1, 1 > & B )
extern

◆ IsStabilizable< 2, 1 >()

template WPILIB_DLLEXPORT bool frc::IsStabilizable< 2, 1 > ( const Matrixd< 2, 2 > & A,
const Matrixd< 2, 1 > & B )
extern

◆ IsStabilizable< Eigen::Dynamic, Eigen::Dynamic >()

template WPILIB_DLLEXPORT bool frc::IsStabilizable< Eigen::Dynamic, Eigen::Dynamic > ( const Eigen::MatrixXd & A,
const Eigen::MatrixXd & B )
extern

◆ LoadAprilTagLayoutField()

WPILIB_DLLEXPORT AprilTagFieldLayout frc::LoadAprilTagLayoutField ( AprilTagField field)

Loads an AprilTagFieldLayout from a predefined field.

Parameters
fieldThe predefined field
Returns
AprilTagFieldLayout of the field
Deprecated
Use AprilTagFieldLayout::LoadField() instead

◆ MakeCostMatrix() [1/3]

template<size_t N>
Matrixd< N, N > frc::MakeCostMatrix ( const std::array< double, N > & costs)
constexpr

Creates a cost matrix from the given vector for use with LQR.

The cost matrix is constructed using Bryson's rule. The inverse square of each element in the input is placed on the cost matrix diagonal. If a tolerance is infinity, its cost matrix entry is set to zero.

Parameters
costsAn array. For a Q matrix, its elements are the maximum allowed excursions of the states from the reference. For an R matrix, its elements are the maximum allowed excursions of the control inputs from no actuation.
Returns
State excursion or control effort cost matrix.

◆ MakeCostMatrix() [2/3]

WPILIB_DLLEXPORT Eigen::MatrixXd frc::MakeCostMatrix ( const std::span< const double > costs)

Creates a cost matrix from the given vector for use with LQR.

The cost matrix is constructed using Bryson's rule. The inverse square of each element in the input is placed on the cost matrix diagonal. If a tolerance is infinity, its cost matrix entry is set to zero.

Parameters
costsA possibly variable length container. For a Q matrix, its elements are the maximum allowed excursions of the states from the reference. For an R matrix, its elements are the maximum allowed excursions of the control inputs from no actuation.
Returns
State excursion or control effort cost matrix.

◆ MakeCostMatrix() [3/3]

template<std::same_as< double >... Ts>
Matrixd< sizeof...(Ts), sizeof...(Ts)> frc::MakeCostMatrix ( Ts... tolerances)
constexpr

Creates a cost matrix from the given vector for use with LQR.

The cost matrix is constructed using Bryson's rule. The inverse square of each tolerance is placed on the cost matrix diagonal. If a tolerance is infinity, its cost matrix entry is set to zero.

Parameters
tolerancesAn array. For a Q matrix, its elements are the maximum allowed excursions of the states from the reference. For an R matrix, its elements are the maximum allowed excursions of the control inputs from no actuation.
Returns
State excursion or control effort cost matrix.

◆ MakeCovMatrix() [1/3]

template<size_t N>
Matrixd< N, N > frc::MakeCovMatrix ( const std::array< double, N > & stdDevs)
constexpr

Creates a covariance matrix from the given vector for use with Kalman filters.

Each element is squared and placed on the covariance matrix diagonal.

Parameters
stdDevsAn array. For a Q matrix, its elements are the standard deviations of each state from how the model behaves. For an R matrix, its elements are the standard deviations for each output measurement.
Returns
Process noise or measurement noise covariance matrix.

◆ MakeCovMatrix() [2/3]

WPILIB_DLLEXPORT Eigen::MatrixXd frc::MakeCovMatrix ( const std::span< const double > stdDevs)

Creates a covariance matrix from the given vector for use with Kalman filters.

Each element is squared and placed on the covariance matrix diagonal.

Parameters
stdDevsA possibly variable length container. For a Q matrix, its elements are the standard deviations of each state from how the model behaves. For an R matrix, its elements are the standard deviations for each output measurement.
Returns
Process noise or measurement noise covariance matrix.

◆ MakeCovMatrix() [3/3]

template<std::same_as< double >... Ts>
Matrixd< sizeof...(Ts), sizeof...(Ts)> frc::MakeCovMatrix ( Ts... stdDevs)
constexpr

Creates a covariance matrix from the given vector for use with Kalman filters.

Each element is squared and placed on the covariance matrix diagonal.

Parameters
stdDevsAn array. For a Q matrix, its elements are the standard deviations of each state from how the model behaves. For an R matrix, its elements are the standard deviations for each output measurement.
Returns
Process noise or measurement noise covariance matrix.

◆ MakeError()

template<typename... Args>
RuntimeError frc::MakeError ( int32_t status,
const char * fileName,
int lineNumber,
const char * funcName,
fmt::string_view format,
Args &&... args )
inlinenodiscard

◆ MakeErrorV()

RuntimeError frc::MakeErrorV ( int32_t status,
const char * fileName,
int lineNumber,
const char * funcName,
fmt::string_view format,
fmt::format_args args )
nodiscard

Makes a runtime error exception object.

This object should be thrown by the caller. Generally the FRC_MakeError wrapper macro should be used instead.

Parameters
[out]statuserror code
[in]fileNamesource file name
[in]lineNumbersource line number
[in]funcNamesource function name
[in]formaterror message format
[in]argserror message format args
Returns
runtime error object

◆ MakeWhiteNoiseVector() [1/3]

template<int N>
Vectord< N > frc::MakeWhiteNoiseVector ( const std::array< double, N > & stdDevs)

Creates a vector of normally distributed white noise with the given noise intensities for each element.

Parameters
stdDevsAn array whose elements are the standard deviations of each element of the noise vector.
Returns
White noise vector.

◆ MakeWhiteNoiseVector() [2/3]

WPILIB_DLLEXPORT Eigen::VectorXd frc::MakeWhiteNoiseVector ( const std::span< const double > stdDevs)

Creates a vector of normally distributed white noise with the given noise intensities for each element.

Parameters
stdDevsA possibly variable length container whose elements are the standard deviations of each element of the noise vector.
Returns
White noise vector.

◆ MakeWhiteNoiseVector() [3/3]

template<std::same_as< double >... Ts>
Vectord< sizeof...(Ts)> frc::MakeWhiteNoiseVector ( Ts... stdDevs)

◆ NumericalJacobian() [1/2]

template<typename F >
Eigen::MatrixXd frc::NumericalJacobian ( F && f,
const Eigen::VectorXd & x )

Returns numerical Jacobian with respect to x for f(x).

Parameters
fVector-valued function from which to compute Jacobian.
xVector argument.

◆ NumericalJacobian() [2/2]

template<int Rows, int Cols, typename F >
auto frc::NumericalJacobian ( F && f,
const Vectord< Cols > & x )

Returns numerical Jacobian with respect to x for f(x).

Template Parameters
RowsNumber of rows in result of f(x).
ColsNumber of columns in result of f(x).
Parameters
fVector-valued function from which to compute Jacobian.
xVector argument.

◆ NumericalJacobianU() [1/2]

template<typename F , typename... Args>
auto frc::NumericalJacobianU ( F && f,
const Eigen::VectorXd & x,
const Eigen::VectorXd & u,
Args &&... args )

Returns numerical Jacobian with respect to u for f(x, u, ...).

Template Parameters
FFunction object type.
Args...Types of remaining arguments to f(x, u, ...).
Parameters
fVector-valued function from which to compute Jacobian.
xState vector.
uInput vector.
argsRemaining arguments to f(x, u, ...).

◆ NumericalJacobianU() [2/2]

template<int Rows, int States, int Inputs, typename F , typename... Args>
auto frc::NumericalJacobianU ( F && f,
const Vectord< States > & x,
const Vectord< Inputs > & u,
Args &&... args )

Returns numerical Jacobian with respect to u for f(x, u, ...).

Template Parameters
RowsNumber of rows in result of f(x, u, ...).
StatesNumber of rows in x.
InputsNumber of rows in u.
FFunction object type.
Args...Types of remaining arguments to f(x, u, ...).
Parameters
fVector-valued function from which to compute Jacobian.
xState vector.
uInput vector.
argsRemaining arguments to f(x, u, ...).

◆ NumericalJacobianX() [1/2]

template<typename F , typename... Args>
auto frc::NumericalJacobianX ( F && f,
const Eigen::VectorXd & x,
const Eigen::VectorXd & u,
Args &&... args )

Returns numerical Jacobian with respect to x for f(x, u, ...).

Template Parameters
FFunction object type.
Args...Types of remaining arguments to f(x, u, ...).
Parameters
fVector-valued function from which to compute Jacobian.
xState vector.
uInput vector.
argsRemaining arguments to f(x, u, ...).

◆ NumericalJacobianX() [2/2]

template<int Rows, int States, int Inputs, typename F , typename... Args>
auto frc::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 Parameters
RowsNumber of rows in result of f(x, u, ...).
StatesNumber of rows in x.
InputsNumber of rows in u.
FFunction object type.
Args...Types of remaining arguments to f(x, u, ...).
Parameters
fVector-valued function from which to compute Jacobian.
xState vector.
uInput vector.
argsRemaining arguments to f(x, u, ...).

◆ ObjectToRobotPose()

WPILIB_DLLEXPORT constexpr frc::Pose3d frc::ObjectToRobotPose ( const frc::Pose3d & objectInField,
const frc::Transform3d & cameraToObject,
const frc::Transform3d & robotToCamera )
constexpr

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.

The object could be a target or a fiducial marker.

Parameters
objectInFieldAn object's field-relative pose.
cameraToObjectThe transformation from the camera's pose to the object's pose. This comes from computer vision.
robotToCameraThe transformation from the robot's pose to the camera's pose. This can either be a constant for a rigidly mounted camera, or variable if the camera is mounted to a turret. If the camera was mounted 3 inches in front of the "origin" (usually physical center) of the robot, this would be frc::Transform3d{3_in, 0_in, 0_in, frc::Rotation3d{}}.
Returns
The robot's field-relative pose.

◆ PoseTo3dVector()

WPILIB_DLLEXPORT constexpr Eigen::Vector3d frc::PoseTo3dVector ( const Pose2d & pose)
constexpr

Converts a Pose2d into a vector of [x, y, theta].

Parameters
poseThe pose that is being represented.
Returns
The vector.
Deprecated
Create the vector manually instead. If you were using this as an intermediate step for constructing affine transformations, use Pose2d.ToMatrix() instead.

◆ PoseTo4dVector()

WPILIB_DLLEXPORT constexpr Eigen::Vector4d frc::PoseTo4dVector ( const Pose2d & pose)
constexpr

Converts a Pose2d into a vector of [x, y, std::cos(theta), std::sin(theta)].

Parameters
poseThe pose that is being represented.
Returns
The vector.
Deprecated
Create the vector manually instead. If you were using this as an intermediate step for constructing affine transformations, use Pose2d.ToMatrix() instead.

◆ PoseToVector()

WPILIB_DLLEXPORT constexpr Eigen::Vector3d frc::PoseToVector ( const Pose2d & pose)
constexpr

Converts a Pose2d into a vector of [x, y, theta].

Parameters
poseThe pose that is being represented.
Returns
The vector.
Deprecated
Create the vector manually instead. If you were using this as an intermediate step for constructing affine transformations, use Pose2d.ToMatrix() instead.

◆ ReportError()

template<typename... Args>
void frc::ReportError ( int32_t status,
const char * fileName,
int lineNumber,
const char * funcName,
fmt::string_view format,
Args &&... args )
inline

Reports an error to the driver station (using HAL_SendError).

Generally the FRC_ReportError wrapper macro should be used instead.

Parameters
[out]statuserror code
[in]fileNamesource file name
[in]lineNumbersource line number
[in]funcNamesource function name
[in]formaterror message format
[in]argserror message format args

◆ ReportErrorV()

void frc::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).

Generally the FRC_ReportError wrapper macro should be used instead.

Parameters
[out]statuserror code
[in]fileNamesource file name
[in]lineNumbersource line number
[in]funcNamesource function name
[in]formaterror message format
[in]argserror message format args

◆ RK4() [1/3]

template<typename F , typename T , typename U >
T frc::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.

Parameters
fThe function to integrate. It must take two arguments x and u.
xThe initial value of x.
uThe value u held constant over the integration period.
dtThe time over which to integrate.

◆ RK4() [2/3]

template<typename F , typename T >
T frc::RK4 ( F && f,
T x,
units::second_t dt )

Performs 4th order Runge-Kutta integration of dx/dt = f(x) for dt.

Parameters
fThe function to integrate. It must take one argument x.
xThe initial value of x.
dtThe time over which to integrate.

◆ RK4() [3/3]

template<typename F , typename T >
T frc::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.

Parameters
fThe function to integrate. It must take two arguments t and y.
tThe initial value of t.
yThe initial value of y.
dtThe time over which to integrate.

◆ RKDP() [1/2]

template<typename F , typename T , typename U >
T frc::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.

Parameters
fThe function to integrate. It must take two arguments x and u.
xThe initial value of x.
uThe value u held constant over the integration period.
dtThe time over which to integrate.
maxErrorThe maximum acceptable truncation error. Usually a small number like 1e-6.

◆ RKDP() [2/2]

template<typename F , typename T >
T frc::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.

Parameters
fThe function to integrate. It must take two arguments t and y.
tThe initial value of t.
yThe initial value of y.
dtThe time over which to integrate.
maxErrorThe maximum acceptable truncation error. Usually a small number like 1e-6.

◆ RunHALInitialization()

int frc::RunHALInitialization ( )

◆ SetCurrentThreadPriority()

bool frc::SetCurrentThreadPriority ( bool realTime,
int priority )

Sets the thread priority for the current thread.

Parameters
realTimeSet to true to set a real-time priority, false for standard priority.
priorityPriority to set the thread to. For real-time, this is 1-99 with 99 being highest. For non-real-time, this is forced to
  1. See "man 7 sched" for more details.
Returns
True on success.

◆ SetThreadPriority()

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 real-time priority, false for standard priority.
priorityPriority to set the thread to. For real-time, this is 1-99 with 99 being highest. For non-real-time, this is forced to
  1. See "man 7 sched" for more details.
Returns
True on success.

◆ SlewRateLimit() [1/2]

Translation2d frc::SlewRateLimit ( const Translation2d & current,
const Translation2d & next,
units::second_t dt,
units::meters_per_second_t maxVelocity )
constexpr

Limits translation velocity.

Parameters
currentTranslation at current timestep.
nextTranslation at next timestep.
dtTimestep duration.
maxVelocityMaximum translation velocity.
Returns
Returns the next Translation2d limited to maxVelocity

◆ SlewRateLimit() [2/2]

Translation3d frc::SlewRateLimit ( const Translation3d & current,
const Translation3d & next,
units::second_t dt,
units::meters_per_second_t maxVelocity )
constexpr

Limits translation velocity.

Parameters
currentTranslation at current timestep.
nextTranslation at next timestep.
dtTimestep duration.
maxVelocityMaximum translation velocity.
Returns
Returns the next Translation3d limited to maxVelocity

◆ SquareRootUnscentedTransform()

template<int CovDim, int NumSigmas>
std::tuple< Vectord< CovDim >, Matrixd< CovDim, CovDim > > frc::SquareRootUnscentedTransform ( const Matrixd< CovDim, NumSigmas > & sigmas,
const Vectord< NumSigmas > & Wm,
const Vectord< NumSigmas > & Wc,
std::function< Vectord< CovDim >(const Matrixd< CovDim, NumSigmas > &, const Vectord< NumSigmas > &)> 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.

CovDim returns the mean and square-root covariance of the sigma points in a tuple.

This works in conjunction with the UnscentedKalmanFilter class. For use with square-root form UKFs.

Template Parameters
CovDimDimension of covariance of sigma points after passing through the transform.
NumSigmasNumber of sigma points.
Parameters
sigmasList of sigma points.
WmWeights for the mean.
WcWeights for the covariance.
meanFuncA function that computes the mean of NumSigmas state vectors using a given set of weights.
residualFuncA function that computes the residual of two state vectors (i.e. it subtracts them.)
squareRootRSquare-root of the noise covariance of the sigma points.
Returns
Tuple of x, mean of sigma points; S, square-root covariance of sigmas.

◆ StartRobot()

template<class Robot >
int frc::StartRobot ( )

◆ SwerveDriveKinematics()

template<typename ModuleTranslation , typename... ModuleTranslations>
frc::SwerveDriveKinematics ( ModuleTranslation ,
ModuleTranslations...  ) -> SwerveDriveKinematics< 1+sizeof...(ModuleTranslations)>

◆ to_json() [1/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const AprilTag & apriltag )

◆ to_json() [2/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const AprilTagFieldLayout & layout )

◆ to_json() [3/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const Pose2d & pose )

◆ to_json() [4/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const Pose3d & pose )

◆ to_json() [5/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const Quaternion & quaternion )

◆ to_json() [6/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const Rotation2d & rotation )

◆ to_json() [7/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const Rotation3d & rotation )

◆ to_json() [8/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const Trajectory::State & state )

◆ to_json() [9/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const Translation2d & state )

◆ to_json() [10/10]

WPILIB_DLLEXPORT void frc::to_json ( wpi::json & json,
const Translation3d & state )

◆ to_string()

std::string_view frc::to_string ( const DAREError & error)
constexpr

Converts the given DAREError enum to a string.

◆ Wait()

void frc::Wait ( units::second_t 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.