From ef08b7ca8405bce8d9a85c020c240bf480db3426 Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Mon, 23 Oct 2023 21:12:04 -0400 Subject: [PATCH 1/9] first portion done, heading to bed. still have 34 files to go --- .../contributing/frc-docs/style-guide.rst | 26 +- .../control-system-hardware.rst | 27 +- .../networking-utilities/portforwarding.rst | 16 +- .../controllers/bang-bang.rst | 24 +- .../combining-feedforward-feedback.rst | 16 +- .../controllers/feedforward.rst | 42 +-- .../controllers/pidcontroller.rst | 42 +-- .../controllers/profiled-pidcontroller.rst | 42 ++- .../controllers/trapezoidal-profiles.rst | 54 ++-- .../advanced-controls/filters/debouncer.rst | 6 +- .../filters/linear-filter.rst | 24 +- .../filters/median-filter.rst | 12 +- .../filters/slew-rate-limiter.rst | 18 +- .../state-space/state-space-debugging.rst | 6 +- .../state-space-flywheel-walkthrough.rst | 83 ++--- .../state-space/state-space-intro.rst | 52 ++- .../state-space/state-space-observers.rst | 7 +- .../state-space-pose-estimators.rst | 72 ++--- .../trajectories/constraints.rst | 6 +- .../trajectories/holonomic.rst | 18 +- .../manipulating-trajectories.rst | 12 +- .../trajectories/ramsete.rst | 18 +- .../trajectories/trajectory-generation.rst | 12 +- .../transforming-trajectories.rst | 12 +- .../trajectories/troubleshooting.rst | 44 ++- .../basic-programming/git-getting-started.rst | 6 +- .../software/basic-programming/joystick.rst | 48 +-- .../basic-programming/reading-stacktraces.rst | 302 +++++++++--------- .../basic-programming/robot-preferences.rst | 24 +- .../can-devices/power-distribution-module.rst | 88 +++-- .../binding-commands-to-triggers.rst | 70 ++-- .../commandbased/command-compositions.rst | 91 +++--- .../commandbased/command-scheduler.rst | 51 +-- .../commandbased/organizing-command-based.rst | 72 ++--- .../commandbased/what-is-command-based.rst | 12 +- .../glass/command-based-widgets.rst | 6 +- .../software/dashboards/glass/widgets.rst | 12 +- ...e-labview-dashboard-with-c++-java-code.rst | 54 ++-- .../shuffleboard-commands-subsystems.rst | 12 +- .../shuffleboard-tuning-pid.rst | 6 +- .../getting-started/shuffleboard-tour.rst | 4 +- .../layouts-with-code/configuring-widgets.rst | 12 +- .../layouts-with-code/organizing-widgets.rst | 12 +- .../layouts-with-code/retrieving-data.rst | 4 +- .../layouts-with-code/sending-data.rst | 22 +- .../layouts-with-code/using-tabs.rst | 12 +- .../smartdashboard/displaying-expressions.rst | 6 +- ...ying-status-of-commands-and-subsystems.rst | 18 +- .../displaying-LiveWindow-values.rst | 12 +- .../enabling-test-mode.rst | 6 +- .../verifying-smartdashboard-is-working.rst | 6 +- .../software/hardware-apis/motors/servos.rst | 16 +- .../motors/using-motor-controllers.rst | 8 +- .../sensors/accelerometers-software.rst | 48 +-- .../sensors/analog-inputs-software.rst | 54 ++-- .../analog-potentiometers-software.rst | 18 +- .../hardware-apis/sensors/counters.rst | 78 ++--- .../sensors/digital-inputs-software.rst | 30 +- .../sensors/encoders-software.rst | 120 +++---- .../hardware-apis/sensors/gyros-software.rst | 60 ++-- .../hardware-apis/sensors/limit-switch.rst | 6 +- .../differential-drive-kinematics.rst | 12 +- .../differential-drive-odometry.rst | 12 +- .../intro-and-chassis-speeds.rst | 12 +- .../mecanum-drive-kinematics.rst | 24 +- .../mecanum-drive-odometry.rst | 12 +- .../swerve-drive-kinematics.rst | 30 +- .../swerve-drive-odometry.rst | 12 +- ...rray-values-published-by-networktables.rst | 10 +- .../software/networktables/robot-program.rst | 8 +- .../roborio-info/roborio-brownouts.rst | 6 +- source/docs/software/telemetry/datalog.rst | 18 +- .../robot-telemetry-with-sendable.rst | 6 +- .../telemetry/writing-sendable-classes.rst | 48 ++- ...sing-generated-code-in-a-robot-program.rst | 12 +- .../introduction/cameraserver-class.rst | 12 +- .../roborio/using-multiple-cameras.rst | 18 +- .../wpilibpi/basic-vision-example.rst | 4 +- .../wpilibpi/image-thresholding.rst | 8 +- .../wpilibpi/morphological-operations.rst | 16 +- .../wpilibpi/using-cameraserver.rst | 8 +- .../wpilibpi/working-with-contours.rst | 24 +- .../creating-robot-program.rst | 31 +- .../debugging-robot-program.rst | 6 +- .../robot-simulation/device-sim.rst | 30 +- .../drivesim-tutorial/drivetrain-model.rst | 18 +- .../drivesim-tutorial/odometry-simgui.rst | 18 +- .../drivesim-tutorial/simulation-instance.rst | 12 +- .../updating-drivetrain-model.rst | 6 +- .../robot-simulation/simulation-gui.rst | 4 +- ...robotbuilder-writing-pidsubsystem-code.rst | 18 +- .../robotbuilder-created-code.rst | 28 +- ...robotbuilder-testing-with-shuffleboard.rst | 6 +- .../writing-code/robotbuilder-drive-tank.rst | 25 +- .../robotbuilder-writing-command-code.rst | 180 ++++++----- .../docs/yearly-overview/2020-Game-Data.rst | 6 +- .../step-1/intro-to-frc-robot-wiring.rst | 112 ++++--- .../zero-to-robot/step-2/frc-game-tools.rst | 6 +- .../zero-to-robot/step-2/labview-setup.rst | 6 +- ...ating-test-drivetrain-program-cpp-java.rst | 194 +++++------ 100 files changed, 1571 insertions(+), 1544 deletions(-) diff --git a/source/docs/contributing/frc-docs/style-guide.rst b/source/docs/contributing/frc-docs/style-guide.rst index 1e851f70f9..ca71eb0252 100644 --- a/source/docs/contributing/frc-docs/style-guide.rst +++ b/source/docs/contributing/frc-docs/style-guide.rst @@ -105,25 +105,23 @@ RLI (Remote Literal Include) When possible, instead of using code blocks, an RLI should be used. This pulls code lines directly from GitHub, most commonly using the example programs. This automatically keeps the code up to date with any changes that are made. The format of an RLI is: -.. code-block:: ReST +.. tab-set-code:: - .. group-tab:: Java - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Robot.java - :language: java - :lines: 44-61 - :linenos: - :lineno-start: 44 + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Robot.java + :language: java + :lines: 44-61 + :linenos: + :lineno-start: 44 - .. group-tab:: C++ - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Robot.cpp - :language: cpp - :lines: 18-30 - :linenos: - :lineno-start: 18 + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Robot.cpp + :language: cpp + :lines: 18-30 + :linenos: + :lineno-start: 18 -Note that group-tab rather than code-tab needs to be used. Also make sure to link to the raw version of the file on GitHub. There is a handy ``Raw`` button in the top right corner of the page. +Make sure to link to the raw version of the file on GitHub. There is a handy ``Raw`` button in the top right corner of the page. Admonitions ----------- diff --git a/source/docs/controls-overviews/control-system-hardware.rst b/source/docs/controls-overviews/control-system-hardware.rst index 0677bebc85..7dc16e0162 100644 --- a/source/docs/controls-overviews/control-system-hardware.rst +++ b/source/docs/controls-overviews/control-system-hardware.rst @@ -10,23 +10,24 @@ The goal of this document is to provide a brief overview of the hardware compone Overview of Control System -------------------------- -.. tabs:: +.. tab-set:: + .. tab-item:: REV + :sync: rev - .. group-tab:: REV - - .. figure:: images/frc-control-system-layout-rev.svg + .. figure:: images/frc-control-system-layout-rev.svg :alt: Layout of all popular components of the control system including REV Control System Components :width: 500 - Diagram courtesy of FRC\ |reg| Team 3161 and Stefen Acepcion. + Diagram courtesy of FRC\ |reg| Team 3161 and Stefen Acepcion. - .. group-tab:: CTRE + .. tab-item:: CTRE + :sync: ctre - .. figure:: images/frc-control-system-layout.svg - :alt: Layout of all of the core components of the control system and how they are connected. - :width: 500 + .. figure:: images/frc-control-system-layout.svg + :alt: Layout of all of the core components of the control system and how they are connected. + :width: 500 - Diagram courtesy of FRC\ |reg| Team 3161 and Stefen Acepcion. + Diagram courtesy of FRC\ |reg| Team 3161 and Stefen Acepcion. NI roboRIO ---------- @@ -116,9 +117,9 @@ The power supply for an FRC robot is a single 12V 18Ah Sealed Lead Acid (SLA) ba Robot Signal Light ------------------ -.. tabs:: +.. tab-set:: - .. tab:: Allen-Bradley + .. tab-item:: Allen-Bradley .. figure:: images/control-system-hardware/rsl-allenbradley.png :alt: Orange Robot Signal Light (Allen-Bradley) @@ -126,7 +127,7 @@ Robot Signal Light Allen-Bradley 855PB-B12ME522 - .. tab:: AndyMark + .. tab-item:: AndyMark .. figure:: images/control-system-hardware/rsl-andymark.png :alt: Orange Robot Signal Light (AndyMark) diff --git a/source/docs/networking/networking-utilities/portforwarding.rst b/source/docs/networking/networking-utilities/portforwarding.rst index db9be70f2c..e647d94bf8 100644 --- a/source/docs/networking/networking-utilities/portforwarding.rst +++ b/source/docs/networking/networking-utilities/portforwarding.rst @@ -8,22 +8,22 @@ Forwarding a Remote Port Often teams may wish to connect directly to the roboRIO for controlling their robot. The PortForwarding class (`Java `__, `C++ `__) can be used to forward the Raspberry Pi connection for usage during these times. The PortForwarding class establishes a bridge between the remote and the client. To forward a port in Java, simply do ``PortForwarder.add(int port, String remoteName, int remotePort)``. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void robotInit() { PortForwarder.add(8888, "wpilibpi.local", 80); } - .. code-tab:: c++ + .. code-block:: c++ void Robot::RobotInit { wpi::PortForwarder::GetInstance().Add(8888, "wpilibpi.local", 80); } - .. code-tab:: python + .. code-block:: python wpiutil.PortForwarder.getInstance().add(8888, "wpilibpi.local", 80) @@ -34,21 +34,21 @@ Removing a Forwarded Port To stop forwarding on a specified port, simply call ``remove(int port)`` with port being the port number. If you call ``remove()`` on a port that is not being forwarded, nothing will happen. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void robotInit() { PortForwarder.remove(8888); } - .. code-tab:: c++ + .. code-block:: c++ void Robot::RobotInit { wpi::PortForwarder::GetInstance().Remove(8888); } - .. code-tab:: python + .. code-block:: python wpiutil.PortForwarder.getInstance().remove(8888) diff --git a/source/docs/software/advanced-controls/controllers/bang-bang.rst b/source/docs/software/advanced-controls/controllers/bang-bang.rst index f9849f49fa..34acb75e2d 100644 --- a/source/docs/software/advanced-controls/controllers/bang-bang.rst +++ b/source/docs/software/advanced-controls/controllers/bang-bang.rst @@ -14,19 +14,19 @@ Constructing a BangBangController Since a bang-bang controller does not have any gains, it does not need any constructor arguments (one can optionally specify the controller tolerance used by ``atSetpoint``, but it is not required). -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a BangBangController BangBangController controller = new BangBangController(); - .. code-tab:: c++ + .. code-block:: c++ // Creates a BangBangController frc::BangBangController controller; - .. code-tab:: python + .. code-block:: python # Creates a BangBangController controller = wpimath.BangBangController() @@ -38,19 +38,19 @@ Using a BangBangController Using a bang-bang controller is easy: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Controls a motor with the output of the BangBang controller motor.set(controller.calculate(encoder.getRate(), setpoint)); - .. code-tab:: c++ + .. code-block:: c++ // Controls a motor with the output of the BangBang controller motor.Set(controller.Calculate(encoder.GetRate(), setpoint)); - .. code-tab:: python + .. code-block:: python # Controls a motor with the output of the BangBang controller motor.set(controller.calculate(encoder.getRate(), setpoint)) @@ -60,21 +60,21 @@ Combining Bang Bang Control with Feedforward Like a PID controller, best results are obtained in conjunction with a :ref:`feedforward ` controller that provides the necessary voltage to sustain the system output at the desired speed, so that the bang-bang controller is only responsible for rejecting disturbances. Since the bang-bang controller can *only* correct in the forward direction, however, it may be preferable to use a slightly conservative feedforward estimate to ensure that the shooter does not over-speed. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Controls a motor with the output of the BangBang controller and a feedforward // Shrinks the feedforward slightly to avoid overspeeding the shooter motor.setVoltage(controller.calculate(encoder.getRate(), setpoint) * 12.0 + 0.9 * feedforward.calculate(setpoint)); - .. code-tab:: c++ + .. code-block:: c++ // Controls a motor with the output of the BangBang controller and a feedforward // Shrinks the feedforward slightly to avoid overspeeding the shooter motor.SetVoltage(controller.Calculate(encoder.GetRate(), setpoint) * 12.0 + 0.9 * feedforward.Calculate(setpoint)); - .. code-tab:: python + .. code-block:: python # Controls a motor with the output of the BangBang controller and a feedforward motor.setVoltage(controller.calculate(encoder.getRate(), setpoint) * 12.0 + 0.9 * feedforward.calculate(setpoint)) diff --git a/source/docs/software/advanced-controls/controllers/combining-feedforward-feedback.rst b/source/docs/software/advanced-controls/controllers/combining-feedforward-feedback.rst index 20d4bb9888..490e6fdb11 100644 --- a/source/docs/software/advanced-controls/controllers/combining-feedforward-feedback.rst +++ b/source/docs/software/advanced-controls/controllers/combining-feedforward-feedback.rst @@ -14,19 +14,19 @@ Using Feedforward with a PIDController Users may add any feedforward they like to the output of the controller before sending it to their motors: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Adds a feedforward to the loop output before sending it to the motor motor.setVoltage(pid.calculate(encoder.getDistance(), setpoint) + feedforward); - .. code-tab:: c++ + .. code-block:: c++ // Adds a feedforward to the loop output before sending it to the motor motor.SetVoltage(pid.Calculate(encoder.GetDistance(), setpoint) + feedforward); - .. code-tab:: python + .. code-block:: python // Adds a feedforward to the loop output before sending it to the motor motor.setVoltage(pid.calculate(encoder.getDistance(), setpoint) + feedforward) @@ -40,9 +40,9 @@ Using Feedforward Components with PID What might a more complete example of combined feedforward/PID control look like? Consider the :ref:`drive example ` from the feedforward page. We can easily modify this to include feedback control (with a ``SimpleMotorFeedforward`` component): -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public void tankDriveWithFeedforwardPID(double leftVelocitySetpoint, double rightVelocitySetpoint) { leftMotor.setVoltage(feedforward.calculate(leftVelocitySetpoint) @@ -51,7 +51,7 @@ What might a more complete example of combined feedforward/PID control look like + rightPID.calculate(rightEncoder.getRate(), rightVelocitySetpoint)); } - .. code-tab:: c++ + .. code-block:: c++ void TankDriveWithFeedforwardPID(units::meters_per_second_t leftVelocitySetpoint, units::meters_per_second_t rightVelocitySetpoint) { @@ -61,7 +61,7 @@ What might a more complete example of combined feedforward/PID control look like + rightPID.Calculate(rightEncoder.getRate(), rightVelocitySetpoint.value())); } - .. code-tab:: python + .. code-block:: python def tank_drive_with_feedforward_PID( left_velocity_setpoint: float, diff --git a/source/docs/software/advanced-controls/controllers/feedforward.rst b/source/docs/software/advanced-controls/controllers/feedforward.rst index 956d929a44..d583590108 100644 --- a/source/docs/software/advanced-controls/controllers/feedforward.rst +++ b/source/docs/software/advanced-controls/controllers/feedforward.rst @@ -35,14 +35,14 @@ To create a ``SimpleMotorFeedforward``, simply construct it with the required ga .. note:: The ``kA`` gain can be omitted, and if it is, will default to a value of zero. For many mechanisms, especially those with little inertia, it is not necessary. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Create a new SimpleMotorFeedforward with gains kS, kV, and kA SimpleMotorFeedforward feedforward = new SimpleMotorFeedforward(kS, kV, kA); - .. code-tab:: c++ + .. code-block:: c++ // Create a new SimpleMotorFeedforward with gains kS, kV, and kA // Distance is measured in meters @@ -52,15 +52,15 @@ To calculate the feedforward, simply call the ``calculate()`` method with the de .. note:: The acceleration argument may be omitted from the ``calculate()`` call, and if it is, will default to a value of zero. This should be done whenever there is not a clearly-defined acceleration setpoint. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Calculates the feedforward for a velocity of 10 units/second and an acceleration of 20 units/second^2 // Units are determined by the units of the gains passed in at construction. feedforward.calculate(10, 20); - .. code-tab:: c++ + .. code-block:: c++ // Calculates the feedforward for a velocity of 10 meters/second and an acceleration of 20 meters/second^2 // Output is in volts @@ -79,14 +79,14 @@ To create an ``ArmFeedforward``, simply construct it with the required gains: .. note:: The ``kA`` gain can be omitted, and if it is, will default to a value of zero. For many mechanisms, especially those with little inertia, it is not necessary. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Create a new ArmFeedforward with gains kS, kG, kV, and kA ArmFeedforward feedforward = new ArmFeedforward(kS, kG, kV, kA); - .. code-tab:: c++ + .. code-block:: c++ // Create a new ArmFeedforward with gains kS, kG, kV, and kA frc::ArmFeedforward feedforward(kS, kG, kV, kA); @@ -95,16 +95,16 @@ To calculate the feedforward, simply call the ``calculate()`` method with the de .. note:: The acceleration argument may be omitted from the ``calculate()`` call, and if it is, will default to a value of zero. This should be done whenever there is not a clearly-defined acceleration setpoint. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Calculates the feedforward for a position of 1 units, a velocity of 2 units/second, and // an acceleration of 3 units/second^2 // Units are determined by the units of the gains passed in at construction. feedforward.calculate(1, 2, 3); - .. code-tab:: c++ + .. code-block:: c++ // Calculates the feedforward for a position of 1 radians, a velocity of 2 radians/second, and // an acceleration of 3 radians/second^2 @@ -124,14 +124,14 @@ To create a ``ElevatorFeedforward``, simply construct it with the required gains .. note:: The ``kA`` gain can be omitted, and if it is, will default to a value of zero. For many mechanisms, especially those with little inertia, it is not necessary. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Create a new ElevatorFeedforward with gains kS, kG, kV, and kA ElevatorFeedforward feedforward = new ElevatorFeedforward(kS, kG, kV, kA); - .. code-tab:: c++ + .. code-block:: c++ // Create a new ElevatorFeedforward with gains kS, kV, and kA // Distance is measured in meters @@ -141,16 +141,16 @@ To calculate the feedforward, simply call the ``calculate()`` method with the de .. note:: The acceleration argument may be omitted from the ``calculate()`` call, and if it is, will default to a value of zero. This should be done whenever there is not a clearly-defined acceleration setpoint. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Calculates the feedforward for a velocity of 20 units/second // and an acceleration of 30 units/second^2 // Units are determined by the units of the gains passed in at construction. feedforward.calculate(20, 30); - .. code-tab:: c++ + .. code-block:: c++ // Calculates the feedforward for a velocity of 20 meters/second // and an acceleration of 30 meters/second^2 @@ -164,16 +164,16 @@ Using Feedforward to Control Mechanisms Feedforward control can be used entirely on its own, without a feedback controller. This is known as "open-loop" control, and for many mechanisms (especially robot drives) can be perfectly satisfactory. A ``SimpleMotorFeedforward`` might be employed to control a robot drive as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public void tankDriveWithFeedforward(double leftVelocity, double rightVelocity) { leftMotor.setVoltage(feedforward.calculate(leftVelocity)); rightMotor.setVoltage(feedForward.calculate(rightVelocity)); } - .. code-tab:: c++ + .. code-block:: c++ void TankDriveWithFeedforward(units::meters_per_second_t leftVelocity, units::meters_per_second_t rightVelocity) { diff --git a/source/docs/software/advanced-controls/controllers/pidcontroller.rst b/source/docs/software/advanced-controls/controllers/pidcontroller.rst index 606da04750..ecdae1ff17 100644 --- a/source/docs/software/advanced-controls/controllers/pidcontroller.rst +++ b/source/docs/software/advanced-controls/controllers/pidcontroller.rst @@ -17,14 +17,14 @@ Constructing a PIDController In order to use WPILib's PID control functionality, users must first construct a ``PIDController`` object with the desired gains: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a PIDController with gains kP, kI, and kD PIDController pid = new PIDController(kP, kI, kD); - .. code-tab:: c++ + .. code-block:: c++ // Creates a PIDController with gains kP, kI, and kD frc::PIDController pid{kP, kI, kD}; @@ -38,15 +38,15 @@ Using the Feedback Loop Output Using the constructed ``PIDController`` is simple: simply call the ``calculate()`` method from the robot's main loop (e.g. the robot's ``autonomousPeriodic()`` method): -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Calculates the output of the PID algorithm based on the sensor reading // and sends it to a motor motor.set(pid.calculate(encoder.getDistance(), setpoint)); - .. code-tab:: c++ + .. code-block:: c++ // Calculates the output of the PID algorithm based on the sensor reading // and sends it to a motor @@ -72,9 +72,9 @@ Occasionally, it is useful to know if a controller has tracked the setpoint to w To do this, we first must specify the tolerances with the ``setTolerance()`` method; then, we can check it with the ``atSetpoint()`` method. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Sets the error tolerance to 5, and the error derivative tolerance to 10 per second pid.setTolerance(5, 10); @@ -83,7 +83,7 @@ To do this, we first must specify the tolerances with the ``setTolerance()`` met // error derivative is less than 10 units pid.atSetpoint(); - .. code-tab:: c++ + .. code-block:: c++ // Sets the error tolerance to 5, and the error derivative tolerance to 10 per second pid.SetTolerance(5, 10); @@ -108,15 +108,15 @@ By default, the total output contribution from the integral gain is limited to b The range limits may be increased or decreased using the ``setIntegratorRange()`` method. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // The integral gain term will never add or subtract more than 0.5 from // the total loop output pid.setIntegratorRange(-0.5, 0.5); - .. code-tab:: c++ + .. code-block:: c++ // The integral gain term will never add or subtract more than 0.5 from // the total loop output @@ -131,9 +131,9 @@ By default, ``IZone`` is disabled. ``IZone`` may be set using the ``setIZone()`` method. To disable it, set it to infinity. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Disable IZone pid.setIZone(Double.POSITIVE_INFINITY); @@ -142,7 +142,7 @@ By default, ``IZone`` is disabled. // more than 2 pid.setIZone(2); - .. code-tab:: c++ + .. code-block:: c++ // Disable IZone pid.SetIZone(std::numeric_limits::infinity()); @@ -162,14 +162,14 @@ Some process variables (such as the angle of a turret) are measured on a circula To configure a ``PIDController`` to automatically do this, use the ``enableContinuousInput()`` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Enables continuous input on a range from -180 to 180 pid.enableContinuousInput(-180, 180); - .. code-tab:: c++ + .. code-block:: c++ // Enables continuous input on a range from -180 to 180 pid.EnableContinuousInput(-180, 180); @@ -177,14 +177,14 @@ To configure a ``PIDController`` to automatically do this, use the ``enableConti Clamping Controller Output -------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Clamps the controller output to between -0.5 and 0.5 MathUtil.clamp(pid.calculate(encoder.getDistance(), setpoint), -0.5, 0.5); - .. code-tab:: c++ + .. code-block:: c++ // Clamps the controller output to between -0.5 and 0.5 std::clamp(pid.Calculate(encoder.GetDistance(), setpoint), -0.5, 0.5); diff --git a/source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst b/source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst index 0502a2a0f1..3a3b237471 100644 --- a/source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst +++ b/source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst @@ -22,9 +22,9 @@ Constructing a ProfiledPIDController Creating a ``ProfiledPIDController`` is nearly identical to :ref:`creating a PIDController `. The only difference is the need to supply a set of :ref:`trapezoidal profile constraints `, which will be automatically forwarded to the internally-generated ``TrapezoidProfile`` instances: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a ProfiledPIDController // Max velocity is 5 meters per second @@ -33,7 +33,7 @@ Creating a ``ProfiledPIDController`` is nearly identical to :ref:`creating a PID kP, kI, kD, new TrapezoidProfile.Constraints(5, 10)); - .. code-tab:: c++ + .. code-block:: c++ // Creates a ProfiledPIDController // Max velocity is 5 meters per second @@ -47,15 +47,15 @@ Goal vs Setpoint A major difference between a standard ``PIDController`` and a ``ProfiledPIDController`` is that the actual *setpoint* of the control loop is not directly specified by the user. Rather, the user specifies a *goal* position or state, and the setpoint for the controller is computed automatically from the generated motion profile between the current state and the goal. So, while the user-side call looks mostly identical: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Calculates the output of the PID algorithm based on the sensor reading // and sends it to a motor motor.set(controller.calculate(encoder.getDistance(), goal)); - .. code-tab:: c++ + .. code-block:: c++ // Calculates the output of the PID algorithm based on the sensor reading // and sends it to a motor @@ -70,9 +70,9 @@ Since the ``ProfiledPIDController`` goal differs from the setpoint, is if often The returned setpoint might then be used as in the following example: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java double lastSpeed = 0; double lastTime = Timer.getFPGATimestamp(); @@ -89,7 +89,7 @@ The returned setpoint might then be used as in the following example: lastTime = Timer.getFPGATimestamp(); } - .. code-tab:: c++ + .. code-block:: c++ units::meters_per_second_t lastSpeed = 0_mps; units::second_t lastTime = frc2::Timer::GetFPGATimestamp(); @@ -112,20 +112,18 @@ Complete Usage Example A more complete example of ``ProfiledPIDController`` usage is provided in the ElevatorProfilePID example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java - :language: java - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorprofiledpid/Robot.java + :language: java + :lines: 5- + :linenos: + :lineno-start: 5 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp - :language: c++ - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp + :language: c++ + :lines: 5- + :linenos: + :lineno-start: 5 diff --git a/source/docs/software/advanced-controls/controllers/trapezoidal-profiles.rst b/source/docs/software/advanced-controls/controllers/trapezoidal-profiles.rst index 0df1d24f31..0abeac8972 100644 --- a/source/docs/software/advanced-controls/controllers/trapezoidal-profiles.rst +++ b/source/docs/software/advanced-controls/controllers/trapezoidal-profiles.rst @@ -25,16 +25,16 @@ Constraints In order to create a trapezoidal motion profile, we must first impose some constraints on the desired motion. Namely, we must specify a maximum velocity and acceleration that the mechanism will be expected to achieve during the motion. To do this, we create an instance of the ``TrapezoidProfile.Constraints`` class (`Java `__, `C++ `__): -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a new set of trapezoidal motion profile constraints // Max velocity of 10 meters per second // Max acceleration of 20 meters per second squared new TrapezoidProfile.Constraints(10, 20); - .. code-tab:: c++ + .. code-block:: c++ // Creates a new set of trapezoidal motion profile constraints // Max velocity of 10 meters per second @@ -46,15 +46,15 @@ Start and End States Next, we must specify the desired starting and ending states for our mechanisms using the ``TrapezoidProfile.State`` class (`Java `__, `C++ `__). Each state has a position and a velocity: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a new state with a position of 5 meters // and a velocity of 0 meters per second new TrapezoidProfile.State(5, 0); - .. code-tab:: c++ + .. code-block:: c++ // Creates a new state with a position of 5 meters // and a velocity of 0 meters per second @@ -67,16 +67,16 @@ Putting It All Together Now that we know how to create a set of constraints and the desired start/end states, we are ready to create our motion profile. The ``TrapezoidProfile`` constructor takes 1 parameter: the constraints. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a new TrapezoidProfile // Profile will have a max vel of 5 meters per second // Profile will have a max acceleration of 10 meters per second squared TrapezoidProfile profile = new TrapezoidProfile(new TrapezoidProfile.Constraints(5, 10)); - .. code-tab:: c++ + .. code-block:: c++ // Creates a new TrapezoidProfile // Profile will have a max vel of 5 meters per second @@ -92,16 +92,16 @@ Sampling the Profile Once we've created a ``TrapezoidProfile``, using it is very simple: to get the profile state at the given time after the profile has started, call the ``calculate()`` method with the goal state and initial state: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Profile will end stationary at 5 meters // Profile will start stationary at zero position // Returns the motion profile state after 5 seconds of motion profile.calculate(5, new TrapezoidProfile.State(5, 0), new TrapezoidProfile.State(0, 0)); - .. code-tab:: c++ + .. code-block:: c++ // Profile will end stationary at 5 meters // Profile will start stationary at zero position @@ -115,14 +115,14 @@ Using the State The ``calculate`` method returns a ``TrapezoidProfile.State`` class (the same one that was used to specify the initial/end states when calculating the profile state). To use this for actual control, simply pass the contained position and velocity values to whatever controller you wish (for example, a PIDController): -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java var setpoint = profile.calculate(elapsedTime, goalState, initialState); controller.calculate(encoder.getDistance(), setpoint.position); - .. code-tab:: c++ + .. code-block:: c++ auto setpoint = profile.Calculate(elapsedTime, goalState, initialState); controller.Calculate(encoder.GetDistance(), setpoint.position.value()); @@ -134,20 +134,18 @@ Complete Usage Example A more complete example of ``TrapezoidProfile`` usage is provided in the ElevatorTrapezoidProfile example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java - :language: java - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatortrapezoidprofile/Robot.java + :language: java + :lines: 5- + :linenos: + :lineno-start: 5 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp - :language: c++ - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp + :language: c++ + :lines: 5- + :linenos: + :lineno-start: 5 diff --git a/source/docs/software/advanced-controls/filters/debouncer.rst b/source/docs/software/advanced-controls/filters/debouncer.rst index e747fe9f31..97066a3a59 100644 --- a/source/docs/software/advanced-controls/filters/debouncer.rst +++ b/source/docs/software/advanced-controls/filters/debouncer.rst @@ -17,9 +17,9 @@ The WPILib ``Debouncer`` can be configured in three different modes: Usage ----- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes a DigitalInput on DIO 0 DigitalInput input = new DigitalInput(0); @@ -32,7 +32,7 @@ Usage // Do something now that the DI is True. } - .. code-tab:: c++ + .. code-block:: c++ // Initializes a DigitalInput on DIO 0 frc::DigitalInput input{0}; diff --git a/source/docs/software/advanced-controls/filters/linear-filter.rst b/source/docs/software/advanced-controls/filters/linear-filter.rst index 363a8abad9..c506d52fdd 100644 --- a/source/docs/software/advanced-controls/filters/linear-filter.rst +++ b/source/docs/software/advanced-controls/filters/linear-filter.rst @@ -30,16 +30,16 @@ singlePoleIIR The ``singlePoleIIR()`` factory method creates a single-pole infinite impulse response filter which performs :term:`exponential smoothing`. This is the "go-to," "first-try" low-pass filter in most applications; it is computationally trivial and works in most cases. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a new Single-Pole IIR filter // Time constant is 0.1 seconds // Period is 0.02 seconds - this is the standard FRC main loop period LinearFilter filter = LinearFilter.singlePoleIIR(0.1, 0.02); - .. code-tab:: c++ + .. code-block:: c++ // Creates a new Single-Pole IIR filter // Time constant is 0.1 seconds @@ -58,15 +58,15 @@ movingAverage The ``movingAverage`` factory method creates a simple flat moving average filter. This is the simplest possible low-pass FIR filter, and is useful in many of the same contexts as the single-pole IIR filter. It is somewhat more costly to compute, but generally behaves in a somewhat nicer manner. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a new flat moving average filter // Average will be taken over the last 5 samples LinearFilter filter = LinearFilter.movingAverage(5); - .. code-tab:: c++ + .. code-block:: c++ // Creates a new flat moving average filter // Average will be taken over the last 5 samples @@ -82,16 +82,16 @@ highPass The ``highPass`` factory method creates a simple first-order infinite impulse response high-pass filter. This is the "counterpart" to the `singlePoleIIR`_. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a new high-pass IIR filter // Time constant is 0.1 seconds // Period is 0.02 seconds - this is the standard FRC main loop period LinearFilter filter = LinearFilter.highPass(0.1, 0.02); - .. code-tab:: c++ + .. code-block:: c++ // Creates a new high-pass IIR filter // Time constant is 0.1 seconds @@ -109,14 +109,14 @@ Using a LinearFilter Once your filter has been created, using it is easy - simply call the ``calculate()`` method with the most recent input to obtain the filtered output: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Calculates the next value of the output filter.calculate(input); - .. code-tab:: c++ + .. code-block:: c++ // Calculates the next value of the output filter.Calculate(input); diff --git a/source/docs/software/advanced-controls/filters/median-filter.rst b/source/docs/software/advanced-controls/filters/median-filter.rst index 342ac1addf..8392fbf656 100644 --- a/source/docs/software/advanced-controls/filters/median-filter.rst +++ b/source/docs/software/advanced-controls/filters/median-filter.rst @@ -19,14 +19,14 @@ Creating a MedianFilter Creating a ``MedianFilter`` is simple: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a MedianFilter with a window size of 5 samples MedianFilter filter = new MedianFilter(5); - .. code-tab:: c++ + .. code-block:: c++ // Creates a MedianFilter with a window size of 5 samples frc::MedianFilter filter(5); @@ -36,14 +36,14 @@ Using a MedianFilter Once your filter has been created, using it is easy - simply call the ``calculate()`` method with the most recent input to obtain the filtered output: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Calculates the next value of the output filter.calculate(input); - .. code-tab:: c++ + .. code-block:: c++ // Calculates the next value of the output filter.Calculate(input); diff --git a/source/docs/software/advanced-controls/filters/slew-rate-limiter.rst b/source/docs/software/advanced-controls/filters/slew-rate-limiter.rst index 6bfe58b4f0..f6876f9918 100644 --- a/source/docs/software/advanced-controls/filters/slew-rate-limiter.rst +++ b/source/docs/software/advanced-controls/filters/slew-rate-limiter.rst @@ -18,14 +18,14 @@ Creating a SlewRateLimiter Creating a SlewRateLimiter is simple: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates a SlewRateLimiter that limits the rate of change of the signal to 0.5 units per second SlewRateLimiter filter = new SlewRateLimiter(0.5); - .. code-tab:: c++ + .. code-block:: c++ // Creates a SlewRateLimiter that limits the rate of change of the signal to 0.5 volts per second frc::SlewRateLimiter filter{0.5_V / 1_s}; @@ -35,14 +35,14 @@ Using a SlewRateLimiter Once your filter has been created, using it is easy - simply call the ``calculate()`` method with the most recent input to obtain the filtered output: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Calculates the next value of the output filter.calculate(input); - .. code-tab:: c++ + .. code-block:: c++ // Calculates the next value of the output filter.Calculate(input); @@ -54,9 +54,9 @@ Using a SlewRateLimiter with DifferentialDrive A typical use of a SlewRateLimiter is to limit the acceleration of a robot's drive. This can be especially handy for robots that are very top-heavy, or that have very powerful drives. To do this, apply a SlewRateLimiter to a value passed into your robot drive function: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Ordinary call with no ramping applied drivetrain.arcadeDrive(forward, turn); @@ -64,7 +64,7 @@ A typical use of a SlewRateLimiter is to limit the acceleration of a robot's dri // Slew-rate limits the forward/backward input, limiting forward/backward acceleration drivetrain.arcadeDrive(filter.calculate(forward), turn); - .. code-tab:: c++ + .. code-block:: c++ // Ordinary call with no ramping applied drivetrain.ArcadeDrive(forward, turn); diff --git a/source/docs/software/advanced-controls/state-space/state-space-debugging.rst b/source/docs/software/advanced-controls/state-space/state-space-debugging.rst index 34a16bdf41..ffd0f2a26d 100644 --- a/source/docs/software/advanced-controls/state-space/state-space-debugging.rst +++ b/source/docs/software/advanced-controls/state-space/state-space-debugging.rst @@ -18,16 +18,16 @@ Reliable data of the :term:`system's ` :term:`state`\s, :term:`input`\s .. danger:: This will send extra data (at up to 100hz) over NetworkTables, which can cause lag with both user code and robot dashboards. This will also increase network utilization. It is often a good idea to disable this during competitions. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void robotPeriodic() { NetworkTableInstance.getDefault().flush(); } - .. code-tab:: c++ + .. code-block:: c++ void RobotPeriodic() { NetworkTableInstance::GetDefault().Flush(); diff --git a/source/docs/software/advanced-controls/state-space/state-space-flywheel-walkthrough.rst b/source/docs/software/advanced-controls/state-space/state-space-flywheel-walkthrough.rst index 68dde023aa..6ad88d9a5f 100644 --- a/source/docs/software/advanced-controls/state-space/state-space-flywheel-walkthrough.rst +++ b/source/docs/software/advanced-controls/state-space/state-space-flywheel-walkthrough.rst @@ -65,9 +65,9 @@ The second part of state-space notation relates the system's current :term:`stat The ``LinearSystem`` class contains methods for easily creating state-space systems identified using :term:`system identification`. This example shows a flywheel model with a kV of 0.023 and a kA of 0.001: -.. tabs:: - - .. group-tab:: Java +.. tab-set:: + .. tab-item:: JAVA + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheelsysid/Robot.java :language: java @@ -75,19 +75,22 @@ The ``LinearSystem`` class contains methods for easily creating state-space syst :linenos: :lineno-start: 33 - .. group-tab:: C++ + + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp :language: cpp - :lines: 17-17 - :linenos: + :lines: 17 + :linenos: :lineno-start: 17 .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp :language: cpp :lines: 30-46 - :linenos: - :lineno-start: 32 + :linenos: + :lineno-start: 30 + Modeling Using Flywheel Moment of Inertia and Gearing ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ @@ -100,9 +103,10 @@ The ``LinearSystem`` class contains methods to easily create a model of a flywhe .. note:: The C++ LinearSystem class uses :ref:`the C++ Units Library ` to prevent unit mixups and assert dimensionality. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: JAVA + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java :language: java @@ -110,7 +114,8 @@ The ``LinearSystem`` class contains methods to easily create a model of a flywhe :linenos: :lineno-start: 34 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp :language: cpp @@ -120,7 +125,7 @@ The ``LinearSystem`` class contains methods to easily create a model of a flywhe .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp :language: cpp - :lines: 31-46 + :lines: 17,31-46 :linenos: :lineno-start: 31 @@ -138,9 +143,10 @@ The above graph shows two differently tuned Kalman filters, as well as a :ref:`s Because the feedback controller computes error using the :term:`x-hat` estimated by the Kalman filter, the controller will react to disturbances only as quickly the filter's state estimate changes. In the above chart, the upper left plot (with a state standard deviation of 3.0 and measurement standard deviation of 0.2) produced a filter that reacted quickly to disturbances while rejecting noise, while the upper right plot shows a filter that was barely affected by the velocity dips. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: JAVA + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java :language: java @@ -148,7 +154,8 @@ Because the feedback controller computes error using the :term:`x-hat` estimated :linenos: :lineno-start: 59 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp :language: cpp @@ -173,9 +180,10 @@ Linear-Quadratic Regulators and Plant Inversion Feedforward Much like ``SimpleMotorFeedforward`` can be used to generate feedforward voltage inputs given kS, kV, and kA constants, the Plant Inversion Feedforward class generate :ref:`feedforward ` voltage inputs given a state-space system. The voltage commands generated by the ``LinearSystemLoop`` class are the sum of the feedforward and feedback inputs. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: JAVA + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java :language: java @@ -183,7 +191,8 @@ Much like ``SimpleMotorFeedforward`` can be used to generate feedforward voltage :linenos: :lineno-start: 60 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp :language: cpp @@ -202,9 +211,10 @@ Bringing it All Together: LinearSystemLoop LinearSystemLoop combines our system, controller, and observer that we created earlier. The constructor shown will also instantiate a ``PlantInversionFeedforward``. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: JAVA + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java :language: java @@ -212,7 +222,8 @@ LinearSystemLoop combines our system, controller, and observer that we created e :linenos: :lineno-start: 73 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp :language: cpp @@ -228,9 +239,10 @@ LinearSystemLoop combines our system, controller, and observer that we created e Once we have our ``LinearSystemLoop``, the only thing left to do is actually run it. To do that, we'll periodically update our Kalman filter with our new encoder velocity measurements and apply new voltage commands to it. To do that, we first set the :term:`reference`, then ``correct`` with the current flywheel speed, ``predict`` the Kalman filter into the next timestep, and apply the inputs generated using ``getU``. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: JAVA + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java :language: java @@ -238,7 +250,8 @@ Once we have our ``LinearSystemLoop``, the only thing left to do is actually run :linenos: :lineno-start: 96 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp :language: cpp @@ -257,20 +270,16 @@ Angle Wrap with LQR Mechanisms with a continuous angle can have that angle wrapped by calling the code below instead of ``lqr.Calculate(x, r)``. -.. tabs:: - - .. group-tab:: Java - - .. code-block:: Java +.. tab-set-code:: - var error = lqr.getR().minus(x); - error.set(0, 0, MathUtil.angleModulus(error.get(0, 0))); - var u = lqr.getK().times(error); + .. code-block:: java - .. group-tab:: C++ + var error = lqr.getR().minus(x); + error.set(0, 0, MathUtil.angleModulus(error.get(0, 0))); + var u = lqr.getK().times(error); - .. code-block:: C++ + .. code-block:: cpp - Eigen::Vector error = lqr.R() - x; - error(0) = frc::AngleModulus(units::radian_t{error(0)}).value(); - Eigen::Vector u = lqr.K() * error; + Eigen::Vector error = lqr.R() - x; + error(0) = frc::AngleModulus(units::radian_t{error(0)}).value(); + Eigen::Vector u = lqr.K() * error; diff --git a/source/docs/software/advanced-controls/state-space/state-space-intro.rst b/source/docs/software/advanced-controls/state-space/state-space-intro.rst index 243fe07f06..a943e30dc0 100644 --- a/source/docs/software/advanced-controls/state-space/state-space-intro.rst +++ b/source/docs/software/advanced-controls/state-space/state-space-intro.rst @@ -170,36 +170,34 @@ Similarly, decreasing the :math:`\mathbf{q}` elements would make the LQR penaliz For example, we might use the following Q and R for an elevator system with position and velocity states. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. code-block:: Java + .. code-block:: Java - // Example system -- must be changed to match your robot. - LinearSystem elevatorSystem = LinearSystemId.identifyPositionSystem(5, 0.5); - LinearQuadraticRegulator controller = new LinearQuadraticRegulator(elevatorSystem, - // q's elements - VecBuilder.fill(0.02, 0.4), - // r's elements - VecBuilder.fill(12.0), - // our dt - 0.020); + // Example system -- must be changed to match your robot. + LinearSystem elevatorSystem = LinearSystemId.identifyPositionSystem(5, 0.5); + LinearQuadraticRegulator controller = new LinearQuadraticRegulator(elevatorSystem, + // q's elements + VecBuilder.fill(0.02, 0.4), + // r's elements + VecBuilder.fill(12.0), + // our dt + 0.020); - .. group-tab:: C++ - .. code-block:: C++ + .. code-block:: C++ - // Example system -- must be changed to match your robot. - LinearSystem<2, 1, 1> elevatorSystem = frc::LinearSystemId::IdentifyVelocitySystem(5, 0.5); - LinearQuadraticRegulator<2, 1> controller{ - elevatorSystem, - // q's elements - {0.02, 0.4}, - // r's elements - {12.0}, - // our dt - 0.020_s}; + // Example system -- must be changed to match your robot. + LinearSystem<2, 1, 1> elevatorSystem = frc::LinearSystemId::IdentifyVelocitySystem(5, 0.5); + LinearQuadraticRegulator<2, 1> controller{ + elevatorSystem, + // q's elements + {0.02, 0.4}, + // r's elements + {12.0}, + // our dt + 0.020_s}; LQR: example application ^^^^^^^^^^^^^^^^^^^^^^^^ @@ -241,15 +239,15 @@ Multiplying :math:`\mathbf{K}` by :math:`\mathbf{A} - \mathbf{BK}` essentially a The code below shows how to adjust the LQR controller's K gain for sensor input delays: -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java // Adjust our LQR's controller for 25 ms of sensor input delay. We // provide the linear system, discretization timestep, and the sensor // input delay as arguments. controller.latencyCompensate(elevatorSystem, 0.02, 0.025); - .. code-tab:: c++ + .. code-block:: c++ // Adjust our LQR's controller for 25 ms of sensor input delay. We // provide the linear system, discretization timestep, and the sensor diff --git a/source/docs/software/advanced-controls/state-space/state-space-observers.rst b/source/docs/software/advanced-controls/state-space/state-space-observers.rst index b0f96a7168..8edeb056e5 100644 --- a/source/docs/software/advanced-controls/state-space/state-space-observers.rst +++ b/source/docs/software/advanced-controls/state-space/state-space-observers.rst @@ -96,9 +96,8 @@ Tuning Kalman Filters WPILib's Kalman Filter classes' constructors take a linear system, a vector of process noise standard deviations and measurement noise standard deviations. These are converted to :math:`\mathbf{Q}` and :math:`\mathbf{R}` matrices by filling the diagonals with the square of the standard deviations, or variances, of each state or measurement. By decreasing a state's standard deviation (and therefore its corresponding entry in :math:`\mathbf{Q}`), the filter will distrust incoming measurements more. Similarly, increasing a state's standard deviation will trust incoming measurements more. The same holds for the measurement standard deviations -- decreasing an entry will make the filter more highly trust the incoming measurement for the corresponding state, while increasing it will decrease trust in the measurement. -.. tabs:: - - .. group-tab:: Java +.. tab-set:: + .. tab-item:: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java :language: java @@ -106,7 +105,7 @@ WPILib's Kalman Filter classes' constructors take a linear system, a vector of p :linenos: :lineno-start: 49 - .. group-tab:: C++ + .. tab-item:: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp :language: cpp diff --git a/source/docs/software/advanced-controls/state-space/state-space-pose-estimators.rst b/source/docs/software/advanced-controls/state-space/state-space-pose-estimators.rst index c2a4329765..61c49b6146 100644 --- a/source/docs/software/advanced-controls/state-space/state-space-pose-estimators.rst +++ b/source/docs/software/advanced-controls/state-space/state-space-pose-estimators.rst @@ -7,63 +7,57 @@ Pose estimators estimate robot position using a state-space system with the stat Here's how to initialize a ``DifferentialDrivePoseEstimator``: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java - :language: java - :lines: 87-95 - :linenos: - :lineno-start: 87 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java + :language: java + :lines: 87-95 + :linenos: + :lineno-start: 87 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h - :language: c++ - :lines: 158-165 - :linenos: - :lineno-start: 158 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.h + :language: c++ + :lines: 158-165 + :linenos: + :lineno-start: 158 Add odometry measurements every loop by calling ``Update()``. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java - :language: java - :lines: 234-235 - :linenos: - :lineno-start: 234 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java + :language: java + :lines: 234-235 + :linenos: + :lineno-start: 234 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp - :language: c++ - :lines: 84-86 - :linenos: - :lineno-start: 84 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp + :language: c++ + :lines: 84-86 + :linenos: + :lineno-start: 84 Add vision pose measurements occasionally by calling ``AddVisionMeasurement()``. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java - :language: java - :lines: 243-252 - :linenos: - :lineno-start: 243 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/differentialdriveposeestimator/Drivetrain.java + :language: java + :lines: 243-252 + :linenos: + :lineno-start: 243 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp - :language: c++ - :lines: 93-106 - :linenos: - :lineno-start: 93 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp + :language: c++ + :lines: 93-106 + :linenos: + :lineno-start: 93 Tuning Pose Estimators ---------------------- diff --git a/source/docs/software/advanced-controls/trajectories/constraints.rst b/source/docs/software/advanced-controls/trajectories/constraints.rst index 7423d2b0d9..a638f7a8eb 100644 --- a/source/docs/software/advanced-controls/trajectories/constraints.rst +++ b/source/docs/software/advanced-controls/trajectories/constraints.rst @@ -23,9 +23,9 @@ Creating a Custom Constraint ---------------------------- Users can create their own constraint by implementing the ``TrajectoryConstraint`` interface. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public double getMaxVelocityMetersPerSecond(Pose2d poseMeters, double curvatureRadPerMeter, @@ -40,7 +40,7 @@ Users can create their own constraint by implementing the ``TrajectoryConstraint // code here } - .. code-tab:: c++ + .. code-block:: c++ units::meters_per_second_t MaxVelocity( const Pose2d& pose, units::curvature_t curvature, diff --git a/source/docs/software/advanced-controls/trajectories/holonomic.rst b/source/docs/software/advanced-controls/trajectories/holonomic.rst index 842729aed3..4ac38b8a0c 100644 --- a/source/docs/software/advanced-controls/trajectories/holonomic.rst +++ b/source/docs/software/advanced-controls/trajectories/holonomic.rst @@ -12,8 +12,8 @@ The 2 PID controllers are controllers that should correct for error in the field The final parameter is a ``ProfiledPIDController`` for the rotation of the robot. Because the rotation dynamics of a holonomic drivetrain are decoupled from movement in the x and y directions, users can set custom heading references while following a trajectory. These heading references are profiled according to the parameters set in the ``ProfiledPIDController``. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java var controller = new HolonomicDriveController( new PIDController(1, 0, 0), new PIDController(1, 0, 0), @@ -23,7 +23,7 @@ The final parameter is a ``ProfiledPIDController`` for the rotation of the robot // of 1 rotation per second and a max acceleration of 180 degrees // per second squared. - .. code-tab:: c++ + .. code-block:: c++ frc::HolonomicDriveController controller{ frc::PIDController{1, 0, 0}, frc::PIDController{1, 0, 0}, @@ -42,8 +42,8 @@ The holonomic drive controller returns "adjusted velocities" such that when the The controller can be updated using the ``Calculate`` (C++) / ``calculate`` (Java) method. There are two overloads for this method. Both of these overloads accept the current robot position as the first parameter and the desired heading as the last parameter. For the middle parameters, one overload accepts the desired pose and the linear velocity reference while the other accepts a ``Trajectory.State`` object, which contains information about the goal pose. The latter method is preferred for tracking trajectories. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java // Sample the trajectory at 3.4 seconds from the beginning. Trajectory.State goal = trajectory.sample(3.4); @@ -53,7 +53,7 @@ The controller can be updated using the ``Calculate`` (C++) / ``calculate`` (Jav ChassisSpeeds adjustedSpeeds = controller.calculate( currentRobotPose, goal, Rotation2d.fromDegrees(70.0)); - .. code-tab:: c++ + .. code-block:: c++ // Sample the trajectoty at 3.4 seconds from the beginning. const auto goal = trajectory.Sample(3.4_s); @@ -69,8 +69,8 @@ The adjusted velocities are of type ``ChassisSpeeds``, which contains a ``vx`` ( The returned adjusted speeds can be converted into usable speeds using the kinematics classes for your drivetrain type. In the example code below, we will assume a swerve drive robot; however, the kinematics code is exactly the same for a mecanum drive robot except using ``MecanumDriveKinematics``. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(adjustedSpeeds); @@ -79,7 +79,7 @@ The returned adjusted speeds can be converted into usable speeds using the kinem SwerveModuleState backLeft = moduleStates[2]; SwerveModuleState backRight = moduleStates[3]; - .. code-tab:: c++ + .. code-block:: c++ auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(adjustedSpeeds); diff --git a/source/docs/software/advanced-controls/trajectories/manipulating-trajectories.rst b/source/docs/software/advanced-controls/trajectories/manipulating-trajectories.rst index 83344eda4b..a673e19f6d 100644 --- a/source/docs/software/advanced-controls/trajectories/manipulating-trajectories.rst +++ b/source/docs/software/advanced-controls/trajectories/manipulating-trajectories.rst @@ -7,14 +7,14 @@ Getting the total duration of the trajectory Because all trajectories have timestamps at each point, the amount of time it should take for a robot to traverse the entire trajectory is pre-determined. The ``TotalTime()`` (C++) / ``getTotalTimeSeconds()`` (Java) method can be used to determine the time it takes to traverse the trajectory. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Get the total time of the trajectory in seconds double duration = trajectory.getTotalTimeSeconds(); - .. code-tab:: c++ + .. code-block:: c++ // Get the total time of the trajectory units::second_t duration = trajectory.TotalTime(); @@ -23,15 +23,15 @@ Sampling the trajectory ----------------------- The trajectory can be sampled at various timesteps to get the pose, velocity, and acceleration at that point. The ``Sample(units::second_t time)`` (C++) / ``sample(double timeSeconds)`` (Java) method can be used to sample the trajectory at any timestep. The parameter refers to the amount of time passed since 0 seconds (the starting point of the trajectory). This method returns a ``Trajectory::Sample`` with information about that sample point. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Sample the trajectory at 1.2 seconds. This represents where the robot // should be after 1.2 seconds of traversal. Trajectory.Sample point = trajectory.sample(1.2); - .. code-tab:: c++ + .. code-block:: c++ // Sample the trajectory at 1.2 seconds. This represents where the robot // should be after 1.2 seconds of traversal. diff --git a/source/docs/software/advanced-controls/trajectories/ramsete.rst b/source/docs/software/advanced-controls/trajectories/ramsete.rst index e623ab1727..a715e49a09 100644 --- a/source/docs/software/advanced-controls/trajectories/ramsete.rst +++ b/source/docs/software/advanced-controls/trajectories/ramsete.rst @@ -8,8 +8,8 @@ The Ramsete controller should be initialized with two gains, namely ``b`` and `` .. note:: Gains of ``2.0`` and ``0.7`` for ``b`` and ``zeta`` have been tested repeatedly to produce desirable results when all units were in meters. As such, a zero-argument constructor for ``RamseteController`` exists with gains defaulted to these values. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java // Using the default constructor of RamseteController. Here // the gains are initialized to 2.0 and 0.7. @@ -19,7 +19,7 @@ The Ramsete controller should be initialized with two gains, namely ``b`` and `` // the user can choose any other gains. RamseteController controller2 = new RamseteController(2.1, 0.8); - .. code-tab:: c++ + .. code-block:: c++ // Using the default constructor of RamseteController. Here // the gains are initialized to 2.0 and 0.7. @@ -37,15 +37,15 @@ The Ramsete controller returns "adjusted velocities" so that the when the robot The controller can be updated using the ``Calculate`` (C++) / ``calculate`` (Java) method. There are two overloads for this method. Both of these overloads accept the current robot position as the first parameter. For the other parameters, one of these overloads takes in the goal as three separate parameters (pose, linear velocity, and angular velocity) whereas the other overload accepts a ``Trajectory.State`` object, which contains information about the goal pose. For its ease, users should use the latter method when tracking trajectories. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Trajectory.State goal = trajectory.sample(3.4); // sample the trajectory at 3.4 seconds from the beginning ChassisSpeeds adjustedSpeeds = controller.calculate(currentRobotPose, goal); - .. code-tab:: c++ + .. code-block:: c++ const Trajectory::State goal = trajectory.Sample(3.4_s); // sample the trajectory at 3.4 seconds from the beginning ChassisSpeeds adjustedSpeeds = controller.Calculate(currentRobotPose, goal); @@ -58,16 +58,16 @@ The adjusted velocities are of type ``ChassisSpeeds``, which contains a ``vx`` ( The returned adjusted speeds can be converted to usable speeds using the kinematics classes for your drivetrain type. For example, the adjusted velocities can be converted to left and right velocities for a differential drive using a ``DifferentialDriveKinematics`` object. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java ChassisSpeeds adjustedSpeeds = controller.calculate(currentRobotPose, goal); DifferentialDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(adjustedSpeeds); double left = wheelSpeeds.leftMetersPerSecond; double right = wheelSpeeds.rightMetersPerSecond; - .. code-tab:: cpp + .. code-block:: cpp ChassisSpeeds adjustedSpeeds = controller.Calculate(currentRobotPose, goal); DifferentialDriveWheelSpeeds wheelSpeeds = kinematics.ToWheelSpeeds(adjustedSpeeds); diff --git a/source/docs/software/advanced-controls/trajectories/trajectory-generation.rst b/source/docs/software/advanced-controls/trajectories/trajectory-generation.rst index fee038136f..ba2199d687 100644 --- a/source/docs/software/advanced-controls/trajectories/trajectory-generation.rst +++ b/source/docs/software/advanced-controls/trajectories/trajectory-generation.rst @@ -45,15 +45,15 @@ When using clamped cubic splines, the length of the array must be 2 (0th and 1st Here is an example of generating a trajectory using clamped cubic splines for the 2018 game, FIRST Power Up: -.. tabs:: +.. tab-set:: - .. tab:: Java + .. tab-item:: Java .. literalinclude:: examples/trajectory-generation-1/java/ExampleTrajectory.java :language: java :lines: 10-32 - .. tab:: C++ + .. tab-item:: C++ .. literalinclude:: examples/trajectory-generation-1/cpp/ExampleTrajectory.cpp :language: cpp @@ -70,9 +70,9 @@ Trajectories in Java can be combined into a single trajectory using the ``concat .. warning:: It is up to the user to ensure that the end of the initial and start of the appended trajectory match. It is also the user's responsibility to ensure that the start and end velocities of their trajectories match. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java var trajectoryOne = TrajectoryGenerator.generateTrajectory( @@ -90,7 +90,7 @@ Trajectories in Java can be combined into a single trajectory using the ``concat var concatTraj = trajectoryOne.concatenate(trajectoryTwo); - .. code-tab:: cpp + .. code-block:: cpp auto trajectoryOne = frc::TrajectoryGenerator::GenerateTrajectory( frc::Pose2d(0_m, 0_m, 0_rad), diff --git a/source/docs/software/advanced-controls/trajectories/transforming-trajectories.rst b/source/docs/software/advanced-controls/trajectories/transforming-trajectories.rst index 6cbcaf5960..38b8d46bed 100644 --- a/source/docs/software/advanced-controls/trajectories/transforming-trajectories.rst +++ b/source/docs/software/advanced-controls/trajectories/transforming-trajectories.rst @@ -12,14 +12,14 @@ The ``relativeTo`` method is used to redefine an already existing trajectory in For example, a trajectory defined in coordinate system A can be redefined in coordinate system B, whose origin is at (3, 3, 30 degrees) in coordinate system A, using the ``relativeTo`` method. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Pose2d bOrigin = new Pose2d(3, 3, Rotation2d.fromDegrees(30)); Trajectory bTrajectory = aTrajectory.relativeTo(bOrigin); - .. code-tab:: c++ + .. code-block:: c++ frc::Pose2d bOrigin{3_m, 3_m, frc::Rotation2d(30_deg)}; frc::Trajectory bTrajectory = aTrajectory.RelativeTo(bOrigin); @@ -36,14 +36,14 @@ The ``transformBy`` method can be used to move (i.e. translate and rotate) a tra For example, one may want to transform a trajectory that begins at (2, 2, 30 degrees) to make it begin at (4, 4, 50 degrees) using the ``transformBy`` method. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Transform2d transform = new Pose2d(4, 4, Rotation2d.fromDegrees(50)).minus(trajectory.getInitialPose()); Trajectory newTrajectory = trajectory.transformBy(transform); - .. code-tab:: c++ + .. code-block:: c++ frc::Transform2d transform = Pose2d(4_m, 4_m, Rotation2d(50_deg)) - trajectory.InitialPose(); frc::Trajectory newTrajectory = trajectory.TransformBy(transform); diff --git a/source/docs/software/advanced-controls/trajectories/troubleshooting.rst b/source/docs/software/advanced-controls/trajectories/troubleshooting.rst index eeaa00fe9d..f69d45b97a 100644 --- a/source/docs/software/advanced-controls/trajectories/troubleshooting.rst +++ b/source/docs/software/advanced-controls/trajectories/troubleshooting.rst @@ -60,9 +60,9 @@ If your odometry is bad, then your Ramsete controller may misbehave, because it 1. Set up your code to record your robot's position after each odometry update: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java NetworkTableEntry m_xEntry = NetworkTableInstance.getDefault().getTable("troubleshooting").getEntry("X"); NetworkTableEntry m_yEntry = NetworkTableInstance.getDefault().getTable("troubleshooting").getEntry("Y"); @@ -78,7 +78,7 @@ If your odometry is bad, then your Ramsete controller may misbehave, because it m_yEntry.setNumber(translation.getY()); } - .. code-tab:: c++ + .. code-block:: c++ NetworkTableEntry m_xEntry = nt::NetworkTableInstance::GetDefault().GetTable("troubleshooting")->GetEntry("X"); NetworkTableEntry m_yEntry = nt::NetworkTableInstance::GetDefault().GetTable("troubleshooting")->GetEntry("Y"); @@ -107,29 +107,27 @@ If your feedforwards are bad then the P controllers for each side of the robot w 1. First, we must set disable the P controller for each wheel. Set the ``P`` gain to 0 for every controller. In the ``RamseteCommand`` example, you would set ``kPDriveVel`` to 0: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java - :language: java - :lines: 123-124 - :linenos: - :lineno-start: 123 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java + :language: java + :lines: 123-124 + :linenos: + :lineno-start: 123 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp - :language: c++ - :lines: 79-80 - :linenos: - :lineno-start: 81 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp + :language: c++ + :lines: 79-80 + :linenos: + :lineno-start: 81 -2. Next, we want to disable the Ramsete controller to make it easier to isolate our problematic behavior. To do so, simply call ``setEnabled(false)`` on the ``RamseteController`` passed into your ``RamseteCommand``: +1. Next, we want to disable the Ramsete controller to make it easier to isolate our problematic behavior. To do so, simply call ``setEnabled(false)`` on the ``RamseteController`` passed into your ``RamseteCommand``: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java RamseteController m_disabledRamsete = new RamseteController(); m_disabledRamsete.setEnabled(false); @@ -142,7 +140,7 @@ If your feedforwards are bad then the P controllers for each side of the robot w ... ); - .. code-tab:: c++ + .. code-block:: c++ frc::RamseteController m_disabledRamsete; m_disabledRamsete.SetEnabled(false); @@ -157,9 +155,9 @@ If your feedforwards are bad then the P controllers for each side of the robot w 3. Finally, we need to log desired wheel velocity and actual wheel velocity (you should put actual and desired velocities on the same graph if you're using Shuffleboard, or if your graphing software has that capability): -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java var table = NetworkTableInstance.getDefault().getTable("troubleshooting"); var leftReference = table.getEntry("left_reference"); @@ -191,7 +189,7 @@ If your feedforwards are bad then the P controllers for each side of the robot w m_robotDrive ); - .. code-tab:: c++ + .. code-block:: c++ auto table = nt::NetworkTableInstance::GetDefault().GetTable("troubleshooting"); diff --git a/source/docs/software/basic-programming/git-getting-started.rst b/source/docs/software/basic-programming/git-getting-started.rst index 7d145e57a5..0caf0a6347 100644 --- a/source/docs/software/basic-programming/git-getting-started.rst +++ b/source/docs/software/basic-programming/git-getting-started.rst @@ -104,9 +104,9 @@ If a directory is empty, a file needs to be created in order for git to have som .. note:: Replace the filepath ``"C:\Users\ExampleUser9007\Documents\Example Folder"`` with the one you want to create the repo in, and replace the remote URL ``https://github.com/ExampleUser9007/ExampleRepo.git`` with the URL for the repo you created in the previous steps. -.. tabs:: +.. tab-set:: - .. tab:: Empty Directory + .. tab-item:: Empty Directory .. code-block:: console @@ -122,7 +122,7 @@ If a directory is empty, a file needs to be created in order for git to have som > git remote add origin https://github.com/ExampleUser9007/ExampleRepo.git > git push -u origin main - .. tab:: Existing Project + .. tab-item:: Existing Project .. code-block:: console diff --git a/source/docs/software/basic-programming/joystick.rst b/source/docs/software/basic-programming/joystick.rst index 8b8ffff17b..18207444cf 100644 --- a/source/docs/software/basic-programming/joystick.rst +++ b/source/docs/software/basic-programming/joystick.rst @@ -33,17 +33,17 @@ When the robot is connected to the Field Management System at competition, the D :alt: A Logitech flight stick with an explanation of the axis values and buttons. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Joystick exampleJoystick = new Joystick(0); // 0 is the USB Port to be used as indicated on the Driver Station - .. code-tab:: c++ + .. code-block:: c++ Joystick exampleJoystick{0}; // 0 is the USB Port to be used as indicated on the Driver Station - .. code-tab:: python + .. code-block:: python exampleJoystick = wpilib.Joystick(0) # 0 is the USB Port to be used as indicated on the Driver Station @@ -55,17 +55,17 @@ The ``Joystick`` class is designed to make using a flight joystick to operate th .. image:: images/joystick/xbox.jpg :alt: Original Xbox Controller. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java XboxController exampleXbox = new XboxController(0); // 0 is the USB Port to be used as indicated on the Driver Station - .. code-tab:: c++ + .. code-block:: c++ XboxController exampleXbox{0}; // 0 is the USB Port to be used as indicated on the Driver Station - .. code-tab:: python + .. code-block:: python exampleXbox = wpilib.XboxController(0) # 0 is the USB Port to be used as indicated on the Driver Station @@ -78,17 +78,17 @@ The ``XboxController`` class provides named methods (e.g. ``getXButton``, ``getX :alt: PlayStation 4 controller. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java PS4Controller examplePS4 = new PS4Controller(0); // 0 is the USB Port to be used as indicated on the Driver Station - .. code-tab:: c++ + .. code-block:: c++ PS4Controller examplePS4{0}; // 0 is the USB Port to be used as indicated on the Driver Station - .. code-tab:: python + .. code-block:: python examplePS4 = wpilib.PS4Controller(0) # 0 is the USB Port to be used as indicated on the Driver Station @@ -108,9 +108,9 @@ On joysticks, the POV is a directional hat that can select one of 8 different an An axis can be used with ``.getRawAxis(int index)`` (if not using any of the classes above) that returns the current value. Zero and one in this example are each the index of an axis as found in the Driver Station mentioned above. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java private final PWMSparkMax m_leftMotor = new PWMSparkMax(Constants.kLeftMotorPort); private final PWMSparkMax m_rightMotor = new PWMSparkMax(Constants.kRightMotorPort); @@ -119,7 +119,7 @@ An axis can be used with ``.getRawAxis(int index)`` (if not using any of the cla m_robotDrive.arcadeDrive(-m_stick.getRawAxis(0), m_stick.getRawAxis(1)); - .. code-tab:: c++ + .. code-block:: c++ frc::PWMVictorSPX m_leftMotor{Constants::kLeftMotorPort}; frc::PWMVictorSPX m_rightMotor{Constants::kRightMotorPort}; @@ -128,7 +128,7 @@ An axis can be used with ``.getRawAxis(int index)`` (if not using any of the cla m_robotDrive.ArcadeDrive(-m_stick.GetRawAxis(0), m_stick.GetRawAxis(1)); - .. code-tab:: python + .. code-block:: python leftMotor = wpilib.PWMVictorSPX(LEFT_MOTOR_PORT) rightMotor = wpilib.PWMVictorSPX(RIGHT_MOTOR_PORT) @@ -145,9 +145,9 @@ Button Usage Unlike an axis, you will usually want to use the ``pressed`` and ``released`` methods to respond to button input. These will return true if the button has been activated since the last check. This is helpful for taking an action once when the event occurs but not having to continuously do it while the button is held down. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java if (joystick.getRawButtonPressed(0)) { turnIntakeOn(); // When pressed the intake turns on @@ -164,7 +164,7 @@ Unlike an axis, you will usually want to use the ``pressed`` and ``released`` me turnIntakeOff(); } - .. code-tab:: c++ + .. code-block:: c++ if (joystick.GetRawButtonPressed(0)) { turnIntakeOn(); // When pressed the intake turns on @@ -181,7 +181,7 @@ Unlike an axis, you will usually want to use the ``pressed`` and ``released`` me turnIntakeOff(); } - .. code-tab:: python + .. code-block:: python if joystick.getRawButtonPressed(0): turnIntakeOn() # When pressed the intake turns on @@ -198,9 +198,9 @@ Unlike an axis, you will usually want to use the ``pressed`` and ``released`` me A common request is to toggle something on and off with the press of a button. Toggles should be used with caution, as they require the user to keep track of the robot state. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java boolean toggle = false; @@ -216,7 +216,7 @@ A common request is to toggle something on and off with the press of a button. } } - .. code-tab:: c++ + .. code-block:: c++ bool toggle{false}; @@ -232,7 +232,7 @@ A common request is to toggle something on and off with the press of a button. } } - .. code-tab:: python + .. code-block:: python toggle = False diff --git a/source/docs/software/basic-programming/reading-stacktraces.rst b/source/docs/software/basic-programming/reading-stacktraces.rst index 2c7f37f45c..21f820171c 100644 --- a/source/docs/software/basic-programming/reading-stacktraces.rst +++ b/source/docs/software/basic-programming/reading-stacktraces.rst @@ -33,9 +33,9 @@ Read the Stack Trace To start, search above the ``unexpected error has occurred`` for the stack trace. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java In Java, it should look something like this: @@ -83,7 +83,7 @@ To start, search above the ``unexpected error has occurred`` for the stack trace In this case: ``robotInit`` called ``fooInit``, which in turn called ``barInit``, which in turn called ``buggyMethod``. Then, during the execution of ``buggyMethod``, the ``NullPointerException`` occurred. - .. group-tab:: C++ + .. tab-item:: C++ Java will usually produce stack traces automatically when programs run into issues. C++ will require more digging to extract the same info. Usually, a single-step debugger will need to be hooked up to the executing robot program. @@ -166,42 +166,41 @@ Manipulating a "null" reference will produce a runtime error. For example, consider the following code: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. code-block:: Java - :lineno-start: 19 + .. code-block:: Java + :lineno-start: 19 - PWMSparkMax armMotorCtrl; + PWMSparkMax armMotorCtrl; - @Override - public void robotInit() { - armMotorCtrl.setInverted(true); - } + @Override + public void robotInit() { + armMotorCtrl.setInverted(true); + } - .. group-tab:: C++ - .. code-block:: C++ - :lineno-start: 17 + .. code-block:: C++ + :lineno-start: 17 - class Robot : public frc::TimedRobot { - public: - void RobotInit() override { - motorRef->SetInverted(false); - } + class Robot : public frc::TimedRobot { + public: + void RobotInit() override { + motorRef->SetInverted(false); + } - private: - frc::PWMVictorSPX m_armMotor{0}; - frc::PWMVictorSPX* motorRef; - }; + private: + frc::PWMVictorSPX m_armMotor{0}; + frc::PWMVictorSPX* motorRef; + }; When run, you'll see output that looks like this: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java .. code-block:: text @@ -225,7 +224,8 @@ When run, you'll see output that looks like this: Alternatively, you can step through lines of code with the single step debugger, and stop when you hit line 23. Inspecting the ``armMotorCtrl`` object at that point would show that it is null. - .. group-tab:: C++ + .. tab-item:: C++ + :sync: tabcode-c++ .. code-block:: text @@ -251,37 +251,35 @@ Generally, you will want to ensure each reference has been initialized before us A functional implementation could look like this: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. code-block:: Java - :lineno-start: 19 + .. code-block:: Java + :lineno-start: 19 - PWMSparkMax armMotorCtrl; + PWMSparkMax armMotorCtrl; - @Override - public void robotInit() { - armMotorCtrl = new PWMSparkMax(0); - armMotorCtrl.setInverted(true); - } + @Override + public void robotInit() { + armMotorCtrl = new PWMSparkMax(0); + armMotorCtrl.setInverted(true); + } - .. group-tab:: C++ - .. code-block:: C++ - :lineno-start: 17 + .. code-block:: C++ + :lineno-start: 17 - class Robot : public frc::TimedRobot { - public: - void RobotInit() override { - motorRef = &m_armMotor; - motorRef->SetInverted(false); - } + class Robot : public frc::TimedRobot { + public: + void RobotInit() override { + motorRef = &m_armMotor; + motorRef->SetInverted(false); + } - private: - frc::PWMVictorSPX m_armMotor{0}; - frc::PWMVictorSPX* motorRef; - }; + private: + frc::PWMVictorSPX m_armMotor{0}; + frc::PWMVictorSPX* motorRef; + }; @@ -292,47 +290,47 @@ It is not generally possible to divide an integer by zero, and expect reasonable For example, consider the following code: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. code-block:: Java - :lineno-start: 18 + .. code-block:: Java + :lineno-start: 18 - int armLengthRatio; - int elbowToWrist_in = 39; - int shoulderToElbow_in = 0; //TODO + int armLengthRatio; + int elbowToWrist_in = 39; + int shoulderToElbow_in = 0; //TODO - @Override - public void robotInit() { - armLengthRatio = elbowToWrist_in / shoulderToElbow_in; - } + @Override + public void robotInit() { + armLengthRatio = elbowToWrist_in / shoulderToElbow_in; + } - .. group-tab:: C++ - .. code-block:: C++ - :lineno-start: 17 + .. code-block:: C++ + :lineno-start: 17 - class Robot : public frc::TimedRobot { - public: - void RobotInit() override { - armLengthRatio = elbowToWrist_in / shoulderToElbow_in; - } + class Robot : public frc::TimedRobot { + public: + void RobotInit() override { + armLengthRatio = elbowToWrist_in / shoulderToElbow_in; + } - private: - int armLengthRatio; - int elbowToWrist_in = 39; - int shoulderToElbow_in = 0; //TODO + private: + int armLengthRatio; + int elbowToWrist_in = 39; + int shoulderToElbow_in = 0; //TODO - }; + }; When run, you'll see output that looks like this: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java .. code-block:: text + ********** Robot program starting ********** Error at frc.robot.Robot.robotInit(Robot.java:24): Unhandled exception: java.lang.ArithmeticException: / by zero @@ -351,8 +349,8 @@ When run, you'll see output that looks like this: Alternatively, by running the single-step debugger and stopping on line 24, you could inspect the value of all variables to discover ``shoulderToElbow_in`` has a value of ``0``. - .. group-tab:: C++ - + .. tab-item:: C++ + :sync: tabcode-c++ .. code-block:: text @@ -381,42 +379,39 @@ Sometimes, you just need to use a different number other than 0. A functional implementation could look like this: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. code-block:: Java + :lineno-start: 18 - .. code-block:: Java - :lineno-start: 18 + int armLengthRatio; + int elbowToWrist_in = 39; + int shoulderToElbow_in = 3; - int armLengthRatio; - int elbowToWrist_in = 39; - int shoulderToElbow_in = 3; + @Override + public void robotInit() { - @Override - public void robotInit() { + armLengthRatio = elbowToWrist_in / shoulderToElbow_in; - armLengthRatio = elbowToWrist_in / shoulderToElbow_in; - - } + } - .. group-tab:: C++ - .. code-block:: C++ - :lineno-start: 17 + .. code-block:: C++ + :lineno-start: 17 - class Robot : public frc::TimedRobot { - public: - void RobotInit() override { - armLengthRatio = elbowToWrist_in / shoulderToElbow_in; - } + class Robot : public frc::TimedRobot { + public: + void RobotInit() override { + armLengthRatio = elbowToWrist_in / shoulderToElbow_in; + } - private: - int armLengthRatio; - int elbowToWrist_in = 39; - int shoulderToElbow_in = 3 + private: + int armLengthRatio; + int elbowToWrist_in = 39; + int shoulderToElbow_in = 3 - }; + }; Alternatively, if zero *is* a valid value, adding ``if/else`` statements around the calculation can help you define alternate behavior to avoid making the processor perform a division by zero. @@ -430,46 +425,45 @@ A very common FRC-specific error occurs when the code attempts to put two hardwa For example, consider the following code: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. code-block:: Java - :lineno-start: 19 + .. code-block:: Java + :lineno-start: 19 - PWMSparkMax leftFrontMotor; - PWMSparkMax leftRearMotor; + PWMSparkMax leftFrontMotor; + PWMSparkMax leftRearMotor; - @Override - public void robotInit() { - leftFrontMotor = new PWMSparkMax(0); - leftRearMotor = new PWMSparkMax(0); - } + @Override + public void robotInit() { + leftFrontMotor = new PWMSparkMax(0); + leftRearMotor = new PWMSparkMax(0); + } - .. group-tab:: C++ - .. code-block:: C++ - :lineno-start: 17 + .. code-block:: C++ + :lineno-start: 17 - class Robot : public frc::TimedRobot { - public: - void RobotInit() override { - m_frontLeftMotor.Set(0.5); - m_rearLeftMotor.Set(0.25); - } + class Robot : public frc::TimedRobot { + public: + void RobotInit() override { + m_frontLeftMotor.Set(0.5); + m_rearLeftMotor.Set(0.25); + } - private: - frc::PWMVictorSPX m_frontLeftMotor{0}; - frc::PWMVictorSPX m_rearLeftMotor{0}; + private: + frc::PWMVictorSPX m_frontLeftMotor{0}; + frc::PWMVictorSPX m_rearLeftMotor{0}; - }; + }; When run, you'll see output that looks like this: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java .. code-block:: text @@ -505,7 +499,8 @@ When run, you'll see output that looks like this: Taking a peek at the code, we see line 24 is where the first motor controller is declared and line 25 is where the second motor controller is declared. We can also note that *both* motor controllers are assigned to PWM output ``0``. This doesn't make logical sense, and isn't physically possible. Therefore, WPILib purposely generates a custom error message and exception to alert the software developers of a non-achievable hardware configuration. - .. group-tab:: C++ + .. tab-item:: C++ + :sync: tabcode-c++ In C++, you won't specifically see a stacktrace from this issue. Instead, you'll get messages which look like the following: @@ -562,42 +557,39 @@ Fixing HAL Resource Already Allocated Issues In the example, the left motor controllers are plugged into PWM ports ``0`` and ``1``. Therefore, corrected code would look like this: -.. tabs:: - - .. group-tab:: Java +.. tab-set-code:: - .. code-block:: Java - :lineno-start: 19 + .. code-block:: Java + :lineno-start: 19 - PWMSparkMax leftFrontMotor; - PWMSparkMax leftRearMotor; + PWMSparkMax leftFrontMotor; + PWMSparkMax leftRearMotor; - @Override - public void robotInit() { + @Override + public void robotInit() { - leftFrontMotor = new PWMSparkMax(0); - leftRearMotor = new PWMSparkMax(1); + leftFrontMotor = new PWMSparkMax(0); + leftRearMotor = new PWMSparkMax(1); - } + } - .. group-tab:: C++ - .. code-block:: C++ + .. code-block:: C++ - :lineno-start: 17 + :lineno-start: 17 - class Robot : public frc::TimedRobot { - public: - void RobotInit() override { - m_frontLeftMotor.Set(0.5); - m_rearLeftMotor.Set(0.25); - } + class Robot : public frc::TimedRobot { + public: + void RobotInit() override { + m_frontLeftMotor.Set(0.5); + m_rearLeftMotor.Set(0.25); + } - private: - frc::PWMVictorSPX m_frontLeftMotor{0}; - frc::PWMVictorSPX m_rearLeftMotor{1}; + private: + frc::PWMVictorSPX m_frontLeftMotor{0}; + frc::PWMVictorSPX m_rearLeftMotor{1}; - }; + }; gradlew is not recognized... ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/source/docs/software/basic-programming/robot-preferences.rst b/source/docs/software/basic-programming/robot-preferences.rst index c84fda6cb7..050de83622 100644 --- a/source/docs/software/basic-programming/robot-preferences.rst +++ b/source/docs/software/basic-programming/robot-preferences.rst @@ -9,9 +9,10 @@ This example shows how to utilize Preferences to change the setpoint of a PID co Initializing Preferences ------------------------ -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Constants.java :language: java @@ -21,7 +22,8 @@ Initializing Preferences :language: java :lines: 28-30, 71-72, 79-82 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.h :language: cpp @@ -40,15 +42,17 @@ If using the Command Framework, this type of code could be placed in the constru Reading Preferences ------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/subsystems/Arm.java :language: java :lines: 104-111 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp :language: cpp @@ -58,9 +62,10 @@ Reading a preference is easy. The ``getDouble`` method takes two parameters, the Depending on the data that is stored in preferences, you can use it when you read it, such as the proportional constant above. Or you can store it in a variable and use it later, such as the setpoint, which is used in ``telopPeriodic`` below. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armsimulation/Robot.java :language: java @@ -69,7 +74,8 @@ Depending on the data that is stored in preferences, you can use it when you rea :language: java :lines: 113-119 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp :language: cpp diff --git a/source/docs/software/can-devices/power-distribution-module.rst b/source/docs/software/can-devices/power-distribution-module.rst index f4139bc664..ca8bc0e625 100644 --- a/source/docs/software/can-devices/power-distribution-module.rst +++ b/source/docs/software/can-devices/power-distribution-module.rst @@ -8,15 +8,15 @@ Creating a Power Distribution Object To use the either Power Distribution module, create an instance of the :code:`PowerDistribution` class (`Java `__, `C++ `__). With no arguments, the Power Distribution object will be detected, and must use CAN ID of 0 for CTRE or 1 for REV. If the CAN ID is non-default, additional constructors are available to specify the CAN ID and type. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java PowerDistribution examplePD = new PowerDistribution(); PowerDistribution examplePD = new PowerDistribution(0, ModuleType.kCTRE); PowerDistribution examplePD = new PowerDistribution(1, ModuleType.kRev); - .. code-tab:: c++ + .. code-block:: c++ PowerDistribution examplePD{}; PowerDistribution examplePD{0, frc::PowerDistribution::ModuleType::kCTRE}; @@ -29,9 +29,8 @@ Note: it is not necessary to create a PowerDistribution object unless you need t Reading the Bus Voltage ----------------------- -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java :language: java @@ -39,7 +38,6 @@ Reading the Bus Voltage :linenos: :lineno-start: 32 - .. group-tab:: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp :language: cpp @@ -52,46 +50,42 @@ Monitoring the bus voltage can be useful for (among other things) detecting when Reading the Temperature ----------------------- -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java - :language: java - :lines: 37-39 - :linenos: - :lineno-start: 37 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java + :language: java + :lines: 37-39 + :linenos: + :lineno-start: 37 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp - :language: cpp - :lines: 33-35 - :linenos: - :lineno-start: 33 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp + :language: cpp + :lines: 33-35 + :linenos: + :lineno-start: 33 Monitoring the temperature can be useful for detecting if the robot has been drawing too much power and needs to be shut down for a while, or if there is a short or other wiring problem. Reading the Total Current, Power, and Energy -------------------------------------------- -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java - :language: java - :lines: 41-53 - :linenos: - :lineno-start: 41 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java + :language: java + :lines: 41-53 + :linenos: + :lineno-start: 41 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp - :language: cpp - :lines: 37-49 - :linenos: - :lineno-start: 37 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp + :language: cpp + :lines: 37-49 + :linenos: + :lineno-start: 37 Monitoring the total current, power and energy can be useful for controlling how much power is being drawn from the battery, both for preventing brownouts and ensuring that mechanisms have sufficient power available to perform the actions required. Power is the bus voltage multiplied by the current with the units Watts. Energy is the power summed over time with units Joules. @@ -100,23 +94,21 @@ Reading Individual Channel Currents The PDP/PDH also allows users to monitor the current drawn by the individual device power channels. You can read the current on any of the 16 PDP channels (0-15) or 24 PDH channels (0-23). -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java - :language: java - :lines: 26-30 - :linenos: - :lineno-start: 26 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/canpdp/Robot.java + :language: java + :lines: 26-30 + :linenos: + :lineno-start: 26 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp - :language: cpp - :lines: 22-26 - :linenos: - :lineno-start: 22 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp + :language: cpp + :lines: 22-26 + :linenos: + :lineno-start: 22 Monitoring individual device current draws can be useful for detecting shorts or stalled motors. @@ -125,14 +117,14 @@ Using the Switchable Channel (PDH) The REV PDH has one channel that can be switched on or off to control custom circuits. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java examplePD.setSwitchableChannel(true); examplePD.setSwitchableChannel(false); - .. code-tab:: c++ + .. code-block:: c++ examplePD.SetSwitchableChannel(true); examplePD.SetSwitchableChannel(false); diff --git a/source/docs/software/commandbased/binding-commands-to-triggers.rst b/source/docs/software/commandbased/binding-commands-to-triggers.rst index ce65086dd7..427380f057 100644 --- a/source/docs/software/commandbased/binding-commands-to-triggers.rst +++ b/source/docs/software/commandbased/binding-commands-to-triggers.rst @@ -17,14 +17,14 @@ HID Factories The command-based HID classes contain factory methods returning a ``Trigger`` for a given button. ``CommandGenericHID`` has an index-based ``button(int)`` factory (`Java `__, `C++ `__), and its subclasses ``CommandXboxController`` (`Java `__, `C++ `__), ``CommandPS4Controller`` (`Java `__, `C++ `__), and ``CommandJoystick`` (`Java `__, `C++ `__) have named factory methods for each button. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java CommandXboxController exampleCommandController = new CommandXboxController(1); // Creates a CommandXboxController on port 1. Trigger xButton = exampleCommandController.x(); // Creates a new Trigger object for the `X` button on exampleCommandController - .. code-tab:: c++ + .. code-block:: c++ frc2::CommandXboxController exampleCommandController{1} // Creates a CommandXboxController on port 1 frc2::Trigger xButton = exampleCommandController.X() // Creates a new Trigger object for the `X` button on exampleCommandController @@ -34,14 +34,14 @@ JoystickButton Alternatively, the :ref:`regular HID classes ` can be used and passed to create an instance of ``JoystickButton`` (`Java `__, `C++ `__), a constructor-only subclass of ``Trigger``: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java XboxController exampleController = new XboxController(2); // Creates an XboxController on port 2. Trigger yButton = new JoystickButton(exampleController, XboxController.Button.kY.value); // Creates a new JoystickButton object for the `Y` button on exampleController - .. code-tab:: c++ + .. code-block:: c++ frc::XboxController exampleController{2} // Creates an XboxController on port 2 frc2::JoystickButton yButton(&exampleStick, frc::XboxController::Button::kY); // Creates a new JoystickButton object for the `Y` button on exampleController @@ -51,15 +51,15 @@ Arbitrary Triggers While binding to HID buttons is by far the most common use case, users may want to bind commands to arbitrary triggering events. This can be done inline by passing a lambda to the constructor of ``Trigger``: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java DigitalInput limitSwitch = new DigitalInput(3); // Limit switch on DIO 3 Trigger exampleTrigger = new Trigger(limitSwitch::get); - .. code-tab:: c++ + .. code-block:: c++ frc::DigitalInput limitSwitch{3}; // Limit switch on DIO 3 @@ -81,9 +81,8 @@ onTrue This binding schedules a command when a trigger changes from ``false`` to ``true`` (or, accordingly, when a button changes is initially pressed). The command will be scheduled on the iteration when the state changes, and will not be scheduled again unless the trigger becomes ``false`` and then ``true`` again (or the button is released and then re-pressed). -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java :language: java @@ -91,7 +90,6 @@ This binding schedules a command when a trigger changes from ``false`` to ``true :linenos: :lineno-start: 52 - .. group-tab:: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp :language: c++ @@ -106,23 +104,21 @@ whileTrue This binding schedules a command when a trigger changes from ``false`` to ``true`` (or, accordingly, when a button is initially pressed) and cancels it when the trigger becomes ``false`` again (or the button is released). The command will *not* be re-scheduled if it finishes while the trigger is still ``true``. For the command to restart if it finishes while the trigger is ``true``, wrap the command in a ``RepeatCommand``, or use a ``RunCommand`` instead of an ``InstantCommand``. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java - :language: java - :lines: 114-116 - :linenos: - :lineno-start: 114 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java + :language: java + :lines: 114-116 + :linenos: + :lineno-start: 114 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp - :language: c++ - :lines: 75-78 - :linenos: - :lineno-start: 75 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp + :language: c++ + :lines: 75-78 + :linenos: + :lineno-start: 75 The ``whileFalse`` binding is identical, only that it schedules on ``false`` and cancels on ``true``. @@ -131,15 +127,15 @@ toggleOnTrue This binding toggles a command, scheduling it when a trigger changes from ``false`` to ``true`` (or a button is initially pressed), and canceling it under the same condition if the command is currently running. Note that while this functionality is supported, toggles are not a highly-recommended option for user control, as they require the driver to keep track of the robot state. The preferred method is to use two buttons; one to turn on and another to turn off. Using a `StartEndCommand `__ or a `ConditionalCommand `__ is a good way to specify the commands that you want to be want to be toggled between. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java myButton.toggleOnTrue(Commands.startEnd(mySubsystem::onMethod, mySubsystem::offMethod, mySubsystem)); - .. code-tab:: c++ + .. code-block:: c++ myButton.ToggleOnTrue(frc2::cmd::StartEnd([&] { mySubsystem.OnMethod(); }, [&] { mySubsystem.OffMethod(); }, @@ -152,9 +148,9 @@ Chaining Calls It is useful to note that the command binding methods all return the trigger that they were called on, and thus can be chained to bind multiple commands to different states of the same trigger. For example: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java exampleButton // Binds a FooCommand to be scheduled when the button is pressed @@ -162,7 +158,7 @@ It is useful to note that the command binding methods all return the trigger tha // Binds a BarCommand to be scheduled when that same button is released .onFalse(new BarCommand()); - .. code-tab:: c++ + .. code-block:: c++ exampleButton // Binds a FooCommand to be scheduled when the button is pressed @@ -175,16 +171,16 @@ Composing Triggers The ``Trigger`` class can be composed to create composite triggers through the ``and()``, ``or()``, and ``negate()`` methods (or, in C++, the ``&&``, ``||``, and ``!`` operators). For example: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Binds an ExampleCommand to be scheduled when both the 'X' and 'Y' buttons of the driver gamepad are pressed exampleCommandController.x() .and(exampleCommandController.y()) .onTrue(new ExampleCommand()); - .. code-tab:: c++ + .. code-block:: c++ // Binds an ExampleCommand to be scheduled when both the 'X' and 'Y' buttons of the driver gamepad are pressed (exampleCommandController.X() @@ -196,9 +192,9 @@ Debouncing Triggers To avoid rapid repeated activation, triggers (especially those originating from digital inputs) can be debounced with the :ref:`WPILib Debouncer class ` using the `debounce` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // debounces exampleButton with a 0.1s debounce time, rising edges only exampleButton.debounce(0.1).onTrue(new ExampleCommand()); @@ -206,7 +202,7 @@ To avoid rapid repeated activation, triggers (especially those originating from // debounces exampleButton with a 0.1s debounce time, both rising and falling edges exampleButton.debounce(0.1, Debouncer.DebounceType.kBoth).onTrue(new ExampleCommand()); - .. code-tab:: c++ + .. code-block:: c++ // debounces exampleButton with a 100ms debounce time, rising edges only exampleButton.Debounce(100_ms).OnTrue(ExampleCommand().ToPtr()); diff --git a/source/docs/software/commandbased/command-compositions.rst b/source/docs/software/commandbased/command-compositions.rst index 9781a608b4..6cb5b725bc 100644 --- a/source/docs/software/commandbased/command-compositions.rst +++ b/source/docs/software/commandbased/command-compositions.rst @@ -7,14 +7,14 @@ As the name suggests, a command composition is a :term:`composition` of one or m Most importantly, however, command compositions are themselves commands - they extend the ``Command`` class. This allows command compositions to be further composed as a :term:`recursive composition` - that is, a command composition may contain other command compositions as components. This allows very powerful and concise inline expressions: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Will run fooCommand, and then a race between barCommand and bazCommand button.onTrue(fooCommand.andThen(barCommand.raceWith(bazCommand))); - .. code-tab:: c++ + .. code-block:: c++ // Will run fooCommand, and then a race between barCommand and bazCommand button.OnTrue(std::move(fooCommand).AndThen(std::move(barCommand).RaceWith(std::move(bazCommand)))); @@ -35,14 +35,14 @@ Repeating The ``repeatedly()`` decorator (`Java `__, `C++ `__), backed by the ``RepeatCommand`` class (`Java `__, `C++ `__) restarts the command each time it ends, so that it runs until interrupted. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Will run forever unless externally interrupted, restarting every time command.isFinished() returns true Command repeats = command.repeatedly(); - .. code-tab:: c++ + .. code-block:: c++ // Will run forever unless externally interrupted, restarting every time command.IsFinished() returns true frc2::CommandPtr repeats = std::move(command).Repeatedly(); @@ -54,13 +54,13 @@ The ``Sequence`` factory (`Java `__, `C++ `__) and ``beforeStarting()`` (`Java `__, `C++ `__) decorators can be used to construct a sequence composition with infix syntax. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java fooCommand.andThen(barCommand) - .. code-tab:: c++ + .. code-block:: c++ std::move(fooCommand).AndThen(std::move(barCommand)) @@ -78,9 +78,9 @@ There are three types of parallel compositions, differing based on when the comp - The ``Race`` factory (`Java `__, `C++ `__), backed by the ``ParallelRaceGroup`` class (`Java `__, `C++ `__), constructs a parallel composition that finishes as soon as any member finishes; all other members are interrupted at that point. The ``raceWith`` decorator (`Java `__, `C++ `__) does the same in infix notation. - The ``Deadline`` factory (`Java `__, `C++ `__), ``ParallelDeadlineGroup`` (`Java `__, `C++ `__) finishes when a specific command (the "deadline") ends; all other members still running at that point are interrupted. The ``deadlineWith`` decorator (`Java `__, `C++ `__) does the same in infix notation; the comand the decorator was called on is the deadline. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Will be a parallel command group that ends after three seconds with all three commands running their full duration. button.onTrue(Commands.parallel(twoSecCommand, oneSecCommand, threeSecCommand)); @@ -91,7 +91,7 @@ There are three types of parallel compositions, differing based on when the comp // Will be a parallel deadline group that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished). button.onTrue(Commands.deadline(twoSecCommand, oneSecCommand, threeSecCommand)); - .. code-tab:: c++ + .. code-block:: c++ // Will be a parallel command group that ends after three seconds with all three commands running their full duration. button.OnTrue(frc2::cmd::Parallel(std::move(twoSecCommand), std::move(oneSecCommand), std::move(threeSecCommand))); @@ -107,28 +107,28 @@ Adding Command End Conditions The ``until()`` (`Java `__, `C++ `__) decorator composes the command with an additional end condition. Note that the command the decorator was called on will see this end condition as an interruption. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Will be interrupted if m_limitSwitch.get() returns true button.onTrue(command.until(m_limitSwitch::get)); - .. code-tab:: c++ + .. code-block:: c++ // Will be interrupted if m_limitSwitch.get() returns true button.OnTrue(command.Until([&m_limitSwitch] { return m_limitSwitch.Get(); })); The ``withTimeout()`` decorator (`Java `__, `C++ `__) is a specialization of ``until`` that uses a timeout as the additional end condition. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Will time out 5 seconds after being scheduled, and be interrupted button.onTrue(command.withTimeout(5)); - .. code-tab:: c++ + .. code-block:: c++ // Will time out 5 seconds after being scheduled, and be interrupted button.OnTrue(command.WithTimeout(5.0_s)); @@ -147,9 +147,11 @@ Sometimes it's desired to run a command out of a few options based on sensor fee The ``Select`` factory (`Java `__, `C++ `__), backed by the ``SelectCommand`` class (`Java `__, `C++ `__), executes one command from a map, based on a selector function called when scheduled. -.. tabs:: +.. tab-set:: + + .. tab-item:: Java + :sync: Java - .. group-tab:: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/selectcommand/RobotContainer.java :language: java @@ -157,7 +159,9 @@ The ``Select`` factory (`Java `__, `C++ `__), backed by the ``ConditionalCommand`` class (`Java `__, `C++ `__), is a specialization accepting two commands and a boolean selector function. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Runs either commandOnTrue or commandOnFalse depending on the value of m_limitSwitch.get() new ConditionalCommand(commandOnTrue, commandOnFalse, m_limitSwitch::get) - .. code-tab:: c++ + .. code-block:: c++ // Runs either commandOnTrue or commandOnFalse depending on the value of m_limitSwitch.get() frc2::ConditionalCommand(commandOnTrue, commandOnFalse, [&m_limitSwitch] { return m_limitSwitch.Get(); }) The ``unless()`` decorator (`Java `__, `C++ `__) composes a command with a condition that will prevent it from running. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Command will only run if the intake is deployed. If the intake gets deployed while the command is running, the command will not stop running button.onTrue(command.unless(() -> !intake.isDeployed())); - .. code-tab:: c++ + .. code-block:: c++ // Command will only run if the intake is deployed. If the intake gets deployed while the command is running, the command will not stop running button.OnTrue(command.Unless([&intake] { return !intake.IsDeployed(); })); @@ -202,15 +206,15 @@ By default, composition members are run through the command composition, and are ``ProxyCommand`` (`Java `__, `C++ `__), also creatable using the ``.asProxy()`` decorator (`Java `__, `C++ `__), schedules a command "by proxy": the command is scheduled when the proxy is scheduled, and the proxy finishes when the command finishes. In the case of "forking off" from a command composition, this allows the group to track the command's progress without it being in the composition. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // The sequence continues only after the proxied command ends Commands.waitSeconds(5.0).asProxy() .andThen(Commands.print("This will only be printed after the 5-second delay elapses!")) - .. code-tab:: c++ + .. code-block:: c++ // The sequence continues only after the proxied command ends frc2::cmd::Wait(5.0_s).AsProxy() @@ -218,15 +222,15 @@ By default, composition members are run through the command composition, and are For cases that don't need to track the proxied command, ``ScheduleCommand`` (`Java `__, `C++ `__) schedules a specified command and ends instantly. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // ScheduleCommand ends immediately, so the sequence continues new ScheduleCommand(Commands.waitSeconds(5.0)) .andThen(Commands.print("This will be printed immediately!")) - .. code-tab:: c++ + .. code-block:: c++ // ScheduleCommand ends immediately, so the sequence continues frc2::ScheduleCommand(frc2::cmd::Wait(5.0_s)) @@ -237,9 +241,10 @@ Subclassing Compositions Command compositions can also be written as a constructor-only subclass of the most exterior composition type, passing the composition members to the superclass constructor. Consider the following from the Hatch Bot example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/ComplexAuto.java :language: java @@ -247,7 +252,8 @@ Command compositions can also be written as a constructor-only subclass of the m :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ComplexAuto.h :language: c++ @@ -255,12 +261,13 @@ Command compositions can also be written as a constructor-only subclass of the m :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/commands/ComplexAuto.cpp - :language: c++ - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/commands/ComplexAuto.cpp + :language: c++ + :lines: 5- + :linenos: + :lineno-start: 5 The advantages and disadvantages of this subclassing approach in comparison to others are discussed in :ref:`docs/software/commandbased/organizing-command-based:Subclassing Command Groups`. diff --git a/source/docs/software/commandbased/command-scheduler.rst b/source/docs/software/commandbased/command-scheduler.rst index 78f119223e..343dc5a5f9 100644 --- a/source/docs/software/commandbased/command-scheduler.rst +++ b/source/docs/software/commandbased/command-scheduler.rst @@ -28,9 +28,10 @@ This method walks through the following steps: * If not, don't schedule the new command. #. Call ``initialize()``. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java :language: java @@ -44,13 +45,15 @@ This method walks through the following steps: :linenos: :lineno-start: 181 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp :language: c++ :lines: 114-159 :linenos: :lineno-start: 114 + The Scheduler Run Sequence -------------------------- @@ -64,9 +67,10 @@ Step 1: Run Subsystem Periodic Methods First, the scheduler runs the ``periodic()`` method of each registered ``Subsystem``. In simulation, each subsystem's ``simulationPeriodic()`` method is called as well. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java :language: java @@ -74,7 +78,8 @@ First, the scheduler runs the ``periodic()`` method of each registered ``Subsyst :linenos: :lineno-start: 278 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp :language: c++ @@ -89,17 +94,19 @@ Step 2: Poll Command Scheduling Triggers Secondly, the scheduler polls the state of all registered triggers to see if any new commands that have been bound to those triggers should be scheduled. If the conditions for scheduling a bound command are met, the command is scheduled and its ``Initialize()`` method is run. -.. tabs:: - - .. group-tab:: Java +.. tab-set:: + .. tab-item:: Java + :sync: tabcode-java + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java :language: java :lines: 290-292 :linenos: :lineno-start: 290 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp :language: c++ @@ -114,9 +121,10 @@ Thirdly, the scheduler calls the ``execute()`` method of each currently-schedule Note that this sequence of calls is done in order for each command - thus, one command may have its ``end()`` method called before another has its ``execute()`` method called. Commands are handled in the order they were scheduled. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java :language: java @@ -125,7 +133,8 @@ Note that this sequence of calls is done in order for each command - thus, one c :lineno-start: 295 :emphasize-lines: 16,21-22 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp :language: c++ @@ -139,9 +148,10 @@ Step 4: Schedule Default Commands Finally, any registered ``Subsystem`` has its default command scheduled (if it has one). Note that the ``initialize()`` method of the default command will be called at this time. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java :language: java @@ -149,7 +159,8 @@ Finally, any registered ``Subsystem`` has its default command scheduled (if it h :linenos: :lineno-start: 340 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp :language: c++ @@ -179,9 +190,10 @@ Occasionally, it is desirable to have the scheduler execute a custom action when A typical use-case for these methods is adding markers in an event log whenever a command scheduling event takes place, as demonstrated in the following code from the HatchbotInlined example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java :language: java @@ -189,7 +201,8 @@ A typical use-case for these methods is adding markers in an event log whenever :linenos: :lineno-start: 73 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp :language: c++ diff --git a/source/docs/software/commandbased/organizing-command-based.rst b/source/docs/software/commandbased/organizing-command-based.rst index aaee6fc6b6..f93f386015 100644 --- a/source/docs/software/commandbased/organizing-command-based.rst +++ b/source/docs/software/commandbased/organizing-command-based.rst @@ -33,21 +33,21 @@ Inline Commands The easiest and most expressive way to do this is with a ``StartEndCommand``: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Command runIntake = Commands.startEnd(() -> intake.set(1), () -> intake.set(0), intake); - .. code-tab:: c++ + .. code-block:: c++ frc2::CommandPtr runIntake = frc2::cmd::StartEnd([&intake] { intake.Set(1.0); }, [&intake] { intake.Set(0); }, {&intake}); This is sufficient for commands that are only used once. However, for a command like this that might get used in many different autonomous routines and button bindings, inline commands everywhere means a lot of repetitive code: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // RobotContainer.java intakeButton.whileTrue(Commands.startEnd(() -> intake.set(1.0), () -> intake.set(0), intake)); @@ -61,7 +61,7 @@ This is sufficient for commands that are only used once. However, for a command Commands.startEnd(() -> intake.set(1.0), () -> intake.set(0.0), intake).withTimeout(5.0) ); - .. code-tab:: c++ + .. code-block:: c++ intakeButton.WhileTrue(frc2::cmd::StartEnd([&intake] { intake.Set(1.0); }, [&intake] { intake.Set(0); }, {&intake})); @@ -85,9 +85,9 @@ For example, a command like the intake-running command is conceptually related t .. note:: In this document we will name factory methods as ``lowerCamelCaseCommand``, but teams may decide on other conventions. In general, it is recommended to end the method name with ``Command`` if it might otherwise be confused with an ordinary method (e.g. ``intake.run`` might be the name of a method that simply turns on the intake). -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public class Intake extends SubsystemBase { // [code for motor controllers, configuration, etc.] @@ -99,7 +99,7 @@ For example, a command like the intake-running command is conceptually related t } } - .. code-tab:: c++ + .. code-block:: c++ frc2::CommandPtr Intake::RunIntakeCommand() { // implicitly requires `this` @@ -112,9 +112,9 @@ Since we are inside the ``Intake`` class, technically we can access ``private`` Using this new factory method in command groups and button bindings is highly expressive: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java intakeButton.whileTrue(intake.runIntakeCommand()); @@ -126,7 +126,7 @@ Using this new factory method in command groups and button bindings is highly ex intake.runIntakeCommand().withTimeout(5.0) ); - .. code-tab:: c++ + .. code-block:: c++ intakeButton.WhileTrue(intake.RunIntakeCommand()); @@ -140,15 +140,15 @@ Using this new factory method in command groups and button bindings is highly ex Adding a parameter to the ``runIntakeCommand`` method to provide the exact percentage to run the intake is easy and allows for even more flexibility. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public Command runIntakeCommand(double percent) { return new StartEndCommand(() -> this.set(percent), () -> this.set(0.0), this); } - .. code-tab:: c++ + .. code-block:: c++ frc2::CommandPtr Intake::RunIntakeCommand() { // implicitly requires `this` @@ -157,15 +157,15 @@ Adding a parameter to the ``runIntakeCommand`` method to provide the exact perce For instance, this code creates a command group that runs the intake forwards for two seconds, waits for two seconds, and then runs the intake backwards for five seconds. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Command intakeRunSequence = intake.runIntakeCommand(1.0).withTimeout(2.0) .andThen(Commands.waitSeconds(2.0)) .andThen(intake.runIntakeCommand(-1.0).withTimeout(5.0)); - .. code-tab:: c++ + .. code-block:: c++ frc2::CommandPtr intakeRunSequence = intake.RunIntakeCommand(1.0).WithTimeout(2.0_s) .AndThen(frc2::cmd::Wait(2.0_s)) @@ -181,9 +181,9 @@ Instance factory methods work great for single-subsystem commands. However, com .. note:: The ``sequence`` and ``parallel`` static factories construct sequential and parallel command groups: this is equivalent to the ``andThen`` and ``alongWith`` decorators, but can be more readable. Their use is a matter of personal preference. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public class AutoRoutines { @@ -201,7 +201,7 @@ Instance factory methods work great for single-subsystem commands. However, com } } - .. code-tab:: c++ + .. code-block:: c++ // TODO @@ -209,9 +209,9 @@ Non-Static Command Factories ~~~~~~~~~~~~~~~~~~~~~~~~~~~~ If we want to avoid the verbosity of adding required subsystems as parameters to our factory methods, we can instead construct an instance of our ``AutoRoutines`` class and inject our subsystems through the constructor: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public class AutoRoutines { @@ -247,15 +247,15 @@ If we want to avoid the verbosity of adding required subsystems as parameters to } } - .. code-tab:: c++ + .. code-block:: c++ // TODO Then, elsewhere in our code, we can instantiate an single instance of this class and use it to produce several commands: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java AutoRoutines autoRoutines = new AutoRoutines(this.drivetrain, this.intake); @@ -267,7 +267,7 @@ Then, elsewhere in our code, we can instantiate an single instance of this class autoRoutines.driveThenIntake() ); - .. code-tab:: c++ + .. code-block:: c++ // TODO @@ -280,9 +280,9 @@ However, it is still possible to ergonomically write a stateful command composit .. note:: The ``Subsystem.run`` and ``Subsystem.runOnce`` factory methods sugar the creation of a ``RunCommand`` and an ``InstantCommand`` requiring ``this`` subsystem. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public Command turnToAngle(double targetDegrees) { // Create a controller for the inline command to capture @@ -296,7 +296,7 @@ However, it is still possible to ergonomically write a stateful command composit .andThen(runOnce(() -> arcadeDrive(0, 0))); } - .. code-tab:: c++ + .. code-block:: c++ // TODO @@ -312,9 +312,9 @@ Subclassing Command Returning to our simple intake command from earlier, we could do this by creating a new subclass of ``Command`` that implements the necessary ``initialize`` and ``end`` methods. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public class RunIntakeCommand extends Command { private Intake m_intake; @@ -338,7 +338,7 @@ Returning to our simple intake command from earlier, we could do this by creatin // isFinished() defaults to return false } - .. code-tab:: c++ + .. code-block:: c++ // TODO @@ -352,9 +352,9 @@ Subclassing Command Groups If we wish to write composite commands as their own classes, we may write a constructor-only subclass of the most exterior group type. For example, an intake-then-outtake sequence (with single-subsystem commands defined as instance factory methods) can look like this: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public class IntakeThenOuttake extends SequentialCommandGroup { public IntakeThenOuttake(Intake intake) { @@ -365,7 +365,7 @@ If we wish to write composite commands as their own classes, we may write a cons ); } } - .. code-tab:: c++ + .. code-block:: c++ // TODO diff --git a/source/docs/software/commandbased/what-is-command-based.rst b/source/docs/software/commandbased/what-is-command-based.rst index 872d552b66..f8ac61a8c7 100644 --- a/source/docs/software/commandbased/what-is-command-based.rst +++ b/source/docs/software/commandbased/what-is-command-based.rst @@ -7,21 +7,21 @@ WPILib supports a robot programming methodology called "command-based" programmi The command-based paradigm is also an example of :term:`declarative programming`. The command-based library allow users to define desired robot behaviors while minimizing the amount of iteration-by-iteration robot logic that they must write. For example, in the command-based program, a user can specify that "the robot should perform an action when a condition is true" (note the use of a :ref:`lambda `): -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java new Trigger(condition::get).onTrue(Commands.runOnce(() -> piston.set(DoubleSolenoid.Value.kForward))); - .. code-tab:: c++ + .. code-block:: c++ Trigger([&condition] { return condition.Get()).OnTrue(frc2::cmd::RunOnce([&piston] { piston.Set(frc::DoubleSolenoid::kForward))); In contrast, without using command-based, the user would need to check the button state every iteration, and perform the appropriate action based on the state of the button. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java if(condition.get()) { if(!pressed) { @@ -32,7 +32,7 @@ In contrast, without using command-based, the user would need to check the butto pressed = false; } - .. code-tab:: c++ + .. code-block:: c++ if(condition.Get()) { if(!pressed) { diff --git a/source/docs/software/dashboards/glass/command-based-widgets.rst b/source/docs/software/dashboards/glass/command-based-widgets.rst index 29e387d39b..fca51f5113 100644 --- a/source/docs/software/dashboards/glass/command-based-widgets.rst +++ b/source/docs/software/dashboards/glass/command-based-widgets.rst @@ -8,13 +8,13 @@ Command Selector Widget The :guilabel:`Command Selector` widget allows you to start and cancel a specific instance of a command (sent over NetworkTables) from Glass. For example, you can create an instance of ``MyCommand`` and send it to SmartDashboard: -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java MyCommand command = new MyCommand(...); SmartDashboard.putData("My Command", command); - .. code-tab:: c++ + .. code-block:: c++ #include diff --git a/source/docs/software/dashboards/glass/widgets.rst b/source/docs/software/dashboards/glass/widgets.rst index 11eddca6cc..1cb3a5fe10 100644 --- a/source/docs/software/dashboards/glass/widgets.rst +++ b/source/docs/software/dashboards/glass/widgets.rst @@ -31,12 +31,12 @@ Sendable Chooser Widget The :guilabel:`Sendable Chooser` widget represents a ``SendableChooser`` instance from robot code. It is often used to select autonomous modes. Like other dashboards, your ``SendableChooser`` instance simply needs to be sent using a NetworkTables API. The simplest is to use something like ``SmartDashboard``: -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java SmartDashboard.putData("Auto Selector", m_selector); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutData("Auto Selector", &m_selector); @@ -51,12 +51,12 @@ PID Controller Widget The :guilabel:`PID Controller` widget allows you to quickly tune PID values for a certain controller. A ``PIDController`` instance must be sent using a NetworkTables API. The simplest is to use something like ``SmartDashboard``: -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java SmartDashboard.putData("Elevator PID Controller", m_elevatorPIDController); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutData("Elevator PID Controller", &m_elevatorPIDController); diff --git a/source/docs/software/dashboards/labview-dashboard/using-the-labview-dashboard-with-c++-java-code.rst b/source/docs/software/dashboards/labview-dashboard/using-the-labview-dashboard-with-c++-java-code.rst index be42b9ee1b..fbb371cf00 100644 --- a/source/docs/software/dashboards/labview-dashboard/using-the-labview-dashboard-with-c++-java-code.rst +++ b/source/docs/software/dashboards/labview-dashboard/using-the-labview-dashboard-with-c++-java-code.rst @@ -10,9 +10,9 @@ Drive Tab The :guilabel:`Select Autonomous...` dropdown can be used so show the available autonomous routines and choose one to run for the match. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putStringArray("Auto List", {"Drive Forwards", "Drive Backwards", "Shoot"}); @@ -27,7 +27,7 @@ The :guilabel:`Select Autonomous...` dropdown can be used so show the available // auto here } - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutStringArray("Auto List", {"Drive Forwards", "Drive Backwards", "Shoot"}); @@ -44,25 +44,25 @@ The :guilabel:`Select Autonomous...` dropdown can be used so show the available Sending to the "Gyro" NetworkTables entry will populate the gyro here. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putNumber("Gyro", drivetrain.getHeading()); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutNumber("Gyro", Drivetrain.GetHeading()); There are four outputs that show the motor power to the drivetrain. This is configured for 2 motors per side and a tank style drivetrain. This is done by setting "RobotDrive Motors" like the example below. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putNumberArray("RobotDrive Motors", {drivetrain.getLeftFront(), drivetrain.getRightFront(), drivetrain.getLeftBack(), drivetrain.getRightBack()}); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutNumberArray("Gyro", {drivetrain.GetLeftFront(), drivetrain.GetRightFront(), drivetrain.GetLeftBack(), drivetrain.GetRightBack()}); @@ -80,25 +80,25 @@ Strings The strings are labeled top-to-bottom, left-to-right from "DB/String 0" to "DB/String 9". Each String field can display at least 21 characters (exact number depends on what characters). To write to these strings: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putString("DB/String 0", "My 21 Char TestString"); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutString("DB/String 0", "My 21 Char TestString"); To read string data entered on the Dashboard: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java String dashData = SmartDashboard.getString("DB/String 0", "myDefaultData"); - .. code-tab:: c++ + .. code-block:: c++ std::string dashData = frc::SmartDashboard::GetString("DB/String 0", "myDefaultData"); @@ -109,25 +109,25 @@ Buttons and LEDs The Buttons and LEDs are boolean values and are labeled top-to-bottom from "DB/Button 0" to "DB/Button 3" and "DB/LED 0" to "DB/LED 3". The Buttons are bi-directional, the LEDs are only able to be written from the Robot and read on the Dashboard. To write to the Buttons or LEDs: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putBoolean("DB/Button 0", true); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutBoolean("DB/Button 0", true); To read from the Buttons: (default value is false) -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java boolean buttonValue = SmartDashboard.getBoolean("DB/Button 0", false); - .. code-tab:: c++ + .. code-block:: c++ bool buttonValue = frc::SmartDashboard::GetBoolean("DB/Button 0", false); @@ -138,24 +138,24 @@ Sliders The Sliders are bi-directional analog (double) controls/indicators with a range from 0 to 5. To write to these indicators: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putNumber("DB/Slider 0", 2.58); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutNumber("DB/Slider 0", 2.58); To read values from the Dashboard into the robot program: (default value of 0.0) -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java double dashData = SmartDashboard.getNumber("DB/Slider 0", 0.0); - .. code-tab:: c++ + .. code-block:: c++ double dashData = frc::SmartDashboard::GetNumber("DB/Slider 0", 0.0); diff --git a/source/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-commands-subsystems.rst b/source/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-commands-subsystems.rst index f32883e3f0..eb72869e76 100644 --- a/source/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-commands-subsystems.rst +++ b/source/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-commands-subsystems.rst @@ -8,13 +8,13 @@ Displaying Subsystems To see the status of a subsystem while the robot is operating in either autonomous or teleoperated modes, that is what its default command is and what command is currently using that subsystem, send a subsystem instance to Shuffleboard: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putData(subsystem-reference); - .. code-tab:: cpp + .. code-block:: cpp SmartDashboard::PutData(subsystem-pointer); @@ -42,13 +42,13 @@ Displaying Commands Using commands and subsystems makes very modular robot programs that can easily be tested and modified. Part of this is because commands can be written completely independently of other commands and can therefore be easily run from Shuffleboard. To write a command to Shuffleboard use the ``SmartDashboard.putData`` method as shown here: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putData("ElevatorMove: up", new ElevatorMove(2.7)); - .. code-tab:: cpp + .. code-block:: cpp SmartDashboard::PutData("ElevatorMove: up", new ElevatorMove(2.7)); diff --git a/source/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-tuning-pid.rst b/source/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-tuning-pid.rst index 2924a56b06..56f583ed2b 100644 --- a/source/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-tuning-pid.rst +++ b/source/docs/software/dashboards/shuffleboard/advanced-usage/shuffleboard-tuning-pid.rst @@ -38,9 +38,9 @@ Enable Functionality in the New PIDController The following example demonstrates how to create a button on your dashboard that will enable/disable the PIDController. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java ShuffleboardTab tab = Shuffleboard.getTab("Shooter"); NetworkTableEntry shooterEnable = tab.add("Shooter Enable", false).getEntry(); @@ -55,7 +55,7 @@ The following example demonstrates how to create a button on your dashboard that motor.set(pid.calculate(encoder.getDistance(), setpoint)); } - .. code-tab:: c++ + .. code-block:: c++ frc::ShuffleboardTab& tab = frc::Shuffleboard::GetTab("Shooter"); nt::NetworkTableEntry shooterEnable = tab.Add("Shooter Enable", false).GetEntry(); diff --git a/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-tour.rst b/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-tour.rst index 9c494f8f40..e43e031928 100644 --- a/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-tour.rst +++ b/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-tour.rst @@ -41,9 +41,9 @@ Getting robot data onto the dashboard The easiest way to get data displayed on the dashboard is simply to use methods in the SmartDashboard class. For example to write a number to Shuffleboard write: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putNumber("Joystick X value", joystick1.getX()); diff --git a/source/docs/software/dashboards/shuffleboard/layouts-with-code/configuring-widgets.rst b/source/docs/software/dashboards/shuffleboard/layouts-with-code/configuring-widgets.rst index 2286947a5b..b1a89bbbc3 100644 --- a/source/docs/software/dashboards/shuffleboard/layouts-with-code/configuring-widgets.rst +++ b/source/docs/software/dashboards/shuffleboard/layouts-with-code/configuring-widgets.rst @@ -8,16 +8,16 @@ Specifying a widget Call ``withWidget`` after ``add`` in the call chain: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Shuffleboard.getTab("Drive") .add("Max Speed", 1) .withWidget(BuiltInWidgets.kNumberSlider) // specify the widget here .getEntry(); - .. code-tab:: cpp + .. code-block:: cpp frc::Shuffleboard::GetTab("Drive") .Add("Max Speed", 1) @@ -33,9 +33,9 @@ Setting widget properties ------------------------- Since the maximum speed only makes sense to be a value from 0 to 1 (full stop to full speed), a slider from -1 to 1 can cause problems if the value drops below zero. Fortunately, we can modify that using the ``withProperties`` method -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Shuffleboard.getTab("Drive") .add("Max Speed", 1) @@ -43,7 +43,7 @@ Since the maximum speed only makes sense to be a value from 0 to 1 (full stop to .withProperties(Map.of("min", 0, "max", 1)) // specify widget properties here .getEntry(); - .. code-tab:: cpp + .. code-block:: cpp frc::Shuffleboard::GetTab("Drive") .Add("Max Speed", 1) diff --git a/source/docs/software/dashboards/shuffleboard/layouts-with-code/organizing-widgets.rst b/source/docs/software/dashboards/shuffleboard/layouts-with-code/organizing-widgets.rst index 3056bc4e3c..5aafeb263f 100644 --- a/source/docs/software/dashboards/shuffleboard/layouts-with-code/organizing-widgets.rst +++ b/source/docs/software/dashboards/shuffleboard/layouts-with-code/organizing-widgets.rst @@ -10,16 +10,16 @@ Call ``withSize`` and ``withPosition`` to set the size and position of the widge ``withPosition`` sets the row and column of the top-left corner of the widget. Rows and columns are both 0-indexed, so the topmost row is number 0 and the leftmost column is also number 0. If the position of any widget in a tab is specified, every widget should also have its position set to avoid overlapping widgets. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Shuffleboard.getTab("Pre-round") .add("Auto Mode", autoModeChooser) .withSize(2, 1) // make the widget 2x1 .withPosition(0, 0); // place it in the top-left corner - .. code-tab:: cpp + .. code-block:: cpp frc::Shuffleboard::GetTab("Pre-round") .Add("Auto Mode", autoModeChooser) @@ -31,9 +31,9 @@ Adding Widgets to Layouts If there are many widgets in a tab with related data, it can be useful to place them into smaller subgroups instead of loose in the tab. Much like how the handle to a tab is retrieved with ``Shuffleboard.getTab``, a layout inside a tab (or even in another layout) can be retrieved with ``ShuffleboardTab.getLayout``. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java ShuffleboardLayout elevatorCommands = Shuffleboard.getTab("Commands") .getLayout("Elevator", BuiltInLayouts.kList) @@ -44,7 +44,7 @@ If there are many widgets in a tab with related data, it can be useful to place elevatorCommands.add(new ElevatorUpCommand()); // Similarly for the claw commands - .. code-tab:: cpp + .. code-block:: cpp wpi::StringMap> properties{ std::make_pair("Label position", nt::Value::MakeString("HIDDEN")) diff --git a/source/docs/software/dashboards/shuffleboard/layouts-with-code/retrieving-data.rst b/source/docs/software/dashboards/shuffleboard/layouts-with-code/retrieving-data.rst index b472f7c879..fc55981af0 100644 --- a/source/docs/software/dashboards/shuffleboard/layouts-with-code/retrieving-data.rst +++ b/source/docs/software/dashboards/shuffleboard/layouts-with-code/retrieving-data.rst @@ -2,9 +2,9 @@ Retrieving data =============== Unlike ``SmartDashboard.getNumber`` and friends, retrieving data from Shuffleboard is also done through the NetworkTableEntries, which we covered in the previous article. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java class DriveBase extends Subsystem { private ShuffleboardTab tab = Shuffleboard.getTab("Drive"); diff --git a/source/docs/software/dashboards/shuffleboard/layouts-with-code/sending-data.rst b/source/docs/software/dashboards/shuffleboard/layouts-with-code/sending-data.rst index 08eae7cf5d..8da65c6800 100644 --- a/source/docs/software/dashboards/shuffleboard/layouts-with-code/sending-data.rst +++ b/source/docs/software/dashboards/shuffleboard/layouts-with-code/sending-data.rst @@ -6,23 +6,23 @@ Sending simple data ------------------- Sending simple data (numbers, strings, booleans, and arrays of these) is done by calling ``add`` on a tab. This method will set the value if not already present, but will not overwrite an existing value. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Shuffleboard.getTab("Numbers") .add("Pi", 3.14); - .. code-tab:: c++ + .. code-block:: c++ frc::Shuffleboard::GetTab("Numbers") .Add("Pi", 3.14); If data needs to be updated (for example, the output of some calculation done on the robot), call ``getEntry()`` after defining the value, then update it when needed or in a ``periodic`` function -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java class VisionCalculator { private ShuffleboardTab tab = Shuffleboard.getTab("Vision"); @@ -45,14 +45,14 @@ Simply using `addPersistent` instead of `add` will make the value saved on the r .. note:: This does not apply to sendable data such as choosers or motor controllers. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Shuffleboard.getTab("Drive") .addPersistent("Max Speed", 1.0); - .. code-tab:: c++ + .. code-block:: c++ frc::Shuffleboard::GetTab("Drive") .AddPersistent("Max Speed", 1.0); @@ -62,14 +62,14 @@ Sending sensors, motors, etc Analogous to ``SmartDashboard.putData``, any ``Sendable`` object (most sensors, motor controllers, and SendableChoosers) can be added to any tab -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Shuffleboard.getTab("Tab Title") .add("Sendable Title", mySendable); - .. code-tab:: c++ + .. code-block:: c++ frc::Shuffleboard::GetTab("Tab Title") .Add("Sendable Title", mySendable); diff --git a/source/docs/software/dashboards/shuffleboard/layouts-with-code/using-tabs.rst b/source/docs/software/dashboards/shuffleboard/layouts-with-code/using-tabs.rst index 3b7ca5a2aa..b110659596 100644 --- a/source/docs/software/dashboards/shuffleboard/layouts-with-code/using-tabs.rst +++ b/source/docs/software/dashboards/shuffleboard/layouts-with-code/using-tabs.rst @@ -5,13 +5,13 @@ Shuffleboard is a tabbed interface. Each tab organizes widgets in a logical grou Creating a new tab -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java ShuffleboardTab tab = Shuffleboard.getTab("Tab Title"); - .. code-tab:: c++ + .. code-block:: c++ ShuffleboardTab& tab = Shuffleboard::GetTab("Tab Title"); @@ -21,13 +21,13 @@ Creating a new tab is as simple as calling a single method on the Shuffleboard c Selecting a tab --------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Shuffleboard.selectTab("Tab Title"); - .. code-tab:: c++ + .. code-block:: c++ Shuffleboard::SelectTab("Tab Title"); diff --git a/source/docs/software/dashboards/smartdashboard/displaying-expressions.rst b/source/docs/software/dashboards/smartdashboard/displaying-expressions.rst index c9c2fdadcc..7c002494c3 100644 --- a/source/docs/software/dashboards/smartdashboard/displaying-expressions.rst +++ b/source/docs/software/dashboards/smartdashboard/displaying-expressions.rst @@ -6,9 +6,9 @@ Displaying Expressions from a Robot Program Writing Values to SmartDashboard ------------------------------------ -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java protected void execute() { SmartDashboard.putBoolean("Bridge Limit", bridgeTipper.atBridge()); @@ -21,7 +21,7 @@ Writing Values to SmartDashboard SmartDashboard.putNumber("RPM", shooter.getRPM()); } - .. code-tab:: cpp + .. code-block:: cpp void Command::Execute() { frc::SmartDashboard::PutBoolean("Bridge Limit", BridgeTipper.AtBridge()); diff --git a/source/docs/software/dashboards/smartdashboard/displaying-status-of-commands-and-subsystems.rst b/source/docs/software/dashboards/smartdashboard/displaying-status-of-commands-and-subsystems.rst index ab8c3e8e5c..4a13158cff 100644 --- a/source/docs/software/dashboards/smartdashboard/displaying-status-of-commands-and-subsystems.rst +++ b/source/docs/software/dashboards/smartdashboard/displaying-status-of-commands-and-subsystems.rst @@ -21,13 +21,13 @@ In the following examples, you'll see what the screen would look like when there Displaying the Scheduler Status ------------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putData(CommandScheduler.getInstance()); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutData(frc2::CommandScheduler::GetInstance()); @@ -41,13 +41,13 @@ This is the scheduler status when there are two commands running, ``ExampleComma Displaying Subsystem Status --------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putData(exampleSubsystem); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutData(&exampleSubsystem); @@ -61,13 +61,13 @@ Running commands will "require" subsystems. That is the command is reserving the Activating Commands with a Button --------------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putData("Autonomous Command", exampleCommand); - .. code-tab:: c++ + .. code-block:: c++ frc::SmartDashboard::PutData("Autonomous Command", &exampleCommand); diff --git a/source/docs/software/dashboards/smartdashboard/test-mode-and-live-window/displaying-LiveWindow-values.rst b/source/docs/software/dashboards/smartdashboard/test-mode-and-live-window/displaying-LiveWindow-values.rst index 1373500a87..79fded01a1 100644 --- a/source/docs/software/dashboards/smartdashboard/test-mode-and-live-window/displaying-LiveWindow-values.rst +++ b/source/docs/software/dashboards/smartdashboard/test-mode-and-live-window/displaying-LiveWindow-values.rst @@ -8,9 +8,9 @@ Adding the Necessary Code to your Program For each sensor or actuator that is created, set the subsystem name and display name by calling ``setName`` (``SetName`` in C++). When the SmartDashboard is put into LiveWindow mode, it will display the sensors and actuators. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Ultrasonic ultrasonic = new Ultrasonic(1, 2); SendableRegistry.setName(ultrasonic, "Arm", "Ultrasonic"); @@ -21,7 +21,7 @@ For each sensor or actuator that is created, set the subsystem name and display Victor wrist = new Victor(2); SendableRegistry.setName(wrist, "Arm", "Wrist"); - .. code-tab:: cpp + .. code-block:: cpp frc::Ultrasonic ultrasonic{1, 2}; SendableRegistry::SetName(ultrasonic, "Arm", "Ultrasonic"); @@ -34,9 +34,9 @@ For each sensor or actuator that is created, set the subsystem name and display If your objects are in a ``Subsystem``, this can be simplified using the addChild method of ``SubsystemBase`` -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Ultrasonic ultrasonic = new Ultrasonic(1, 2); addChild("Ultrasonic", ultrasonic); @@ -47,7 +47,7 @@ If your objects are in a ``Subsystem``, this can be simplified using the addChil Victor wrist = new Victor(2); addChild("Wrist", wrist); - .. code-tab:: cpp + .. code-block:: cpp frc::Ultrasonic ultrasonic{1, 2}; AddChild("Ultrasonic", ultrasonic); diff --git a/source/docs/software/dashboards/smartdashboard/test-mode-and-live-window/enabling-test-mode.rst b/source/docs/software/dashboards/smartdashboard/test-mode-and-live-window/enabling-test-mode.rst index bd11490213..e4187ceb0c 100644 --- a/source/docs/software/dashboards/smartdashboard/test-mode-and-live-window/enabling-test-mode.rst +++ b/source/docs/software/dashboards/smartdashboard/test-mode-and-live-window/enabling-test-mode.rst @@ -14,9 +14,9 @@ Enable Test Mode in the Driver Station by clicking on the "Test" button and sett Explicitly vs. implicit test mode display ----------------------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java PWMSparkMax leftDrive; PWMSparkMax rightDrive; @@ -33,7 +33,7 @@ Explicitly vs. implicit test mode display SendableRegistry.setName(accel, "SomeSubsystem", "Accelerometer"); } - .. code-tab:: cpp + .. code-block:: cpp frc::PWMSparkMax leftDrive{0}; frc::PWMSparkMax rigthDrive{1}; diff --git a/source/docs/software/dashboards/smartdashboard/verifying-smartdashboard-is-working.rst b/source/docs/software/dashboards/smartdashboard/verifying-smartdashboard-is-working.rst index 3552b6f962..1271744dff 100644 --- a/source/docs/software/dashboards/smartdashboard/verifying-smartdashboard-is-working.rst +++ b/source/docs/software/dashboards/smartdashboard/verifying-smartdashboard-is-working.rst @@ -22,9 +22,9 @@ SmartDashboard includes a connection indicator widget which will turn red or gre Robot Program Example --------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public class Robot extends TimedRobot { double counter = 0.0; @@ -34,7 +34,7 @@ Robot Program Example } } - .. code-tab:: c++ + .. code-block:: c++ #include "Robot.h" float counter = 0.0; diff --git a/source/docs/software/hardware-apis/motors/servos.rst b/source/docs/software/hardware-apis/motors/servos.rst index 090245dd21..a84c836cdd 100644 --- a/source/docs/software/hardware-apis/motors/servos.rst +++ b/source/docs/software/hardware-apis/motors/servos.rst @@ -6,17 +6,17 @@ Servo motors are a type of motor which integrates positional feedback into the m Constructing a Servo object --------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Servo exampleServo = new Servo(1); - .. code-tab:: c++ + .. code-block:: c++ frc::Servo exampleServo {1}; - .. code-tab:: python + .. code-block:: python exampleServo = wpilib.Servo(1) @@ -25,19 +25,19 @@ A servo object is constructed by passing a channel. Setting Servo Values -------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java exampleServo.set(.5); exampleServo.setAngle(75); - .. code-tab:: c++ + .. code-block:: c++ exampleServo.Set(.5); exampleServo.SetAngle(75); - .. code-tab:: python + .. code-block:: python exampleServo.set(.5) exampleServo.setAngle(75) diff --git a/source/docs/software/hardware-apis/motors/using-motor-controllers.rst b/source/docs/software/hardware-apis/motors/using-motor-controllers.rst index 86890b7b46..cc635bb472 100644 --- a/source/docs/software/hardware-apis/motors/using-motor-controllers.rst +++ b/source/docs/software/hardware-apis/motors/using-motor-controllers.rst @@ -10,9 +10,9 @@ PWM motor controllers can be controlled in the same way as a CAN motor controlle .. note:: The ``Spark`` and ``VictorSP`` classes are used here as an example; other PWM motor controller classes have exactly the same API. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Spark spark = new Spark(0); // 0 is the RIO PWM port this is connected to @@ -22,7 +22,7 @@ PWM motor controllers can be controlled in the same way as a CAN motor controlle victor.set(0.6); // the % output of the motor, between -1 and 1 - .. code-tab:: c++ + .. code-block:: c++ frc::Spark spark{0}; // 0 is the RIO PWM port this is connected to @@ -32,7 +32,7 @@ PWM motor controllers can be controlled in the same way as a CAN motor controlle victor.Set(0.6); // the % output of the motor, between -1 and 1 - .. code-tab:: python + .. code-block:: python spark = wpilib.Spark(0) # 0 is the RIO PWM port this is connected to diff --git a/source/docs/software/hardware-apis/sensors/accelerometers-software.rst b/source/docs/software/hardware-apis/sensors/accelerometers-software.rst index 2720c18d8a..93085f0a87 100644 --- a/source/docs/software/hardware-apis/sensors/accelerometers-software.rst +++ b/source/docs/software/hardware-apis/sensors/accelerometers-software.rst @@ -23,9 +23,9 @@ AnalogAccelerometer The :code:`AnalogAccelerometer` class (`Java `__, `C++ `__) allows users to read values from a single-axis accelerometer that is connected to one of the roboRIO's analog inputs. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates an analog accelerometer on analog input 0 AnalogAccelerometer accelerometer = new AnalogAccelerometer(0); @@ -39,7 +39,7 @@ The :code:`AnalogAccelerometer` class (`Java `__, `C++ `__) provides support for the ADXL345 accelerometer over the I2C communications bus. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates an ADXL345 accelerometer object on the MXP I2C port // with a measurement range from -8 to 8 G's ADXL345_I2C accelerometer = new ADXL345_I2C(I2C.Port.kMXP, ADXL345_I2C.Range.k8G); - .. code-tab:: c++ + .. code-block:: c++ // Creates an ADXL345 accelerometer object on the MXP I2C port // with a measurement range from -8 to 8 G's @@ -93,15 +93,15 @@ ADXL345_SPI The :code:`ADXL345_SPI` class (`Java `__, `C++ `__) provides support for the ADXL345 accelerometer over the SPI communications bus. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates an ADXL345 accelerometer object on the MXP SPI port // with a measurement range from -8 to 8 G's ADXL345_SPI accelerometer = new ADXL345_SPI(SPI.Port.kMXP, ADXL345_SPI.Range.k8G); - .. code-tab:: c++ + .. code-block:: c++ // Creates an ADXL345 accelerometer object on the MXP SPI port // with a measurement range from -8 to 8 G's @@ -112,15 +112,15 @@ ADXL362 The :code:`ADXL362` class (`Java `__, `C++ `__) provides support for the ADXL362 accelerometer over the SPI communications bus. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates an ADXL362 accelerometer object on the MXP SPI port // with a measurement range from -8 to 8 G's ADXL362 accelerometer = new ADXL362(SPI.Port.kMXP, ADXL362.Range.k8G); - .. code-tab:: c++ + .. code-block:: c++ // Creates an ADXL362 accelerometer object on the MXP SPI port // with a measurement range from -8 to 8 G's @@ -131,15 +131,15 @@ BuiltInAccelerometer The :code:`BuiltInAccelerometer` class (`Java `__, `C++ `__) provides access to the roboRIO's own built-in accelerometer: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates an object for the built-in accelerometer // Range defaults to +- 8 G's BuiltInAccelerometer accelerometer = new BuiltInAccelerometer(); - .. code-tab:: c++ + .. code-block:: c++ // Creates an object for the built-in accelerometer // Range defaults to +- 8 G's @@ -159,9 +159,9 @@ It is recommended to use accelerometers in FRC\ |reg| for any application which For detecting collisions, it is often more robust to measure the jerk than the acceleration. The jerk is the derivative (or rate of change) of acceleration, and indicates how rapidly the forces on the robot are changing - the sudden impulse from a collision causes a sharp spike in the jerk. Jerk can be determined by simply taking the difference of subsequent acceleration measurements, and dividing by the time between them: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java double prevXAccel = 0.0; double prevYAccel = 0.0; @@ -183,7 +183,7 @@ For detecting collisions, it is often more robust to measure the jerk than the a prevYAccel = yAccel; } - .. code-tab:: c++ + .. code-block:: c++ double prevXAccel = 0.0; double prevYAccel = 0.0; @@ -206,9 +206,9 @@ For detecting collisions, it is often more robust to measure the jerk than the a Most accelerometers legal for FRC use are quite noisy, and it is often a good idea to combine them with the :code:`LinearFilter` class (`Java `__, `C++ `__) to reduce the noise: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java BuiltInAccelerometer accelerometer = new BuiltInAccelerometer(); @@ -222,7 +222,7 @@ Most accelerometers legal for FRC use are quite noisy, and it is often a good id double filteredXAccel = xAccelFilter.calculate(accelerometer.getX()); } - .. code-tab:: c++ + .. code-block:: c++ frc::BuiltInAccelerometer accelerometer; diff --git a/source/docs/software/hardware-apis/sensors/analog-inputs-software.rst b/source/docs/software/hardware-apis/sensors/analog-inputs-software.rst index 38c7866096..8fb1c6f5ad 100644 --- a/source/docs/software/hardware-apis/sensors/analog-inputs-software.rst +++ b/source/docs/software/hardware-apis/sensors/analog-inputs-software.rst @@ -19,14 +19,14 @@ Initializing an AnalogInput An :code:`AnalogInput` may be initialized as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes an AnalogInput on port 0 AnalogInput analog = new AnalogInput(0); - .. code-tab:: c++ + .. code-block:: c++ // Initializes an AnalogInput on port 0 frc::AnalogInput analog{0}; @@ -44,16 +44,16 @@ Oversampling When oversampling is enabled, the FPGA will add multiple consecutive samples together, and return the accumulated value. Users may specify the number of *bits* of oversampling - for :math:`n` bits of oversampling, the number of samples added together is :math:`2^{n}`: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Sets the AnalogInput to 4-bit oversampling. 16 samples will be added together. // Thus, the reported values will increase by about a factor of 16, and the update // rate will decrease by a similar amount. analog.setOversampleBits(4); - .. code-tab:: c++ + .. code-block:: c++ // Sets the AnalogInput to 4-bit oversampling. 16 samples will be added together. // Thus, the reported values will increase by about a factor of 16, and the update @@ -65,15 +65,15 @@ Averaging Averaging behaves much like oversampling, except the accumulated values are divided by the number of samples so that the scaling of the returned values does not change. This is often more-convenient, but occasionally the additional roundoff error introduced by the rounding is undesirable. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Sets the AnalogInput to 4-bit averaging. 16 samples will be averaged together. // The update rate will decrease by a factor of 16. analog.setAverageBits(4); - .. code-tab:: c++ + .. code-block:: c++ // Sets the AnalogInput to 4-bit averaging. 16 samples will be averaged together. // The update rate will decrease by a factor of 16. @@ -91,13 +91,13 @@ getValue The :code:`getValue` method returns the raw instantaneous measured value from the analog input, without applying any calibration and ignoring oversampling and averaging settings. The returned value is an integer. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java analog.getValue(); - .. code-tab:: c++ + .. code-block:: c++ analog.GetValue(); @@ -106,13 +106,13 @@ getVoltage The :code:`getVoltage` method returns the instantaneous measured voltage from the analog input. Oversampling and averaging settings are ignored, but the value is rescaled to represent a voltage. The returned value is a double. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java analog.getVoltage(); - .. code-tab:: c++ + .. code-block:: c++ analog.GetVoltage(); @@ -121,13 +121,13 @@ getAverageValue The :code:`getAverageValue` method returns the averaged value from the analog input. The value is not rescaled, but oversampling and averaging are both applied. The returned value is an integer. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java analog.getAverageValue(); - .. code-tab:: c++ + .. code-block:: c++ analog.GetAverageValue(); @@ -136,13 +136,13 @@ getAverageVoltage The :code:`getAverageVoltage` method returns the averaged voltage from the analog input. Rescaling, oversampling, and averaging are all applied. The returned value is a double. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java analog.getAverageVoltage(); - .. code-tab:: c++ + .. code-block:: c++ analog.GetAverageVoltage(); @@ -153,9 +153,9 @@ Accumulator Analog input channels 0 and 1 additionally support an accumulator, which integrates (adds up) the signal indefinitely, so that the returned value is the sum of all past measured values. Oversampling and averaging are applied prior to accumulation. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Sets the initial value of the accumulator to 0 // This is the "starting point" from which the value will change over time @@ -174,7 +174,7 @@ Analog input channels 0 and 1 additionally support an accumulator, which integra // Resets the accumulator to the initial value analog.resetAccumulator(); - .. code-tab:: c++ + .. code-block:: c++ // Sets the initial value of the accumulator to 0 // This is the "starting point" from which the value will change over time @@ -198,9 +198,9 @@ Obtaining synchronized count and value Sometimes, it is necessarily to obtain matched measurements of the count and the value. This can be done using the :code:`getAccumulatorOutput` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Instantiate an AccumulatorResult object to hold the matched measurements AccumulatorResult result = new AccumulatorResult(); @@ -212,7 +212,7 @@ Sometimes, it is necessarily to obtain matched measurements of the count and the long count = result.count; long value = result.value; - .. code-tab:: c++ + .. code-block:: c++ // The count and value variables to fill int_64t count; diff --git a/source/docs/software/hardware-apis/sensors/analog-potentiometers-software.rst b/source/docs/software/hardware-apis/sensors/analog-potentiometers-software.rst index 8277a7680f..600f47a9e7 100644 --- a/source/docs/software/hardware-apis/sensors/analog-potentiometers-software.rst +++ b/source/docs/software/hardware-apis/sensors/analog-potentiometers-software.rst @@ -16,9 +16,9 @@ The AnalogPotentiometer class An AnalogPotentiometer can be initialized as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes an AnalogPotentiometer on analog port 0 // The full range of motion (in meaningful external units) is 0-180 (this could be degrees, for instance) @@ -26,7 +26,7 @@ An AnalogPotentiometer can be initialized as follows: AnalogPotentiometer pot = new AnalogPotentiometer(0, 180, 30); - .. code-tab:: c++ + .. code-block:: c++ // Initializes an AnalogPotentiometer on analog port 0 // The full range of motion (in meaningful external units) is 0-180 (this could be degrees, for instance) @@ -41,9 +41,9 @@ Customizing the underlying AnalogInput If the user would like to apply custom settings to the underlying :code:`AnalogInput` used by the :code:`AnalogPotentiometer`, an alternative constructor may be used in which the :code:`AnalogInput` is injected: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes an AnalogInput on port 0, and enables 2-bit averaging AnalogInput input = new AnalogInput(0); @@ -55,7 +55,7 @@ If the user would like to apply custom settings to the underlying :code:`AnalogI AnalogPotentiometer pot = new AnalogPotentiometer(input, 180, 30); - .. code-tab:: c++ + .. code-block:: c++ // Initializes an AnalogInput on port 0, and enables 2-bit averaging frc::AnalogInput input{0}; @@ -72,13 +72,13 @@ Reading values from the AnalogPotentiometer The scaled value can be read by simply calling the :code:`get` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java pot.get(); - .. code-tab:: c++ + .. code-block:: c++ pot.Get(); diff --git a/source/docs/software/hardware-apis/sensors/counters.rst b/source/docs/software/hardware-apis/sensors/counters.rst index 7a67297a00..fc7b7048d7 100644 --- a/source/docs/software/hardware-apis/sensors/counters.rst +++ b/source/docs/software/hardware-apis/sensors/counters.rst @@ -30,9 +30,9 @@ Two-pulse mode In two-pulse mode, the :code:`Counter` will count up for every edge/pulse on the specified "up channel," and down for every edge/pulse on the specified "down channel." A counter can be initialized in two-pulse with the following code: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Create a new Counter object in two-pulse mode Counter counter = new Counter(Counter.Mode.k2Pulse); @@ -48,7 +48,7 @@ In two-pulse mode, the :code:`Counter` will count up for every edge/pulse on the counter.setDownSourceEdge(true, true); } - .. code-tab:: c++ + .. code-block:: c++ // Create a new Counter object in two-pulse mode frc::Counter counter{frc::Counter::Mode::k2Pulse}; @@ -67,9 +67,9 @@ Semi-period mode In semi-period mode, the :code:`Counter` will count the duration of the pulses on a channel, either from a rising edge to the next falling edge, or from a falling edge to the next rising edge. A counter can be initialized in semi-period mode with the following code: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Create a new Counter object in two-pulse mode Counter counter = new Counter(Counter.Mode.kSemiperiod); @@ -83,7 +83,7 @@ In semi-period mode, the :code:`Counter` will count the duration of the pulses o counter.setSemiPeriodMode(true); } - .. code-tab:: c++ + .. code-block:: c++ // Create a new Counter object in two-pulse mode frc::Counter counter{frc::Counter::Mode::kSemiperiod}; @@ -97,14 +97,14 @@ In semi-period mode, the :code:`Counter` will count the duration of the pulses o To get the pulse width, call the :code:`getPeriod()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Return the measured pulse width in seconds counter.getPeriod(); - .. code-tab:: c++ + .. code-block:: c++ // Return the measured pulse width in seconds counter.GetPeriod(); @@ -114,9 +114,9 @@ Pulse-length mode In pulse-length mode, the counter will count either up or down depending on the length of the pulse. A pulse below the specified threshold time will be interpreted as a forward count and a pulse above the threshold is a reverse count. This is useful for some gear tooth sensors which encode direction in this manner. A counter can be initialized in this mode as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Create a new Counter object in two-pulse mode Counter counter = new Counter(Counter.Mode.kPulseLength); @@ -133,7 +133,7 @@ In pulse-length mode, the counter will count either up or down depending on the counter.setPulseLengthMode(.05) } - .. code-tab:: c++ + .. code-block:: c++ // Create a new Counter object in two-pulse mode frc::Counter counter{frc::Counter::Mode::kPulseLength}; @@ -153,9 +153,9 @@ External direction mode In external direction mode, the counter counts either up or down depending on the level on the second channel. If the direction source is low, the counter will increase; if the direction source is high, the counter will decrease (to reverse this, see the next section). A counter can be initialized in this mode as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Create a new Counter object in two-pulse mode Counter counter = new Counter(Counter.Mode.kExternalDirection); @@ -170,7 +170,7 @@ In external direction mode, the counter counts either up or down depending on th counter.setUpSourceEdge(true, true); } - .. code-tab:: c++ + .. code-block:: c++ // Create a new Counter object in two-pulse mode frc::Counter counter{frc::Counter::Mode::kExternalDirection}; @@ -192,9 +192,9 @@ Configuring counter parameters Apart from the mode-specific configurations, the :code:`Counter` class offers a number of additional configuration methods: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Configures the counter to return a distance of 4 for every 256 pulses // Also changes the units of getRate @@ -213,7 +213,7 @@ Apart from the mode-specific configurations, the :code:`Counter` class offers a // Can be between 1 and 127 samples counter.setSamplesToAverage(5); - .. code-tab:: c++ + .. code-block:: c++ // Configures the counter to return a distance of 4 for every 256 pulses // Also changes the units of getRate @@ -242,14 +242,14 @@ Count Users can obtain the current count with the :code:`get()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // returns the current count counter.get(); - .. code-tab:: c++ + .. code-block:: c++ // returns the current count counter.Get(); @@ -261,14 +261,14 @@ Distance If the :ref:`distance per pulse ` has been configured, users can obtain the total distance traveled by the counted sensor with the :code:`getDistance()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // returns the current distance counter.getDistance(); - .. code-tab:: c++ + .. code-block:: c++ // returns the current distance counter.GetDistance(); @@ -280,14 +280,14 @@ Rate Users can obtain the current rate of change of the counter with the :code:`getRate()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the current rate of the counter counter.getRate(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the current rate of the counter counter.GetRate(); @@ -297,14 +297,14 @@ Stopped Users can obtain whether the counter is stationary with the :code:`getStopped()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets whether the counter is stopped counter.getStopped(); - .. code-tab:: c++ + .. code-block:: c++ // Gets whether the counter is stopped counter.GetStopped(); @@ -314,14 +314,14 @@ Direction Users can obtain the direction in which the counter last moved with the :code:`getDirection()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the last direction in which the counter moved counter.getDirection(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the last direction in which the counter moved counter.GetDirection(); @@ -333,14 +333,14 @@ Period Users can obtain the duration (in seconds) of the most-recent period with the :code:`getPeriod()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // returns the current period in seconds counter.getPeriod(); - .. code-tab:: c++ + .. code-block:: c++ // returns the current period in seconds counter.GetPeriod(); @@ -350,14 +350,14 @@ Resetting a counter To reset a counter to a distance reading of zero, call the :code:`reset()` method. This is useful for ensuring that the measured distance corresponds to the actual desired physical measurement. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Resets the encoder to read a distance of zero counter.reset(); - .. code-tab:: c++ + .. code-block:: c++ // Resets the encoder to read a distance of zero counter.Reset(); diff --git a/source/docs/software/hardware-apis/sensors/digital-inputs-software.rst b/source/docs/software/hardware-apis/sensors/digital-inputs-software.rst index b9ab3bc004..e2793fe96a 100644 --- a/source/docs/software/hardware-apis/sensors/digital-inputs-software.rst +++ b/source/docs/software/hardware-apis/sensors/digital-inputs-software.rst @@ -14,14 +14,14 @@ The DigitalInput class A :code:`DigitalInput` can be initialized as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes a DigitalInput on DIO 0 DigitalInput input = new DigitalInput(0); - .. code-tab:: c++ + .. code-block:: c++ // Initializes a DigitalInput on DIO 0 frc::DigitalInput input{0}; @@ -31,14 +31,14 @@ Reading the value of the DigitalInput The state of the :code:`DigitalInput` can be polled with the :code:`get` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the value of the digital input. Returns true if the circuit is open. input.get(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the value of the digital input. Returns true if the circuit is open. input.Get(); @@ -52,9 +52,9 @@ Sometimes, it is desirable to use an analog input as a digital input. This can An :code:`AnalogTrigger` may be initialized as follows. As with :code:`AnalogPotentiometer`, an :code:`AnalogInput` may be passed explicitly if the user wishes to customize the sampling settings: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes an AnalogTrigger on port 0 AnalogTrigger trigger0 = new AnalogTrigger(0); @@ -66,7 +66,7 @@ An :code:`AnalogTrigger` may be initialized as follows. As with :code:`AnalogPo // Initializes an AnalogTrigger using the above input AnalogTrigger trigger1 = new AnalogTrigger(input); - .. code-tab:: c++ + .. code-block:: c++ // Initializes an AnalogTrigger on port 0 frc::AnalogTrigger trigger0{0}; @@ -85,9 +85,9 @@ Setting the trigger points To convert the analog signal to a digital one, it is necessary to specify at what values the trigger will enable and disable. These values may be different to avoid "dithering" around the transition point: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Sets the trigger to enable at a raw value of 3500, and disable at a value of 1000 trigger.setLimitsRaw(1000, 3500); @@ -95,7 +95,7 @@ To convert the analog signal to a digital one, it is necessary to specify at wha // Sets the trigger to enable at a voltage of 4 volts, and disable at a value of 1.5 volts trigger.setLimitsVoltage(1.5, 4); - .. code-tab:: c++ + .. code-block:: c++ // Sets the trigger to enable at a raw value of 3500, and disable at a value of 1000 trigger.SetLimitsRaw(1000, 3500); @@ -113,9 +113,9 @@ Limiting the motion of a mechanism Nearly all motorized mechanisms (such as arms and elevators) in FRC\ |reg| should be given some form of "limit switch" to prevent them from damaging themselves at the end of their range of motions. A short example is given below: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Spark spark = new Spark(0); @@ -131,7 +131,7 @@ Nearly all motorized mechanisms (such as arms and elevators) in FRC\ |reg| shoul } } - .. code-tab:: c++ + .. code-block:: c++ // Motor for the mechanism frc::Spark spark{0}; diff --git a/source/docs/software/hardware-apis/sensors/encoders-software.rst b/source/docs/software/hardware-apis/sensors/encoders-software.rst index e65f160862..ab85455312 100644 --- a/source/docs/software/hardware-apis/sensors/encoders-software.rst +++ b/source/docs/software/hardware-apis/sensors/encoders-software.rst @@ -38,15 +38,15 @@ Initializing a Quadrature Encoder A quadrature encoder can be instantiated as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes an encoder on DIO pins 0 and 1 // Defaults to 4X decoding and non-inverted Encoder encoder = new Encoder(0, 1); - .. code-tab:: c++ + .. code-block:: c++ // Initializes an encoder on DIO pins 0 and 1 // Defaults to 4X decoding and non-inverted @@ -63,15 +63,15 @@ The WPILib :code:`Encoder` class can decode encoder signals in three different m 4X decoding offers the greatest precision, but at the potential cost of increased "jitter" in rate measurements. To use a different decoding type, use the following constructor: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes an encoder on DIO pins 0 and 1 // 2X encoding and non-inverted Encoder encoder = new Encoder(0, 1, false, Encoder.EncodingType.k2X); - .. code-tab:: c++ + .. code-block:: c++ // Initializes an encoder on DIO pins 0 and 1 // 2X encoding and non-inverted @@ -86,9 +86,9 @@ Configuring Quadrature Encoder Parameters The :code:`Encoder` class offers a number of configuration methods: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Configures the encoder to return a distance of 4 for every 256 pulses // Also changes the units of getRate @@ -107,7 +107,7 @@ The :code:`Encoder` class offers a number of configuration methods: // Can be between 1 and 127 samples encoder.setSamplesToAverage(5); - .. code-tab:: c++ + .. code-block:: c++ // Configures the encoder to return a distance of 4 for every 256 pulses // Also changes the units of getRate @@ -138,14 +138,14 @@ Distance Users can obtain the total distance traveled by the encoder with the :code:`getDistance()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the distance traveled encoder.getDistance(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the distance traveled encoder.GetDistance(); @@ -157,14 +157,14 @@ Rate Users can obtain the current rate of change of the encoder with the :code:`getRate()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the current rate of the encoder encoder.getRate(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the current rate of the encoder encoder.GetRate(); @@ -174,14 +174,14 @@ Stopped Users can obtain whether the encoder is stationary with the :code:`getStopped()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets whether the encoder is stopped encoder.getStopped(); - .. code-tab:: c++ + .. code-block:: c++ // Gets whether the encoder is stopped encoder.GetStopped(); @@ -191,14 +191,14 @@ Direction Users can obtain the direction in which the encoder last moved with the :code:`getDirection()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the last direction in which the encoder moved encoder.getDirection(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the last direction in which the encoder moved encoder.GetDirection(); @@ -208,14 +208,14 @@ Period Users can obtain the period of the encoder pulses (in seconds) with the :code:`getPeriod()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the current period of the encoder encoder.getPeriod(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the current period of the encoder encoder.GetPeriod(); @@ -225,14 +225,14 @@ Resetting a Quadrature Encoder To reset a quadrature encoder to a distance reading of zero, call the :code:`reset()` method. This is useful for ensuring that the measured distance corresponds to the actual desired physical measurement, and is often called during a :ref:`homing ` routine: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Resets the encoder to read a distance of zero encoder.reset(); - .. code-tab:: c++ + .. code-block:: c++ // Resets the encoder to read a distance of zero encoder.Reset(); @@ -257,14 +257,14 @@ Initializing a Duty Cycle Encoder A duty cycle encoder can be instantiated as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes a duty cycle encoder on DIO pins 0 DutyCycleEncoder encoder = new DutyCycleEncoder(0); - .. code-tab:: c++ + .. code-block:: c++ // Initializes a duty cycle encoder on DIO pins 0 frc::DutyCycleEncoder encoder{0}; @@ -276,14 +276,14 @@ Configuring Duty Cycle Encoder Parameters The :code:`DutyCycleEncoder` class offers a number of configuration methods: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Configures the encoder to return a distance of 4 for every rotation encoder.setDistancePerRotation(4.0); - .. code-tab:: c++ + .. code-block:: c++ // Configures the encoder to return a distance of 4 for every rotation encoder.SetDistancePerRotation(4.0); @@ -295,14 +295,14 @@ Reading Distance from Duty Cycle Encoders Users can obtain the distance measured by the encoder with the :code:`getDistance()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the distance traveled encoder.getDistance(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the distance traveled encoder.GetDistance(); @@ -313,14 +313,14 @@ Detecting a Duty Cycle Encoder is Connected As duty cycle encoders output a continuous set of pulses, it is possible to detect that the encoder has been unplugged. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets if the encoder is connected encoder.isConnected(); - .. code-tab:: c++ + .. code-block:: c++ // Gets if the encoder is connected encoder.IsConnected(); @@ -331,9 +331,9 @@ Resetting a Duty Cycle Encoder To reset an encoder so the current distance is 0, call the :code:`reset()` method. This is useful for ensuring that the measured distance corresponds to the actual desired physical measurement. Unlike quadrature encoders, duty cycle encoders don't need to be homed. However, after reset, the position offset can be stored to be set when the program starts so that the reset doesn't have to be performed again. The :doc:`Preferences class ` provides a method to save and retrieve the values on the roboRIO. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Resets the encoder to read a distance of zero at the current position encoder.reset(); @@ -344,7 +344,7 @@ To reset an encoder so the current distance is 0, call the :code:`reset()` metho // set the position offset to half a rotation encoder.setPositionOffset(0.5); - .. code-tab:: c++ + .. code-block:: c++ // Resets the encoder to read a distance of zero at the current position encoder.Reset(); @@ -371,14 +371,14 @@ Initializing an Analog Encoder An analog encoder can be instantiated as follows: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Initializes a duty cycle encoder on Analog Input pins 0 AnalogEncoder encoder = new AnalogEncoder(0); - .. code-tab:: c++ + .. code-block:: c++ // Initializes a duty cycle encoder on DIO pins 0 frc::AnalogEncoder encoder{0}; @@ -390,14 +390,14 @@ Configuring Analog Encoder Parameters The :code:`AnalogEncoder` class offers a number of configuration methods: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Configures the encoder to return a distance of 4 for every rotation encoder.setDistancePerRotation(4.0); - .. code-tab:: c++ + .. code-block:: c++ // Configures the encoder to return a distance of 4 for every rotation encoder.SetDistancePerRotation(4.0); @@ -409,14 +409,14 @@ Reading Distance from Analog Encoders Users can obtain the distance measured by the encoder with the :code:`getDistance()` method: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Gets the distance measured encoder.getDistance(); - .. code-tab:: c++ + .. code-block:: c++ // Gets the distance measured encoder.GetDistance(); @@ -428,9 +428,9 @@ Resetting an Analog Encoder To reset an analog encoder so the current distance is 0, call the :code:`reset()` method. This is useful for ensuring that the measured distance corresponds to the actual desired physical measurement. Unlike quadrature encoders, duty cycle encoders don't need to be homed. However, after reset, the position offset can be stored to be set when the program starts so that the reset doesn't have to be performed again. The :doc:`Preferences class ` provides a method to save and retrieve the values on the roboRIO. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Resets the encoder to read a distance of zero at the current position encoder.reset(); @@ -441,7 +441,7 @@ To reset an analog encoder so the current distance is 0, call the :code:`reset() // set the position offset to half a rotation encoder.setPositionOffset(0.5); - .. code-tab:: c++ + .. code-block:: c++ // Resets the encoder to read a distance of zero at the current position encoder.Reset(); @@ -464,9 +464,9 @@ Encoders can be used on a robot drive to create a simple "drive to distance" rou .. note:: The following example uses the `Encoder` class, but is similar if other `DutyCycleEncoder` or `AnalogEncoder` is used. However, quadrature encoders are typically better suited for drivetrains since they roll over many times and don't have an absolute position. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creates an encoder on DIO ports 0 and 1 Encoder encoder = new Encoder(0, 1); @@ -501,7 +501,7 @@ Encoders can be used on a robot drive to create a simple "drive to distance" rou } } - .. code-tab:: c++ + .. code-block:: c++ // Creates an encoder on DIO ports 0 and 1. frc::Encoder encoder{0, 1}; @@ -541,9 +541,9 @@ Since quadrature encoders measure *relative* distance, it is often important to .. note:: Homing is not necessary for absolute encoders like duty cycle encoders and analog encoders. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Encoder encoder = new Encoder(0, 1); @@ -563,7 +563,7 @@ Since quadrature encoders measure *relative* distance, it is often important to } } - .. code-tab:: c++ + .. code-block:: c++ frc::Encoder encoder{0,1}; diff --git a/source/docs/software/hardware-apis/sensors/gyros-software.rst b/source/docs/software/hardware-apis/sensors/gyros-software.rst index 3bc051f3b0..720f5b2040 100644 --- a/source/docs/software/hardware-apis/sensors/gyros-software.rst +++ b/source/docs/software/hardware-apis/sensors/gyros-software.rst @@ -18,14 +18,14 @@ The ADIS16448 uses the :code:`ADIS16448_IMU` class (`Java `__ for additional connection types. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // navX MXP using SPI AHRS gyro = new AHRS(SPI.Port.kMXP); - .. code-tab:: c++ + .. code-block:: c++ // navX MXP using SPI AHRS gyro{SPI::Port::kMXP}; @@ -109,16 +109,16 @@ Pigeon The Pigeon should use the :code:`WPI_PigeonIMU` class. The Pigeon can either be connected with CAN or by data cable to a TalonSRX. The `Pigeon IMU User's Guide `__ contains full details on using the Pigeon. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java WPI_PigeonIMU gyro = new WPI_PigeonIMU(0); // Pigeon is on CAN Bus with device ID 0 // OR (choose one or the other based on your connection) TalonSRX talon = new TalonSRX(0); // TalonSRX is on CAN Bus with device ID 0 WPI_PigeonIMU gyro = new WPI_PigeonIMU(talon); // Pigeon uses the talon created above - .. code-tab:: c++ + .. code-block:: c++ WPI_PigeonIMU gyro{0}; // Pigeon is on CAN Bus with device ID 0 // OR (choose one or the other based on your connection) @@ -137,9 +137,9 @@ Displaying the robot heading on the dashboard :ref:`Shuffleboard ` includes a widget for displaying heading data from a gyro in the form of a compass. This can be helpful for viewing the robot heading when sight lines to the robot are obscured: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Use gyro declaration from above here @@ -148,7 +148,7 @@ Displaying the robot heading on the dashboard Shuffleboard.getTab("Example tab").add(gyro); } - .. code-tab:: c++ + .. code-block:: c++ // Use gyro declaration from above here @@ -171,9 +171,9 @@ Example: Tank drive stabilization using turn rate The following example shows how to stabilize heading using a simple P loop closed on the turn rate. Since a robot that is not turning should have a turn rate of zero, the setpoint for the loop is implicitly zero, making this method very simple. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Use gyro declaration from above here @@ -206,7 +206,7 @@ The following example shows how to stabilize heading using a simple P loop close drive.tankDrive(.5 + kP * error, .5 - kP * error); } - .. code-tab:: c++ + .. code-block:: c++ // Use gyro declaration from above here @@ -243,9 +243,9 @@ Example: Tank drive stabilization using heading The following example shows how to stabilize heading using a simple P loop closed on the heading. Unlike in the turn rate example, we will need to set the setpoint to the current heading before starting motion, making this method slightly more-complicated. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Use gyro declaration from above here @@ -286,7 +286,7 @@ The following example shows how to stabilize heading using a simple P loop close drive.tankDrive(.5 + kP * error, .5 - kP * error); } - .. code-tab:: c++ + .. code-block:: c++ // Use gyro declaration from above here @@ -332,9 +332,9 @@ Another common and highly-useful application for a gyro is turning a robot to fa Much like with heading stabilization, this is often accomplished with a PID loop - unlike with stabilization, however, the loop can only be closed on the heading. The following example code will turn the robot to face 90 degrees with a simple P loop: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Use gyro declaration from above here @@ -367,7 +367,7 @@ Much like with heading stabilization, this is often accomplished with a PID loop drive.tankDrive(kP * error, -kP * error); } - .. code-tab:: c++ + .. code-block:: c++ // Use gyro declaration from above here diff --git a/source/docs/software/hardware-apis/sensors/limit-switch.rst b/source/docs/software/hardware-apis/sensors/limit-switch.rst index 6159989009..a2d4a72168 100644 --- a/source/docs/software/hardware-apis/sensors/limit-switch.rst +++ b/source/docs/software/hardware-apis/sensors/limit-switch.rst @@ -8,9 +8,9 @@ Limit switches can have "normally open" or "normally closed" outputs. This will Controlling a Motor with Two Limit Switches ------------------------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java DigitalInput toplimitSwitch = new DigitalInput(0); DigitalInput bottomlimitSwitch = new DigitalInput(1); @@ -42,7 +42,7 @@ Controlling a Motor with Two Limit Switches } } - .. code-tab:: cpp + .. code-block:: cpp frc::DigitalInput toplimitSwitch {0}; frc::DigitalInput bottomlimitSwitch {1}; diff --git a/source/docs/software/kinematics-and-odometry/differential-drive-kinematics.rst b/source/docs/software/kinematics-and-odometry/differential-drive-kinematics.rst index 9e75aca06d..3bbc1302b8 100644 --- a/source/docs/software/kinematics-and-odometry/differential-drive-kinematics.rst +++ b/source/docs/software/kinematics-and-odometry/differential-drive-kinematics.rst @@ -12,9 +12,9 @@ Converting Chassis Speeds to Wheel Speeds ----------------------------------------- The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java) / ``ToWheelSpeeds(ChassisSpeeds speeds)`` (C++) method should be used to convert a ``ChassisSpeeds`` object to a ``DifferentialDriveWheelSpeeds`` object. This is useful in situations where you have to convert a linear velocity (``vx``) and an angular velocity (``omega``) to left and right wheel velocities. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creating my kinematics object: track width of 27 inches DifferentialDriveKinematics kinematics = @@ -33,7 +33,7 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java) / ``ToWheelSpeeds(ChassisSpee // Right velocity double rightVelocity = wheelSpeeds.rightMetersPerSecond; - .. code-tab:: c++ + .. code-block:: c++ // Creating my kinematics object: track width of 27 inches frc::DifferentialDriveKinematics kinematics{27_in}; @@ -51,9 +51,9 @@ Converting Wheel Speeds to Chassis Speeds ----------------------------------------- One can also use the kinematics object to convert individual wheel speeds (left and right) to a singular ``ChassisSpeeds`` object. The ``toChassisSpeeds(DifferentialDriveWheelSpeeds speeds)`` (Java) / ``ToChassisSpeeds(DifferentialDriveWheelSpeeds speeds)`` (C++) method should be used to achieve this. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creating my kinematics object: track width of 27 inches DifferentialDriveKinematics kinematics = @@ -72,7 +72,7 @@ One can also use the kinematics object to convert individual wheel speeds (left // Angular velocity double angularVelocity = chassisSpeeds.omegaRadiansPerSecond; - .. code-tab:: c++ + .. code-block:: c++ // Creating my kinematics object: track width of 27 inches frc::DifferentialDriveKinematics kinematics{27_in}; diff --git a/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst b/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst index 8fe180b7f9..ce17da81af 100644 --- a/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst +++ b/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst @@ -15,9 +15,9 @@ The optional argument is the starting pose of your robot on the field (as a ``Po .. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :ref:`Field Coordinate System ` for more information about the coordinate system. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Creating my odometry object. Here, // our starting pose is 5 meters along the long end of the field and in the @@ -27,7 +27,7 @@ The optional argument is the starting pose of your robot on the field (as a ``Po m_leftEncoder.getDistance(), m_rightEncoder.getDistance(), new Pose2d(5.0, 13.5, new Rotation2d())); - .. code-tab:: c++ + .. code-block:: c++ // Creating my odometry object. Here, // our starting pose is 5 meters along the long end of the field and in the @@ -45,9 +45,9 @@ The ``update`` method can be used to update the robot's position on the field. T .. note:: If the robot is moving forward in a straight line, **both** distances (left and right) must be increasing positively -- the rate of change must be positive. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void periodic() { @@ -60,7 +60,7 @@ The ``update`` method can be used to update the robot's position on the field. T m_rightEncoder.getDistance()); } - .. code-tab:: c++ + .. code-block:: c++ void Periodic() override { // Get the rotation of the robot from the gyro. diff --git a/source/docs/software/kinematics-and-odometry/intro-and-chassis-speeds.rst b/source/docs/software/kinematics-and-odometry/intro-and-chassis-speeds.rst index 31eadd765b..c16791bd3d 100644 --- a/source/docs/software/kinematics-and-odometry/intro-and-chassis-speeds.rst +++ b/source/docs/software/kinematics-and-odometry/intro-and-chassis-speeds.rst @@ -23,16 +23,16 @@ Constructing a ChassisSpeeds object ----------------------------------- The constructor for the ``ChassisSpeeds`` object is very straightforward, accepting three arguments for ``vx``, ``vy``, and ``omega``. In Java, ``vx`` and ``vy`` must be in meters per second. In C++, the units library may be used to provide a linear velocity using any linear velocity unit. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // The robot is moving at 3 meters per second forward, 2 meters // per second to the right, and rotating at half a rotation per // second counterclockwise. var speeds = new ChassisSpeeds(3.0, -2.0, Math.PI); - .. code-tab:: c++ + .. code-block:: c++ // The robot is moving at 3 meters per second forward, 2 meters // per second to the right, and rotating at half a rotation per @@ -47,9 +47,9 @@ A ``ChassisSpeeds`` object can also be created from a set of field-relative spee The static ``ChassisSpeeds.fromFieldRelativeSpeeds`` (Java) / ``ChassisSpeeds::FromFieldRelativeSpeeds`` (C++) method can be used to generate the ``ChassisSpeeds`` object from field-relative speeds. This method accepts the ``vx`` (relative to the field), ``vy`` (relative to the field), ``omega``, and the robot angle. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // The desired field relative speed here is 2 meters per second // toward the opponent's alliance station wall, and 2 meters per @@ -59,7 +59,7 @@ The static ``ChassisSpeeds.fromFieldRelativeSpeeds`` (Java) / ``ChassisSpeeds::F ChassisSpeeds speeds = ChassisSpeeds.fromFieldRelativeSpeeds( 2.0, 2.0, Math.PI / 2.0, Rotation2d.fromDegrees(45.0)); - .. code-tab:: c++ + .. code-block:: c++ // The desired field relative speed here is 2 meters per second // toward the opponent's alliance station wall, and 2 meters per diff --git a/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst b/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst index 4426e22350..3e6472e6c1 100644 --- a/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst +++ b/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst @@ -6,9 +6,9 @@ Constructing the Kinematics Object ---------------------------------- The ``MecanumDriveKinematics`` class accepts four constructor arguments, with each argument being the location of a wheel relative to the robot center (as a ``Translation2d``). The order for the arguments is front left, front right, back left, and back right. The locations for the wheels must be relative to the center of the robot. Positive x values represent moving toward the front of the robot whereas positive y values represent moving toward the left of the robot. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Locations of the wheels relative to the robot center. Translation2d m_frontLeftLocation = new Translation2d(0.381, 0.381); @@ -22,7 +22,7 @@ The ``MecanumDriveKinematics`` class accepts four constructor arguments, with ea ); - .. code-tab:: c++ + .. code-block:: c++ // Locations of the wheels relative to the robot center. frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m}; @@ -39,9 +39,9 @@ Converting Chassis Speeds to Wheel Speeds ----------------------------------------- The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java) / ``ToWheelSpeeds(ChassisSpeeds speeds)`` (C++) method should be used to convert a ``ChassisSpeeds`` object to a ``MecanumDriveWheelSpeeds`` object. This is useful in situations where you have to convert a forward velocity, sideways velocity, and an angular velocity into individual wheel speeds. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Example chassis speeds: 1 meter per second forward, 3 meters // per second to the left, and rotation at 1.5 radians per second @@ -57,7 +57,7 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java) / ``ToWheelSpeeds(ChassisSpee double backLeft = wheelSpeeds.rearLeftMetersPerSecond double backRight = wheelSpeeds.rearRightMetersPerSecond - .. code-tab:: c++ + .. code-block:: c++ // Example chassis speeds: 1 meter per second forward, 3 meters // per second to the left, and rotation at 1.5 radians per second @@ -73,9 +73,9 @@ Field-oriented drive ~~~~~~~~~~~~~~~~~~~~ :ref:`Recall ` that a ``ChassisSpeeds`` object can be created from a set of desired field-oriented speeds. This feature can be used to get wheel speeds from a set of desired field-oriented speeds. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // The desired field relative speed here is 2 meters per second // toward the opponent's alliance station wall, and 2 meters per @@ -88,7 +88,7 @@ Field-oriented drive // Now use this in our kinematics MecanumDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(speeds); - .. code-tab:: c++ + .. code-block:: c++ // The desired field relative speed here is 2 meters per second // toward the opponent's alliance station wall, and 2 meters per @@ -113,9 +113,9 @@ Converting wheel speeds to chassis speeds ----------------------------------------- One can also use the kinematics object to convert a ``MecanumDriveWheelSpeeds`` object to a singular ``ChassisSpeeds`` object. The ``toChassisSpeeds(MecanumDriveWheelSpeeds speeds)`` (Java) / ``ToChassisSpeeds(MecanumDriveWheelSpeeds speeds)`` (C++) method can be used to achieve this. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Example wheel speeds var wheelSpeeds = new MecanumDriveWheelSpeeds(-17.67, 20.51, -13.44, 16.26); @@ -128,7 +128,7 @@ One can also use the kinematics object to convert a ``MecanumDriveWheelSpeeds`` double sideways = chassisSpeeds.vyMetersPerSecond; double angular = chassisSpeeds.omegaRadiansPerSecond; - .. code-tab:: c++ + .. code-block:: c++ // Example wheel speeds frc::MecanumDriveWheelSpeeds wheelSpeeds{-17.67_mps, 20.51_mps, -13.44_mps, 16.26_mps}; diff --git a/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst b/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst index 97e5da185c..004fccc9a5 100644 --- a/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst +++ b/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst @@ -18,9 +18,9 @@ The fourth optional argument is the starting pose of your robot on the field (as .. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :ref:`Field Coordinate System ` for more information about the coordinate system. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Locations of the wheels relative to the robot center. Translation2d m_frontLeftLocation = new Translation2d(0.381, 0.381); @@ -46,7 +46,7 @@ The fourth optional argument is the starting pose of your robot on the field (as new Pose2d(5.0, 13.5, new Rotation2d()) ); - .. code-tab:: c++ + .. code-block:: c++ // Locations of the wheels relative to the robot center. frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m}; @@ -79,9 +79,9 @@ Updating the robot pose ----------------------- The ``update`` method of the odometry class updates the robot position on the field. The update method takes in the gyro angle of the robot, along with a ``MecanumDriveWheelPositions`` object representing the position of each of the 4 wheels on the robot. This ``update`` method must be called periodically, preferably in the ``periodic()`` method of a :ref:`Subsystem `. The ``update`` method returns the new updated pose of the robot. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void periodic() { @@ -97,7 +97,7 @@ The ``update`` method of the odometry class updates the robot position on the fi m_pose = m_odometry.update(gyroAngle, wheelPositions); } - .. code-tab:: c++ + .. code-block:: c++ void Periodic() override { // Get my wheel positions diff --git a/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst b/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst index 9e6ecc2249..ff2d4d6151 100644 --- a/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst +++ b/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst @@ -19,9 +19,9 @@ The ``SwerveDriveKinematics`` class accepts a variable number of constructor arg The locations for the modules must be relative to the center of the robot. Positive x values represent moving toward the front of the robot whereas positive y values represent moving toward the left of the robot. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Locations for the swerve drive modules relative to the robot center. Translation2d m_frontLeftLocation = new Translation2d(0.381, 0.381); @@ -34,7 +34,7 @@ The locations for the modules must be relative to the center of the robot. Posit m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation ); - .. code-tab:: c++ + .. code-block:: c++ // Locations for the swerve drive modules relative to the robot center. frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m}; @@ -53,9 +53,9 @@ The ``toSwerveModuleStates(ChassisSpeeds speeds)`` (Java) / ``ToSwerveModuleStat The elements in the array that is returned by this method are the same order in which the kinematics object was constructed. For example, if the kinematics object was constructed with the front left module location, front right module location, back left module location, and the back right module location in that order, the elements in the array would be the front left module state, front right module state, back left module state, and back right module state in that order. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Example chassis speeds: 1 meter per second forward, 3 meters // per second to the left, and rotation at 1.5 radians per second @@ -77,7 +77,7 @@ The elements in the array that is returned by this method are the same order in // Back right module state SwerveModuleState backRight = moduleStates[3]; - .. code-tab:: c++ + .. code-block:: c++ // Example chassis speeds: 1 meter per second forward, 3 meters // per second to the left, and rotation at 1.5 radians per second @@ -95,13 +95,13 @@ The ``SwerveModuleState`` class contains a static ``optimize()`` (Java) / ``Opti This method takes two parameters: the desired state (usually from the ``toSwerveModuleStates`` method) and the current angle. It will return the new optimized state which you can use as the setpoint in your feedback control loop. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java var frontLeftOptimized = SwerveModuleState.optimize(frontLeft, new Rotation2d(m_turningEncoder.getDistance())); - .. code-tab:: c++ + .. code-block:: c++ auto flOptimized = frc::SwerveModuleState::Optimize(fl, units::radian_t(m_turningEncoder.GetDistance())); @@ -110,9 +110,9 @@ Field-oriented drive ^^^^^^^^^^^^^^^^^^^^ :ref:`Recall ` that a ``ChassisSpeeds`` object can be created from a set of desired field-oriented speeds. This feature can be used to get module states from a set of desired field-oriented speeds. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // The desired field relative speed here is 2 meters per second // toward the opponent's alliance station wall, and 2 meters per @@ -125,7 +125,7 @@ Field-oriented drive // Now use this in our kinematics SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(speeds); - .. code-tab:: c++ + .. code-block:: c++ // The desired field relative speed here is 2 meters per second // toward the opponent's alliance station wall, and 2 meters per @@ -150,9 +150,9 @@ Converting module states to chassis speeds ------------------------------------------ One can also use the kinematics object to convert an array of ``SwerveModuleState`` objects to a singular ``ChassisSpeeds`` object. The ``toChassisSpeeds(SwerveModuleState... states)`` (Java) / ``ToChassisSpeeds(SwerveModuleState... states)`` (C++) method can be used to achieve this. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Example module states var frontLeftState = new SwerveModuleState(23.43, Rotation2d.fromDegrees(-140.19)); @@ -169,7 +169,7 @@ One can also use the kinematics object to convert an array of ``SwerveModuleStat double sideways = chassisSpeeds.vyMetersPerSecond; double angular = chassisSpeeds.omegaRadiansPerSecond; - .. code-tab:: c++ + .. code-block:: c++ // Example module States frc::SwerveModuleState frontLeftState{23.43_mps, Rotation2d(-140.19_deg)}; diff --git a/source/docs/software/kinematics-and-odometry/swerve-drive-odometry.rst b/source/docs/software/kinematics-and-odometry/swerve-drive-odometry.rst index 77239ee5fb..bebdeedfdd 100644 --- a/source/docs/software/kinematics-and-odometry/swerve-drive-odometry.rst +++ b/source/docs/software/kinematics-and-odometry/swerve-drive-odometry.rst @@ -18,9 +18,9 @@ The fourth optional argument is the starting pose of your robot on the field (as .. note:: 0 degrees / radians represents the robot angle when the robot is facing directly toward your opponent's alliance station. As your robot turns to the left, your gyroscope angle should increase. The ``Gyro`` interface supplies ``getRotation2d``/``GetRotation2d`` that you can use for this purpose. See :ref:`Field Coordinate System ` for more information about the coordinate system. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Locations for the swerve drive modules relative to the robot center. Translation2d m_frontLeftLocation = new Translation2d(0.381, 0.381); @@ -45,7 +45,7 @@ The fourth optional argument is the starting pose of your robot on the field (as m_backRightModule.getPosition() }, new Pose2d(5.0, 13.5, new Rotation2d())); - .. code-tab:: c++ + .. code-block:: c++ // Locations for the swerve drive modules relative to the robot center. frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m}; @@ -74,9 +74,9 @@ The ``update`` method of the odometry class updates the robot position on the fi This ``update`` method must be called periodically, preferably in the ``periodic()`` method of a :ref:`Subsystem `. The ``update`` method returns the new updated pose of the robot. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void periodic() { @@ -91,7 +91,7 @@ This ``update`` method must be called periodically, preferably in the ``periodic }); } - .. code-tab:: c++ + .. code-block:: c++ void Periodic() override { // Get the rotation of the robot from the gyro. diff --git a/source/docs/software/networktables/reading-array-values-published-by-networktables.rst b/source/docs/software/networktables/reading-array-values-published-by-networktables.rst index 70111a7966..b7e5a37b5a 100644 --- a/source/docs/software/networktables/reading-array-values-published-by-networktables.rst +++ b/source/docs/software/networktables/reading-array-values-published-by-networktables.rst @@ -19,9 +19,9 @@ Both of the following examples are extremely simplified programs that just illus Writing a Program to Access the Topics -------------------------------------- -.. tabs:: - - .. code-tab:: java +.. tab-set-code:: + + .. code-block:: java DoubleArraySubscriber areasSub; @@ -44,7 +44,7 @@ Writing a Program to Access the Topics System.out.println(); } - .. code-tab:: cpp + .. code-block:: cpp nt::DoubleArraySubscriber areasSub; @@ -65,7 +65,7 @@ Writing a Program to Access the Topics std::cout << std::endl; } - .. code-tab:: python + .. code-block:: python def robotInit(self): table = ntcore.NetworkTableInstance.getDefault().getTable("GRIP/mycontoursReport") diff --git a/source/docs/software/networktables/robot-program.rst b/source/docs/software/networktables/robot-program.rst index cf92719a1a..e8300a2e32 100644 --- a/source/docs/software/networktables/robot-program.rst +++ b/source/docs/software/networktables/robot-program.rst @@ -5,9 +5,9 @@ In a robot program, a NetworkTables server is automatically started on the defau The example robot program below publishes incrementing X and Y values to a table named ``datatable``. The values for X and Y can be easily viewed using the OutlineViewer program that shows the NetworkTables hierarchy and all the values associated with each topic. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java package edu.wpi.first.wpilibj.templates; @@ -49,7 +49,7 @@ The example robot program below publishes incrementing X and Y values to a table } } - .. code-tab:: c++ + .. code-block:: c++ #include #include @@ -92,7 +92,7 @@ The example robot program below publishes incrementing X and Y values to a table START_ROBOT_CLASS(EasyNetworkExample) - .. code-tab:: python + .. code-block:: python #!/usr/bin/env python3 diff --git a/source/docs/software/roborio-info/roborio-brownouts.rst b/source/docs/software/roborio-info/roborio-brownouts.rst index 936e193372..97371cb783 100644 --- a/source/docs/software/roborio-info/roborio-brownouts.rst +++ b/source/docs/software/roborio-info/roborio-brownouts.rst @@ -71,13 +71,13 @@ The NI roboRIO 1.0 does not support custom brownout voltages. It is fixed at 6.3 The NI roboRIO 2.0 adds the option for a software settable brownout level. The default brownout level (Stage 2) of the roboRIO 2.0 is 6.75V. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java RobotController.setBrownoutVoltage(7.0); - .. code-tab:: c++ + .. code-block:: c++ frc::RobotController::SetBrownoutVoltage(7_V); diff --git a/source/docs/software/telemetry/datalog.rst b/source/docs/software/telemetry/datalog.rst index f1fe807436..e7e43dc269 100644 --- a/source/docs/software/telemetry/datalog.rst +++ b/source/docs/software/telemetry/datalog.rst @@ -25,16 +25,16 @@ On startup, all existing log files where a DS has not been connected will be del The most basic usage of DataLogManager only requires a single line of code (typically this would be called from ``robotInit``). This will record all NetworkTables changes to the data log. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java import edu.wpi.first.wpilibj.DataLogManager; // Starts recording to data log DataLogManager.start(); - .. code-tab:: c++ + .. code-block:: c++ #include "frc/DataLogManager.h" @@ -52,9 +52,9 @@ Logging Joystick Data DataLogManager by default does not record joystick data. The ``DriverStation`` class provides support for logging of DS control and joystick data via the ``startDataLog()`` function: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.DriverStation; @@ -68,7 +68,7 @@ DataLogManager by default does not record joystick data. The ``DriverStation`` // (alternatively) Record only DS control data DriverStation.startDataLog(DataLogManager.getLog(), false); - .. code-tab:: c++ + .. code-block:: c++ #include "frc/DataLogManager.h" #include "frc/DriverStation.h" @@ -91,9 +91,9 @@ The ``DataLog`` class (`Java ` can automatically log telemetry from the controller by calling the following in its constructor: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putData("Arm PID", armPIDController); - .. code-tab:: cpp + .. code-block:: cpp frc::SmartDashboard::PutData("Arm PID", &armPIDController); diff --git a/source/docs/software/telemetry/writing-sendable-classes.rst b/source/docs/software/telemetry/writing-sendable-classes.rst index 436bba551b..2f7fd63d55 100644 --- a/source/docs/software/telemetry/writing-sendable-classes.rst +++ b/source/docs/software/telemetry/writing-sendable-classes.rst @@ -5,23 +5,21 @@ Since the ``Sendable`` interface only has one method, writing your own classes t For example, here is the implementation of ``initSendable`` from WPILib's ``BangBangController``: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java - :language: java - :lines: 150-158 - :linenos: - :lineno-start: 150 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpimath/src/main/java/edu/wpi/first/math/controller/BangBangController.java + :language: java + :lines: 150-158 + :linenos: + :lineno-start: 150 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpimath/src/main/native/cpp/controller/BangBangController.cpp - :language: cpp - :lines: 58-72 - :linenos: - :lineno-start: 58 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpimath/src/main/native/cpp/controller/BangBangController.cpp + :language: cpp + :lines: 58-72 + :linenos: + :lineno-start: 58 To enable the automatic updating of values by WPILib "in the background", ``Sendable`` data names are bound to getter and setter functions rather than specific data values. If a field that you wish to log has no defined setters and getters, they can be defined inline with a lambda expression. @@ -50,22 +48,20 @@ Since ``Sendable`` allows users to consume arbitrary values from the dashboard, To help users ensure safety when interfacing with dashboard values, ``SendableBuilder`` exposes a ``setSafeState`` method, which is called to place any ``Sendable`` mechanism that actuates based on dashboard input into a safe state. Any potentially hazardous user-written ``Sendable`` implementation should call ``setSafeState`` with a suitable safe state implementation. For example, here is the implementation from the WPILib ``PWMMotorController`` class: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java - :language: java - :lines: 118-124 - :linenos: - :lineno-start: 118 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibj/src/main/java/edu/wpi/first/wpilibj/motorcontrol/PWMMotorController.java + :language: java + :lines: 118-124 + :linenos: + :lineno-start: 118 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp - :language: cpp - :lines: 56-62 - :linenos: - :lineno-start: 56 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp + :language: cpp + :lines: 56-62 + :linenos: + :lineno-start: 56 Additionally, users may call ``builder.setActuator(true)`` to mark any mechanism that might move as a result of ``Sendable`` input as an actuator. Currently, this is used by :ref:`Shuffleboard ` to disable actuator widgets when not in :ref:`LiveWindow ` mode. diff --git a/source/docs/software/vision-processing/grip/using-generated-code-in-a-robot-program.rst b/source/docs/software/vision-processing/grip/using-generated-code-in-a-robot-program.rst index 320fb44d9a..4cc955e167 100644 --- a/source/docs/software/vision-processing/grip/using-generated-code-in-a-robot-program.rst +++ b/source/docs/software/vision-processing/grip/using-generated-code-in-a-robot-program.rst @@ -23,9 +23,9 @@ writing your robot program. When writing your own program be aware of the follow Iterative program definitions ----------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java package org.usfirst.frc.team190.robot; @@ -65,9 +65,9 @@ In this first part of the program you can see all the import statements for the - **imgLock** is a variable to synchronize access to the data being simultaneously updated with each image acquisition pass and the code that's processing the coordinates and steering the robot. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void robotInit() { @@ -103,9 +103,9 @@ in order to find its center, then saves that value in the variable centerX. Note this makes sure the main robot thread will always have the most up-to-date value of the variable, as long as it also uses **synchronized** blocks to read the variable. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void autonomousPeriodic() { diff --git a/source/docs/software/vision-processing/introduction/cameraserver-class.rst b/source/docs/software/vision-processing/introduction/cameraserver-class.rst index b61a42515d..6feded250f 100644 --- a/source/docs/software/vision-processing/introduction/cameraserver-class.rst +++ b/source/docs/software/vision-processing/introduction/cameraserver-class.rst @@ -82,9 +82,9 @@ When a new image is captured by the camera, both the CvSink and the MjpegServer The above graph is what the following CameraServer snippet creates: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.cscore.CvSink; @@ -99,7 +99,7 @@ The above graph is what the following CameraServer snippet creates: // Creates the CvSource and MjpegServer [2] and connects them CvSource outputStream = CameraServer.putVideo("Blur", 640, 480); - .. code-tab:: c++ + .. code-block:: c++ #include "cameraserver/CameraServer.h" @@ -114,9 +114,9 @@ The above graph is what the following CameraServer snippet creates: The CameraServer implementation effectively does the following at the cscore level (for explanation purposes). CameraServer takes care of many of the details such as creating unique names for all cscore objects and automatically selecting port numbers. CameraServer also keeps a singleton registry of created objects so they aren't destroyed if they go out of scope. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java import edu.wpi.cscore.CvSink; import edu.wpi.cscore.CvSource; @@ -137,7 +137,7 @@ The CameraServer implementation effectively does the following at the cscore lev MjpegServer mjpegServer2 = new MjpegServer("serve_Blur", 1182); mjpegServer2.setSource(outputStream); - .. code-tab:: c++ + .. code-block:: c++ #include "cscore_oo.h" diff --git a/source/docs/software/vision-processing/roborio/using-multiple-cameras.rst b/source/docs/software/vision-processing/roborio/using-multiple-cameras.rst index 58707580a8..4c2156ad8a 100644 --- a/source/docs/software/vision-processing/roborio/using-multiple-cameras.rst +++ b/source/docs/software/vision-processing/roborio/using-multiple-cameras.rst @@ -6,9 +6,9 @@ Switching the Driver Views If you're interested in just switching what the driver sees, and are using SmartDashboard, the SmartDashboard CameraServer Stream Viewer has an option ("Selected Camera Path") that reads the given :term:`NetworkTables` key and changes the "Camera Choice" to that value (displaying that camera). The robot code then just needs to set the :term:`NetworkTables` key to the correct camera name. Assuming "Selected Camera Path" is set to "CameraSelection", the following code uses the joystick 1 trigger button state to show camera1 and camera2. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java UsbCamera camera1; UsbCamera camera2; @@ -34,7 +34,7 @@ If you're interested in just switching what the driver sees, and are using Smart } } - .. code-tab:: c++ + .. code-block:: c++ cs::UsbCamera camera1; cs::UsbCamera camera2; @@ -61,9 +61,9 @@ If you're interested in just switching what the driver sees, and are using Smart If you're using some other dashboard, you can change the camera used by the camera server dynamically. If you open a stream viewer nominally to camera1, the robot code will change the stream contents to either camera1 or camera2 based on the joystick trigger. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java UsbCamera camera1; UsbCamera camera2; @@ -88,7 +88,7 @@ If you're using some other dashboard, you can change the camera used by the came } } - .. code-tab:: c++ + .. code-block:: c++ cs::UsbCamera camera1; cs::UsbCamera camera2; @@ -118,9 +118,9 @@ Keeping Streams Open By default, the cscore library is pretty aggressive in turning off cameras not in use. What this means is that when you switch cameras, it may disconnect from the camera not in use, so switching back will have some delay as it reconnects to the camera. To keep both camera connections open, use the ``SetConnectionStrategy()`` method to tell the library to keep the streams open, even if you aren't using them. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java UsbCamera camera1; UsbCamera camera2; @@ -148,7 +148,7 @@ By default, the cscore library is pretty aggressive in turning off cameras not i } } - .. code-tab:: c++ + .. code-block:: c++ cs::UsbCamera camera1; cs::UsbCamera camera2; diff --git a/source/docs/software/vision-processing/wpilibpi/basic-vision-example.rst b/source/docs/software/vision-processing/wpilibpi/basic-vision-example.rst index 889c5c080a..e67a8a15a4 100644 --- a/source/docs/software/vision-processing/wpilibpi/basic-vision-example.rst +++ b/source/docs/software/vision-processing/wpilibpi/basic-vision-example.rst @@ -3,9 +3,9 @@ Basic Vision Example This is an example of a basic vision setup that posts the target's location in the aiming coordinate system described :ref:`here ` to NetworkTables, and uses CameraServer to display a bounding rectangle of the contour detected. This example will display the framerate of the processing code on the images sent to CameraServer. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py from cscore import CameraServer import ntcore diff --git a/source/docs/software/vision-processing/wpilibpi/image-thresholding.rst b/source/docs/software/vision-processing/wpilibpi/image-thresholding.rst index 881e94acdb..0c0fa970f7 100644 --- a/source/docs/software/vision-processing/wpilibpi/image-thresholding.rst +++ b/source/docs/software/vision-processing/wpilibpi/image-thresholding.rst @@ -17,9 +17,9 @@ Unlike RGB, HSV allows you to not only filter based on the colors of the pixels, You can use OpenCV to convert a BGR image matrix to HSV. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py hsv_img = cv2.cvtColor(input_img, cv2.COLOR_BGR2HSV) @@ -35,9 +35,9 @@ We will use this field image as an example for the whole process of image proces By thresholding the image using HSV, you can separate the image into the vision target (foreground), and the other things that the camera sees (background). The following code example converts a HSV image into a binary image by thresholding with HSV values. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py binary_img = cv2.inRange(hsv_img, (min_hue, min_sat, min_val), (max_hue, max_sat, max_val)) diff --git a/source/docs/software/vision-processing/wpilibpi/morphological-operations.rst b/source/docs/software/vision-processing/wpilibpi/morphological-operations.rst index 328dee83a6..7e62ef1f1d 100644 --- a/source/docs/software/vision-processing/wpilibpi/morphological-operations.rst +++ b/source/docs/software/vision-processing/wpilibpi/morphological-operations.rst @@ -27,9 +27,9 @@ Erosion Erosion in computer vision is similar to erosion on soil. It takes away from the borders of foreground objects. This process can remove noise from the background. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py kernel = np.ones((3, 3), np.uint8) binary_img = cv2.erode(binary_img, kernel, iterations = 1) @@ -44,9 +44,9 @@ Dilation Dilation is opposite of erosion. Instead of taking away from the borders, it adds to them. This process can remove small holes inside a larger region. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py kernel = np.ones((3, 3), np.uint8) binary_img = cv2.dilate(binary_img, kernel, iterations = 1) @@ -61,9 +61,9 @@ Opening Opening is erosion followed by dilation. This process removes noise without affecting the shape of larger features. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py kernel = np.ones((3, 3), np.uint8) binary_img = cv2.morphologyEx(binary_img, cv2.MORPH_OPEN, kernel) @@ -78,9 +78,9 @@ Closing Closing is dilation followed by erosion. This process removes small holes or breaks without affecting the shape of larger features. -.. tabs:: +.. tab-set-block:: - .. code-tab:: py + .. code-block:: py kernel = np.ones((3, 3), np.uint8) binary_img = cv2.morphologyEx(binary_img, cv2.MORPH_CLOSE, kernel) diff --git a/source/docs/software/vision-processing/wpilibpi/using-cameraserver.rst b/source/docs/software/vision-processing/wpilibpi/using-cameraserver.rst index 736fefa442..702f2e8db6 100644 --- a/source/docs/software/vision-processing/wpilibpi/using-cameraserver.rst +++ b/source/docs/software/vision-processing/wpilibpi/using-cameraserver.rst @@ -6,9 +6,9 @@ Grabbing Frames from CameraServer The WPILibPi image comes with all the necessary libraries to make your own vision processing system. In order to get the current frame from the camera, you can use the CameraServer library. For information about CameraServer, the :ref:`docs/software/vision-processing/introduction/cameraserver-class:Read and Process Video: CameraServer Class`. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py from cscore import CameraServer import cv2 @@ -39,9 +39,9 @@ Sending frames to CameraServer Sometimes, you may want to send processed video frames back to the CameraServer instance for debugging purposes, or viewing in a dashboard application like Shuffleboard. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py # # CameraServer initialization code here diff --git a/source/docs/software/vision-processing/wpilibpi/working-with-contours.rst b/source/docs/software/vision-processing/wpilibpi/working-with-contours.rst index 5bb6b0a3cb..f6582efed8 100644 --- a/source/docs/software/vision-processing/wpilibpi/working-with-contours.rst +++ b/source/docs/software/vision-processing/wpilibpi/working-with-contours.rst @@ -6,17 +6,17 @@ After thresholding and removing noise with morphological operations, you are now Finding and Filtering Contours ------------------------------ -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py _, contours, _ = cv2.findContours(binary_img, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE) In cases where there is only one vision target, you can just take the largest contour and assume that is the target you are looking for. When there is more than one vision target, you can use size, shape, fullness, and other properties to filter unwanted contours out. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py if len(contours) > 0: largest = contours[0] @@ -41,9 +41,9 @@ Now that you've found the contour(s) that you want, you now want to get informat Center ^^^^^^ -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py rect = cv2.minAreaRect(contour) center, _, _ = rect @@ -52,9 +52,9 @@ Center Corners ^^^^^^^ -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py corners = cv2.convexHull(contour) corners = cv2.approxPolyDP(corners, 0.1 * cv2.arcLength(contour), True) @@ -62,9 +62,9 @@ Corners Rotation ^^^^^^^^ -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py _, _, rotation = cv2.fitEllipse(contour) @@ -75,9 +75,9 @@ Publishing to NetworkTables You can use NetworkTables to send these properties to the Driver Station and the RoboRIO. Additional processing could be done on the Raspberry Pi, or the RoboRIO itself. -.. tabs:: +.. tab-set-code:: - .. code-tab:: py + .. code-block:: py import ntcore diff --git a/source/docs/software/vscode-overview/creating-robot-program.rst b/source/docs/software/vscode-overview/creating-robot-program.rst index c3dd811e73..caff907307 100644 --- a/source/docs/software/vscode-overview/creating-robot-program.rst +++ b/source/docs/software/vscode-overview/creating-robot-program.rst @@ -23,37 +23,34 @@ The :code:`TimedRobot` class is the base class recommended for most users. It p .. note:: A `TimedRobot Skeleton` template is available that removes some informative comments and the autonomous example. You can use this if you're already familiar with `TimedRobot`. The example shown below is of `TimedRobot Skeleton`. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java + :language: java + :lines: 7-55 + :linenos: + :lineno-start: 7 - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java - :language: java - :lines: 7-55 - :linenos: - :lineno-start: 7 - .. group-tab:: C++ - - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp - :language: cpp - :lines: 5-29 - :linenos: - :lineno-start: 5 + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp + :language: cpp + :lines: 5-29 + :linenos: + :lineno-start: 5 Periodic methods are called every 20 ms by default. This can be changed by calling the superclass constructor with the new desired update rate. .. danger:: Changing your robot rate can cause some unintended behavior (loop overruns). Teams can also use `Notifiers `__ to schedule methods at a custom rate. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public Robot() { super(0.03); // Periodic methods will now be called every 30 ms. } - .. code-tab:: c++ + .. code-block:: c++ Robot() : frc::TimedRobot(30_ms) {} diff --git a/source/docs/software/vscode-overview/debugging-robot-program.rst b/source/docs/software/vscode-overview/debugging-robot-program.rst index 2038631932..f478203eb8 100644 --- a/source/docs/software/vscode-overview/debugging-robot-program.rst +++ b/source/docs/software/vscode-overview/debugging-robot-program.rst @@ -37,13 +37,13 @@ Debugging with Print Statements Another way to debug your program is to use print statements in your code and view them using the RioLog in Visual Studio Code or the Driver Station. Print statements should be added with care as they are not very efficient especially when used in high quantities. They should be removed for competition as they can cause loop overruns. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java System.out.print("example"); - .. code-tab:: c++ + .. code-block:: c++ wpi::outs() << "example\n"; diff --git a/source/docs/software/wpilib-tools/robot-simulation/device-sim.rst b/source/docs/software/wpilib-tools/robot-simulation/device-sim.rst index 15a0744f34..b37c4d66f5 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/device-sim.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/device-sim.rst @@ -18,15 +18,15 @@ Simulation device object can be constructed in two ways: - a constructor that accepts the regular hardware object. - a constructor or factory method that accepts the port/index/channel number that the device is connected to. These would be the same number that was used to construct the regular hardware object. This is especially useful for :doc:`unit testing `. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java // create a real encoder object on DIO 2,3 Encoder encoder = new Encoder(2, 3); // create a sim controller for the encoder EncoderSim simEncoder = new EncoderSim(encoder); - .. code-tab:: cpp + .. code-block:: cpp // create a real encoder object on DIO 2,3 frc::Encoder encoder{2, 3}; @@ -38,14 +38,14 @@ Reading and Writing Device Data Each simulation class has getter (``getXxx()``/``GetXxx()``) and setter (``setXxx(value)``/``SetXxx(value)``) functions for each field ``Xxx``. The getter functions will return the same as the getter of the regular device class. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java simEncoder.setCount(100); encoder.getCount(); // 100 simEncoder.getCount(); // 100 - .. code-tab:: cpp + .. code-block:: cpp simEncoder.SetCount(100); encoder.GetCount(); // 100 @@ -62,8 +62,8 @@ In C++, save the ``CallbackStore`` object in the right scope - the callback will .. warning:: Attempting to retrieve a value of a type from a ``HALValue`` containing a different type is undefined behavior. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java NotifyCallback callback = (String name, HALValue value) -> { if (value.getType() == HALValue.kInt) { @@ -74,7 +74,7 @@ In C++, save the ``CallbackStore`` object in the right scope - the callback will store.close(); // cancel the callback - .. code-tab:: cpp + .. code-block:: cpp HAL_NotifyCallback callback = [](const char* name, void* param, const HALValue* value) { if (value->type == HAL_INT) { @@ -93,25 +93,25 @@ The ``SimDeviceSim`` (**not** ``SimDevice``!) class is a general device simulati The ``SimDeviceSim`` object is created using a string key identical to the key the vendor used to construct the underlying ``SimDevice`` in their device class. This key is the one that the device shows up with in the :guilabel:`Other Devices` tab, and is typically of the form ``Prefix:Device Name[index]``. If the key contains ports/index/channel numbers, they can be passed as separate arguments to the ``SimDeviceSim`` constructor. The key contains a prefix that is hidden by default in the SimGUI, it can be shown by selecting the :guilabel:`Show prefix` option. Not including this prefix in the key passed to ``SimDeviceSim`` will not match the device! -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java SimDeviceSim device = new SimDeviceSim(deviceKey, index); - .. code-tab:: cpp + .. code-block:: cpp frc::sim::SimDeviceSim device{deviceKey, index}; Once we have the ``SimDeviceSim``, we can get ``SimValue`` objects representing the device's fields. Type-specific ``SimDouble``, ``SimInt``, ``SimLong``, ``SimBoolean``, and ``SimEnum`` subclasses also exist, and should be used instead of the type-unsafe ``SimValue`` class. These are constructed from the ``SimDeviceSim`` using a string key identical to the one the vendor used to define the field. This key is the one the field appears as in the SimGUI. Attempting to retrieve a ``SimValue`` object outside of simulation or when either the device or field keys are unmatched will return ``null`` - this can cause ``NullPointerException`` in Java or undefined behavior in C++. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java SimDouble field = device.getDouble(fieldKey); field.get(); field.set(value); - .. code-tab:: cpp + .. code-block:: cpp hal::SimDouble field = device.GetDouble(fieldKey); field.Get(); diff --git a/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/drivetrain-model.rst b/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/drivetrain-model.rst index 6d582f6845..f40812f1e3 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/drivetrain-model.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/drivetrain-model.rst @@ -22,8 +22,8 @@ You can calculate the measurement noise of your sensors by taking multiple data .. note:: It is very important to use SI units (i.e. meters and radians) when passing parameters in Java. In C++, the :ref:`units library ` can be used to specify any unit type. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java // Create the simulation model of our drivetrain. DifferentialDrivetrainSim m_driveSim = new DifferentialDrivetrainSim( @@ -41,7 +41,7 @@ You can calculate the measurement noise of your sensors by taking multiple data // l and r position: 0.005 m VecBuilder.fill(0.001, 0.001, 0.001, 0.1, 0.1, 0.005, 0.005)); - .. code-tab:: c++ + .. code-block:: c++ #include @@ -85,8 +85,8 @@ You can calculate the measurement noise of your sensors by taking multiple data .. note:: It is very important to use SI units (i.e. meters and radians) when passing parameters in Java. In C++, the :ref:`units library ` can be used to specify any unit type. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java // Create our feedforward gain constants (from the identification // tool) @@ -111,7 +111,7 @@ You can calculate the measurement noise of your sensors by taking multiple data // l and r position: 0.005 m VecBuilder.fill(0.001, 0.001, 0.001, 0.1, 0.1, 0.005, 0.005)); - .. code-tab:: c++ + .. code-block:: c++ #include #include @@ -166,8 +166,8 @@ You can calculate the measurement noise of your sensors by taking multiple data .. note:: It is very important to use SI units (i.e. meters and radians) when passing parameters in Java. In C++, the :ref:`units library ` can be used to specify any unit type. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java private DifferentialDrivetrainSim m_driveSim = DifferentialDrivetrainSim.createKitbotSim( KitbotMotor.kDualCIMPerSide, // 2 CIMs per side. @@ -176,7 +176,7 @@ You can calculate the measurement noise of your sensors by taking multiple data null // No measurement noise. ); - .. code-tab:: c++ + .. code-block:: c++ #include diff --git a/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/odometry-simgui.rst b/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/odometry-simgui.rst index 57fdbe2337..b514b9f38f 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/odometry-simgui.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/odometry-simgui.rst @@ -8,12 +8,12 @@ Robot Pose Visualization ------------------------ The robot pose can be visualized on the Simulator GUI (during simulation) or on a dashboard such as Glass (on a real robot) by sending the odometry pose over a ``Field2d`` object. A ``Field2d`` can be trivially constructed without any constructor arguments: -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java private Field2d m_field = new Field2d(); - .. code-tab:: c++ + .. code-block:: c++ #include @@ -23,15 +23,15 @@ The robot pose can be visualized on the Simulator GUI (during simulation) or on This ``Field2d`` instance must then be sent over NetworkTables. The best place to do this is in the constructor of your subsystem. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java public Drivetrain() { ... SmartDashboard.putData("Field", m_field); } - .. code-tab:: c++ + .. code-block:: c++ #include @@ -44,8 +44,8 @@ This ``Field2d`` instance must then be sent over NetworkTables. The best place t Finally, the pose from your odometry must be updated periodically into the ``Field2d`` object. Remember that this should be in a general ``periodic()`` method i.e. one that runs both during simulation and during real robot operation. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java public void periodic() { ... @@ -58,7 +58,7 @@ Finally, the pose from your odometry must be updated periodically into the ``Fie m_field.setRobotPose(m_odometry.getPoseMeters()); } - .. code-tab:: c++ + .. code-block:: c++ void Periodic() { ... diff --git a/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/simulation-instance.rst b/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/simulation-instance.rst index 488a0ac38a..70f5f89c62 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/simulation-instance.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/simulation-instance.rst @@ -10,8 +10,8 @@ The ``EncoderSim`` class allows users to set encoder positions and velocities on .. note:: It is not possible to simulate encoders that are directly connected to CAN motor controllers using WPILib classes. For more information about your specific motor controller, please read your vendor's documentation. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java // These represent our regular encoder objects, which we would // create to use on a real robot. @@ -24,7 +24,7 @@ The ``EncoderSim`` class allows users to set encoder positions and velocities on private EncoderSim m_leftEncoderSim = new EncoderSim(m_leftEncoder); private EncoderSim m_rightEncoderSim = new EncoderSim(m_rightEncoder); - .. code-tab:: c++ + .. code-block:: c++ #include #include @@ -48,8 +48,8 @@ Similar to the ``EncoderSim`` class, simulated gyroscope classes also exist for .. note:: It is not possible to simulate certain vendor gyros (i.e. Pigeon IMU and NavX) using WPILib classes. Please read the respective vendors' documentation for information on their simulation support. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java // Create our gyro object like we would on a real robot. private AnalogGyro m_gyro = new AnalogGyro(1); @@ -59,7 +59,7 @@ Similar to the ``EncoderSim`` class, simulated gyroscope classes also exist for // when deploying code to the roboRIO. private AnalogGyroSim m_gyroSim = new AnalogGyroSim(m_gyro); - .. code-tab:: c++ + .. code-block:: c++ #include #include diff --git a/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/updating-drivetrain-model.rst b/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/updating-drivetrain-model.rst index 5918bcc1cc..4d6e218c48 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/updating-drivetrain-model.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/drivesim-tutorial/updating-drivetrain-model.rst @@ -10,8 +10,8 @@ There are three main steps to updating the model: 2. Advance the model forward in time by the nominal periodic timestep (Usually 20 ms). This updates all of the drivetrain's states (i.e. pose, encoder positions and velocities) as if 20 ms had passed. 3. Update simulated sensors with new positions, velocities, and angles to use in other places. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java private PWMSparkMax m_leftMotor = new PWMSparkMax(0); private PWMSparkMax m_rightMotor = new PWMSparkMax(1); @@ -42,7 +42,7 @@ There are three main steps to updating the model: m_gyroSim.setAngle(-m_driveSim.getHeading().getDegrees()); } - .. code-tab:: c++ + .. code-block:: c++ frc::PWMSparkMax m_leftMotor{0}; frc::PWMSparkMax m_rightMotor{1}; diff --git a/source/docs/software/wpilib-tools/robot-simulation/simulation-gui.rst b/source/docs/software/wpilib-tools/robot-simulation/simulation-gui.rst index 7b2efa20db..66234ab075 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/simulation-gui.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/simulation-gui.rst @@ -83,9 +83,9 @@ Determining Simulation from Robot Code In cases where vendor libraries do not compile when running the robot simulation, you can wrap their content with ``RobotBase.isReal()`` which returns a ``boolean``. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java TalonSRX motorLeft; TalonSRX motorRight; diff --git a/source/docs/software/wpilib-tools/robotbuilder/advanced/robotbuilder-writing-pidsubsystem-code.rst b/source/docs/software/wpilib-tools/robotbuilder/advanced/robotbuilder-writing-pidsubsystem-code.rst index cc7f9fda3a..ad8fd30837 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/advanced/robotbuilder-writing-pidsubsystem-code.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/advanced/robotbuilder-writing-pidsubsystem-code.rst @@ -13,9 +13,9 @@ Setting the PID Constants The height constants and PID constants are automatically generated. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public class Elevator extends PIDSubsystem { @@ -35,7 +35,7 @@ The height constants and PID constants are automatically generated. private static final double kF = 0.0; // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS - .. code-tab:: cpp + .. code-block:: cpp // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS static constexpr const double Bottom = 4.6; @@ -51,9 +51,9 @@ The height constants and PID constants are automatically generated. Get Potentiometer Measurement ----------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public double getMeasurement() { @@ -63,7 +63,7 @@ Get Potentiometer Measurement // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SOURCE } - .. code-tab:: cpp + .. code-block:: cpp double Elevator::GetMeasurement() { // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SOURCE @@ -77,9 +77,9 @@ The ``getMeasurement()`` method is used to set the value of the sensor that is p Calculate PID Output -------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void useOutput(double output, double setpoint) { @@ -90,7 +90,7 @@ Calculate PID Output // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=OUTPUT } - .. code-tab:: cpp + .. code-block:: cpp void Elevator::UseOutput(double output, double setpoint) { output += setpoint*kF; diff --git a/source/docs/software/wpilib-tools/robotbuilder/introduction/robotbuilder-created-code.rst b/source/docs/software/wpilib-tools/robotbuilder/introduction/robotbuilder-created-code.rst index a84099292e..c2af7196ad 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/introduction/robotbuilder-created-code.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/introduction/robotbuilder-created-code.rst @@ -16,9 +16,9 @@ For more information on the organization of a Command Based robot, see :doc:`/do Autogenerated Code ------------------ -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS m_chooser.setDefaultOption("Autonomous", new Autonomous()); @@ -26,7 +26,7 @@ Autogenerated Code SmartDashboard.putData("Auto Mode", m_chooser); - .. code-tab:: cpp + .. code-block:: cpp // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS m_chooser.SetDefaultOption("Autonomous", new Autonomous()); @@ -38,13 +38,13 @@ When the robot description is modified and code is re-exported RobotBuilder is d If code inside one of these blocks must be modified, the comments can be removed, but this will prevent further updates from happening later. In the above example, if the //BEGIN and //END comments were removed, then later another required subsystem was added in RobotBuilder, it would not be generated on that next export. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // ROBOTBUILDER TYPE: Robot. - .. code-tab:: cpp + .. code-block:: cpp // ROBOTBUILDER TYPE: Robot. @@ -52,9 +52,9 @@ Additionally, each file has a comment defining the type of file. If this is modi Main Robot Program ------------------ -.. tabs:: +.. tab-set:: - .. tab:: Java + .. tab-item:: Java .. code-block:: java :linenos: @@ -179,7 +179,7 @@ Main Robot Program } - .. tab:: C++ (Header) + .. tab-item:: C++ (Header) .. code-block:: C++ :linenos: @@ -215,7 +215,7 @@ Main Robot Program }; - .. tab:: C++ (Source) + .. tab-item:: C++ (Source) .. code-block:: C++ :linenos: @@ -299,9 +299,9 @@ This is the main program generated by RobotBuilder. There are a number of parts RobotContainer -------------- -.. tabs:: +.. tab-set:: - .. tab:: Java + .. tab-item:: Java .. code-block:: java :linenos: @@ -478,7 +478,7 @@ RobotContainer } - .. tab:: C++ (Header) + .. tab-item:: C++ (Header) .. code-block:: C++ :linenos: @@ -554,7 +554,7 @@ RobotContainer void ConfigureButtonBindings(); }; - .. tab:: C++ (Source) + .. tab-item:: C++ (Source) .. code-block:: cpp :linenos: diff --git a/source/docs/software/wpilib-tools/robotbuilder/introduction/robotbuilder-testing-with-shuffleboard.rst b/source/docs/software/wpilib-tools/robotbuilder/introduction/robotbuilder-testing-with-shuffleboard.rst index 6c7d2491f3..df0967b542 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/introduction/robotbuilder-testing-with-shuffleboard.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/introduction/robotbuilder-testing-with-shuffleboard.rst @@ -24,15 +24,15 @@ The buttons will be generated automatically and will appear on the dashboard scr Adding Commands Manually ------------------------ -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java SmartDashboard.putData("Autonomous Command", new AutonomousCommand()); SmartDashboard.putData("Open Claw", new OpenClaw(m_claw); SmartDashboard.putData("Close Claw", new CloseClaw(m_claw)); - .. code-tab:: cpp + .. code-block:: cpp SmartDashboard::PutData("Autonomous Command", new AutonomousCommand()); SmartDashboard::PutData("Open Claw", new OpenClaw(&m_claw)); diff --git a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-drive-tank.rst b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-drive-tank.rst index b59d8be958..823b972348 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-drive-tank.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-drive-tank.rst @@ -41,10 +41,11 @@ Add two joysticks to the Operator Interface, one is the left stick and the other Create a Method to Write the Motors on the Subsystem ---------------------------------------------------- -.. tabs:: - - .. group-tab:: java +.. tab-set:: + .. tab-item:: java + :sync: java + .. code-block:: java :linenos: :lineno-start: 11 @@ -173,7 +174,8 @@ Create a Method to Write the Motors on the Subsystem } } - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. code-block:: c++ :linenos: @@ -235,7 +237,9 @@ Create a Method to Write the Motors on the Subsystem }; - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Header) + .. code-block:: c++ :linenos: @@ -343,9 +347,10 @@ Create a parameter preset to retrieve joystick values. Java: For the left parame Add the Code to do the Driving ------------------------------ -.. tabs:: +.. tab-set:: - .. group-tab:: java + .. tab-item:: java + :sync: java .. code-block:: java :linenos: @@ -423,7 +428,8 @@ Add the Code to do the Driving } } - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. code-block:: c++ :linenos: @@ -475,7 +481,8 @@ Add the Code to do the Driving // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLES }; - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Header) .. code-block:: c++ :linenos: diff --git a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-command-code.rst b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-command-code.rst index ceeb20d39d..2ebef26e47 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-command-code.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-command-code.rst @@ -13,137 +13,135 @@ This is the definition of the `CloseClaw` command in RobotBuilder. Notice that i Generated CloseClaw Class ------------------------- -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. code-block:: java - :linenos: - :lineno-start: 11 - :emphasize-lines: 42, 53, 59 + .. code-block:: java + :linenos: + :lineno-start: 11 + :emphasize-lines: 42, 53, 59 - // ROBOTBUILDER TYPE: Command. + // ROBOTBUILDER TYPE: Command. - package frc.robot.commands; - import edu.wpi.first.wpilibj2.command.CommandBase; + package frc.robot.commands; + import edu.wpi.first.wpilibj2.command.CommandBase; - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS - import frc.robot.subsystems.Claw; + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + import frc.robot.subsystems.Claw; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS - /** - * - */ - public class CloseClaw extends CommandBase { + /** + * + */ + public class CloseClaw extends CommandBase { - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS - private final Claw m_claw; + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS + private final Claw m_claw; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS - public CloseClaw(Claw subsystem) { + public CloseClaw(Claw subsystem) { - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_SETTING + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_SETTING - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_SETTING - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_SETTING + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES - m_claw = subsystem; - addRequirements(m_claw); + m_claw = subsystem; + addRequirements(m_claw); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES - } + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES + } - // Called when the command is initially scheduled. - @Override - public void initialize() { - m_claw.close(); // (1) - } + // Called when the command is initially scheduled. + @Override + public void initialize() { + m_claw.close(); // (1) + } - // Called every time the scheduler runs while the command is scheduled. - @Override - public void execute() { - } + // Called every time the scheduler runs while the command is scheduled. + @Override + public void execute() { + } - // Called once the command ends or is interrupted. - @Override - public void end(boolean interrupted) { - m_claw.stop(); // (3) - } + // Called once the command ends or is interrupted. + @Override + public void end(boolean interrupted) { + m_claw.stop(); // (3) + } - // Returns true when the command should end. - @Override - public boolean isFinished() { - return m_claw.isGripping(); // (2) - } + // Returns true when the command should end. + @Override + public boolean isFinished() { + return m_claw.isGripping(); // (2) + } - @Override - public boolean runsWhenDisabled() { - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED - return false; + @Override + public boolean runsWhenDisabled() { + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED + return false; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED - } - } + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED + } + } - .. group-tab:: C++ - .. code-block:: cpp - :linenos: - :lineno-start: 11 - :emphasize-lines: 21, 31, 36 + .. code-block:: cpp + :linenos: + :lineno-start: 11 + :emphasize-lines: 21, 31, 36 - // ROBOTBUILDER TYPE: Command. + // ROBOTBUILDER TYPE: Command. - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR - #include "commands/CloseClaw.h" + #include "commands/CloseClaw.h" - CloseClaw::CloseClaw(Claw* m_claw) - :m_claw(m_claw){ + CloseClaw::CloseClaw(Claw* m_claw) + :m_claw(m_claw){ - // Use AddRequirements() here to declare subsystem dependencies - // eg. AddRequirements(m_Subsystem); - SetName("CloseClaw"); - AddRequirements({m_claw}); + // Use AddRequirements() here to declare subsystem dependencies + // eg. AddRequirements(m_Subsystem); + SetName("CloseClaw"); + AddRequirements({m_claw}); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR - } + } - // Called just before this Command runs the first time - void CloseClaw::Initialize() { - m_claw->Close(); // (1) - } + // Called just before this Command runs the first time + void CloseClaw::Initialize() { + m_claw->Close(); // (1) + } - // Called repeatedly when this Command is scheduled to run - void CloseClaw::Execute() { + // Called repeatedly when this Command is scheduled to run + void CloseClaw::Execute() { - } + } - // Make this return true when this Command no longer needs to run execute() - bool CloseClaw::IsFinished() { - return m_claw->IsGripping(); // (2) - } + // Make this return true when this Command no longer needs to run execute() + bool CloseClaw::IsFinished() { + return m_claw->IsGripping(); // (2) + } - // Called once after isFinished returns true - void CloseClaw::End(bool interrupted) { - m_claw->Stop(); // (3) - } + // Called once after isFinished returns true + void CloseClaw::End(bool interrupted) { + m_claw->Stop(); // (3) + } - bool CloseClaw::RunsWhenDisabled() const { - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED - return false; + bool CloseClaw::RunsWhenDisabled() const { + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED + return false; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED - } + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED + } RobotBuilder will generate the class files for the `CloseClaw` command. The command represents the behavior of the claw, that is the operation over time. To operate this very simple claw mechanism the motor needs to operate in the close direction,. The `Claw` subsystem has methods to start the motor running in the right direction and to stop it. The commands responsibility is to run the motor for the correct time. The lines of code that are shown in the boxes are added to add this behavior. diff --git a/source/docs/yearly-overview/2020-Game-Data.rst b/source/docs/yearly-overview/2020-Game-Data.rst index d111e77eb2..e341605464 100644 --- a/source/docs/yearly-overview/2020-Game-Data.rst +++ b/source/docs/yearly-overview/2020-Game-Data.rst @@ -28,9 +28,9 @@ C++/Java In C++ and Java the Game Data is accessed by using the GetGameSpecificMessage method of the DriverStation class. Teams likely want to query the data in a Teleop method such as Teleop Periodic in order to receive the data after it is sent during the match. Make sure to handle the case where the data is an empty string as this is what the data will be until the criteria are reached to enable Position Control for either alliance. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java import edu.wpi.first.wpilibj.DriverStation; @@ -60,7 +60,7 @@ In C++ and Java the Game Data is accessed by using the GetGameSpecificMessage me //Code for no data received yet } - .. code-tab:: c++ + .. code-block:: c++ #include diff --git a/source/docs/zero-to-robot/step-1/intro-to-frc-robot-wiring.rst b/source/docs/zero-to-robot/step-1/intro-to-frc-robot-wiring.rst index 46d2e0178a..0ee8e7d10b 100644 --- a/source/docs/zero-to-robot/step-1/intro-to-frc-robot-wiring.rst +++ b/source/docs/zero-to-robot/step-1/intro-to-frc-robot-wiring.rst @@ -19,9 +19,10 @@ Overview ---- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. figure:: /docs/controls-overviews/images/frc-control-system-layout-rev.svg :alt: Detailed diagram of all of the components and how they are connected. @@ -29,7 +30,8 @@ Overview Diagram courtesy of FRC\ |reg| Team 3161 and Stefen Acepcion. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. figure:: /docs/controls-overviews/images/frc-control-system-layout.svg :alt: Detailed diagram of all of the components and how they are connected. @@ -86,14 +88,16 @@ For a test board, cut piece of 1/4" or 1/2" (6-12 mm) material (wood or plastic) Layout the Core Control System Components ----------------------------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/layout-REV.jpg :alt: A basic wiring layout with CTR components. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/layout.jpg :alt: A basic wiring layout with CTR components. @@ -111,9 +115,10 @@ Using the Dual Lock or hardware, fasten all components to the board. Note that i Attach Robot Side Battery Connector ---------------------------------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV The next step will involve using the Wago connectors on the PDH. To use the Wago connectors, open the lever, insert the wire, then close the lever. Two sizes of Wago connector are found on the PDH: @@ -133,7 +138,8 @@ Attach Robot Side Battery Connector Using a 7/16" (11 mm) box end wrench, remove the nut on the "Batt" side of the main breaker and secure the positive terminal of the battery connector - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/terminal-lug.jpg :alt: Highlights the location of the terminal lugs on the PDP and circuit breaker. @@ -152,9 +158,10 @@ Attach Robot Side Battery Connector Wire Breaker to Power Distribution ---------------------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/circuit-breaker-REV.jpg :alt: Show the circuit breaker wired to the PDH. @@ -168,7 +175,8 @@ Wire Breaker to Power Distribution 2. Using the 7/16" (11 mm) wrench, secure the wire to the "AUX" side of the 120A main breaker. 3. Lift the lever on the positive (red) input terminal of the PDH, insert the wire, then close the terminal. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/circuit-breaker.jpg :alt: Show the circuit breaker wired to the PDP. @@ -186,9 +194,10 @@ Wire Breaker to Power Distribution Insulate power connections -------------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/insulate-REV.jpg :alt: Putting tape around the connectors to insulate them. @@ -197,7 +206,8 @@ Insulate power connections Using electrical tape, insulate the two connections to the 120A breaker. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/insulate.jpg :alt: Putting tape around the connectors to insulate them. @@ -211,9 +221,10 @@ Insulate power connections Motor Controller Power ---------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/pdh-motor-power.jpg :alt: Wiring power from the PDH to motor controllers. @@ -235,7 +246,8 @@ Motor Controller Power 3. Strip the other end of each wire, and crimp on a ring or fork terminal 4. Attach the terminal to the motor controller input terminals (red to +, black to -) - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. raw:: html @@ -294,9 +306,10 @@ After making the connection check to be sure that it is clean and secure: roboRIO Power ------------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/roborio-power-REV.jpg :alt: Power coming from the PDH to the roboRIO. @@ -312,7 +325,8 @@ roboRIO Power 4. Cut and strip the wire. 5. Using a very small flat screwdriver connect the wires to the power input connector of the roboRIO (red to V, black to C). Also make sure that the power connector is screwed down securely to the roboRIO. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/roborio-power.jpg :alt: Power coming from the PDP to the roboRIO. @@ -328,9 +342,10 @@ roboRIO Power Radio Power ----------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/rpm-pdh-power.jpg :alt: Power going from the PDH to the RPM. @@ -346,7 +361,8 @@ Radio Power 4. Cut and strip ~5/16" (~8 mm) from the end of the wire. 5. Connect the wire to the RPM 12V Input terminals. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/vrm-power.jpg :alt: Power going from the PDP to the VRM. @@ -373,9 +389,10 @@ Radio Power Pneumatics Power (Optional) --------------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/ph-pdh-power.jpg :alt: Power going from the PDH to the PH. @@ -395,7 +412,8 @@ Pneumatics Power (Optional) 4. Cut and strip ~5/16" (~8 mm) from the other end of the wire. 5. Connect the wire to the PH input terminals. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/pcm-power.jpg :alt: Power going from the PDP to the PCM. @@ -413,9 +431,10 @@ Pneumatics Power (Optional) Ethernet Cables --------------- -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/rpm.jpg :alt: Picture of the RPM. @@ -428,7 +447,8 @@ Ethernet Cables 1. Connect an Ethernet cable from the RJ45 (Ethernet) socket of the roboRIO to the port on the Radio Power Module labeled roboRIO. 2. Connect an Ethernet cable from the RJ45 socket of the radio closest to the barrel connector socket (labeled 18-24v POE) to the socket labeled WiFi Radio on the RPM - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/radio-ethernet.jpg :alt: Connecting Ethernet from the roboRIO to the PoE cable. @@ -443,9 +463,10 @@ CAN Devices roboRIO to Pneumatics CAN ^^^^^^^^^^^^^^^^^^^^^^^^^ -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/roborio-can.jpg :alt: roboRIO CAN connection. @@ -462,7 +483,8 @@ roboRIO to Pneumatics CAN 3. Measure the length required to reach the CAN terminals of the PCM (either of the two available pairs). Cut and strip ~5/16" (~8 mm) off this end of the wires. 4. Insert the wires into the appropriate color coded CAN terminals on the PH. You may use either of the Yellow/Green terminal pairs on the PH, there is no defined in or out. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/pcm-can.jpg :alt: Connecting CAN wire from the roboRIO to the PCM. @@ -479,9 +501,10 @@ roboRIO to Pneumatics CAN Pneumatics to PD CAN ^^^^^^^^^^^^^^^^^^^^^ -.. tabs:: +.. tab-set:: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/ph-pdh-power.jpg :alt: PH CAN connection. @@ -500,7 +523,8 @@ Pneumatics to PD CAN .. note: See the :ref:`CAN Wiring Basics` if you need to terminate the CAN bus somewhere other than the PDP. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/pdp-can.jpg :alt: Connecting the PCM CAN to the PDP. @@ -520,9 +544,10 @@ Pneumatics to PD CAN Motor Controller Signal Wires ----------------------------- -.. tabs :: +.. tab-set :: - .. group-tab:: PWM + .. tab-item:: PWM + :sync: PWM .. image:: images/how-to-wire-a-simple-robot/pwm.jpg :alt: PWM Cables going from the roboRIO to the Spark Motor Controller. @@ -544,7 +569,8 @@ Motor Controller Signal Wires 3. Connect 1 PWM Y-cable to the 2 PWM cables for the controllers controlling each side of the robot. The brown wire on the Y-cable should match the black wire on the PWM cable. 4. Connect the PWM Y-cables to the PWM ports on the roboRIO. The brown wire should be towards the outside of the roboRIO. It is recommended to connect the left side to PWM 0 and the right side to PWM 1 for the most straightforward programming experience, but any channel will work as long as you note which side goes to which channel and adjust the code accordingly. - .. group-tab:: CAN + .. tab-item:: CAN + :sync: CAN The Spark MAX controllers can also be wired using CAN. When wiring CAN the objective is to create a single complete bus running from the roboRIO on one end and running through all CAN devices on the robot. It is recommended to have either Power Distribution device at the other end of the bus because they have built-in termination. If you do not wish to locate one of these devices at the end of the bus see :ref:`CAN Wiring Basics` for info about terminating yourself. @@ -572,9 +598,10 @@ Requires: Wire stripper, 2 pin cable, Robot Signal Light, 18 AWG (1 :math:`mm^2` Circuit Breakers ---------------- -.. tabs :: +.. tab-set :: - .. group-tab:: REV + .. tab-item:: REV + :sync: REV .. image:: images/how-to-wire-a-simple-robot/40A-breaker-REV.jpg :alt: Installing 40A breakers in the PDP. @@ -585,7 +612,8 @@ Circuit Breakers If working on a Robot Quick Build, stop here and insert the board into the robot chassis before continuing. - .. group-tab:: CTR + .. tab-item:: CTR + :sync: CTR .. image:: images/how-to-wire-a-simple-robot/40A-breaker.jpg :alt: Installing 40A breakers in the PDP. diff --git a/source/docs/zero-to-robot/step-2/frc-game-tools.rst b/source/docs/zero-to-robot/step-2/frc-game-tools.rst index 2218775f49..ecd103f7d7 100644 --- a/source/docs/zero-to-robot/step-2/frc-game-tools.rst +++ b/source/docs/zero-to-robot/step-2/frc-game-tools.rst @@ -53,12 +53,12 @@ Installation Extraction ^^^^^^^^^^ -.. tabs:: - .. tab:: Online +.. tab-set:: + .. tab-item:: Online Run the downloaded executable file to start the install process. Click :guilabel:`Yes` if a Windows Security prompt appears. - .. tab:: Offline (Windows 10+) + .. tab-item:: Offline (Windows 10+) Right click on the downloaded iso file and select :guilabel:`mount`. Run ``install.exe`` from the mounted iso. Click :guilabel:`Yes` if a Windows Security prompt appears. diff --git a/source/docs/zero-to-robot/step-2/labview-setup.rst b/source/docs/zero-to-robot/step-2/labview-setup.rst index bb553cfad3..46fe4be318 100644 --- a/source/docs/zero-to-robot/step-2/labview-setup.rst +++ b/source/docs/zero-to-robot/step-2/labview-setup.rst @@ -54,12 +54,12 @@ Teams are permitted to install the software on as many team computers as needed, Starting Install ^^^^^^^^^^^^^^^^ -.. tabs:: - .. tab:: Online Installer +.. tab-set:: + .. tab-item:: Online Installer Run the downloaded exe file to start the install process. Click :guilabel:`Yes` if a Windows Security prompt - .. tab:: Offline Installer (Windows 10+) + .. tab-item:: Offline Installer (Windows 10+) Right click on the downloaded iso file and select mount. Run install.exe from the mounted iso. Click "Yes" if a Windows Security prompt diff --git a/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java.rst b/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java.rst index e482b6f67b..3be8ca3492 100644 --- a/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java.rst +++ b/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java.rst @@ -62,13 +62,15 @@ For C++ projects, there is one more step to set up IntelliSense. Whenever we op Imports/Includes ---------------- -.. tabs:: +.. tab-set:: - .. group-tab:: PWM + .. tab-item:: PWM + :sync: pwm - .. tabs:: + .. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java :language: java @@ -76,78 +78,78 @@ Imports/Includes :linenos: :lineno-start: 7 - .. group-tab:: C++ - + .. tab-item:: C++ + :sync: cpp + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp :language: c++ :lines: 5-10 :linenos: :lineno-start: 5 - .. group-tab:: CTRE + .. tab-item:: CTRE + :sync: ctre - .. tabs:: + .. tab-set-code:: - .. group-tab:: Java - .. code-block:: java + .. code-block:: java - import edu.wpi.first.wpilibj.Joystick; - import edu.wpi.first.wpilibj.TimedRobot; - import edu.wpi.first.wpilibj.Timer; - import edu.wpi.first.wpilibj.drive.DifferentialDrive; - import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; + import edu.wpi.first.wpilibj.Joystick; + import edu.wpi.first.wpilibj.TimedRobot; + import edu.wpi.first.wpilibj.Timer; + import edu.wpi.first.wpilibj.drive.DifferentialDrive; + import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX; - .. group-tab:: C++ - .. code-block:: cpp + .. code-block:: cpp - #include - #include - #include - #include - #include + #include + #include + #include + #include + #include - .. group-tab:: REV + .. tab-item:: REV - .. tabs:: + .. tab-set-code:: - .. group-tab:: Java - .. code-block:: java + .. code-block:: java - import com.revrobotics.CANSparkMax; - import com.revrobotics.CANSparkMaxLowLevel.MotorType; + import com.revrobotics.CANSparkMax; + import com.revrobotics.CANSparkMaxLowLevel.MotorType; - import edu.wpi.first.wpilibj.TimedRobot; - import edu.wpi.first.wpilibj.Timer; - import edu.wpi.first.wpilibj.XboxController; - import edu.wpi.first.wpilibj.drive.DifferentialDrive; + import edu.wpi.first.wpilibj.TimedRobot; + import edu.wpi.first.wpilibj.Timer; + import edu.wpi.first.wpilibj.XboxController; + import edu.wpi.first.wpilibj.drive.DifferentialDrive; - .. group-tab:: C++ - .. code-block:: cpp + .. code-block:: cpp - #include - #include - #include - #include - #include + #include + #include + #include + #include + #include - #include + #include Our code needs to reference the components of WPILib that are used. In C++ this is accomplished using ``#include`` statements; in Java it is done with ``import`` statements. The program references classes for ``Joystick`` (for driving), ``PWMSparkMax`` / ``WPI_TalonFX`` / ``CANSparkMax (for controlling motors), ``TimedRobot`` (the base class used for the example), ``Timer`` (used for autonomous), and ``DifferentialDrive`` (for connecting the joystick control to the motors). Defining the variables for our sample robot ------------------------------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: PWM + .. tab-item:: PWM + :sync: pwm - .. tabs:: + .. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java :language: java @@ -155,7 +157,8 @@ Defining the variables for our sample robot :linenos: :lineno-start: 19 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp :language: c++ @@ -169,11 +172,13 @@ Defining the variables for our sample robot :linenos: :lineno-start: 50 - .. group-tab:: CTRE + .. tab-item:: CTRE + :sync: ctre - .. tabs:: + .. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: java .. code-block:: java @@ -184,7 +189,8 @@ Defining the variables for our sample robot private final Joystick m_stick = new Joystick(0); private final Timer m_timer = new Timer(); - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. code-block:: cpp @@ -209,11 +215,13 @@ Defining the variables for our sample robot frc::Joystick m_stick{0}; frc::Timer m_timer; - .. group-tab:: REV + .. tab-item:: REV + :sync: rev - .. tabs:: + .. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: java .. code-block:: java @@ -224,7 +232,8 @@ Defining the variables for our sample robot private final XboxController m_controller = new XboxController(0); private final Timer m_timer = new Timer(); - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. code-block:: cpp @@ -258,14 +267,14 @@ The sample robot in our examples will have a joystick on USB port 0 for arcade d Robot Initialization -------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java @Override public void robotInit() {} - .. code-tab:: c++ + .. code-block:: c++ void RobotInit() {} @@ -275,23 +284,21 @@ The ``RobotInit`` method is run when the robot program is starting up, but after Simple Autonomous Example ------------------------- -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java - :language: java - :lines: 38-54 - :linenos: - :lineno-start: 38 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java + :language: java + :lines: 38-54 + :linenos: + :lineno-start: 38 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp - :language: c++ - :lines: 22-33 - :linenos: - :lineno-start: 22 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp + :language: c++ + :lines: 22-33 + :linenos: + :lineno-start: 22 The ``AutonomousInit`` method is run once each time the robot transitions to autonomous from another mode. In this program, we restart the ``Timer`` in this method. @@ -300,46 +307,41 @@ The ``AutonomousInit`` method is run once each time the robot transitions to aut Joystick Control for Teleoperation ---------------------------------- -.. tabs:: - - .. group-tab:: Java +.. tab-set-code:: - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java - :language: java - :lines: 56-64 - :linenos: - :lineno-start: 56 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java + :language: java + :lines: 56-64 + :linenos: + :lineno-start: 56 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp - :language: c++ - :lines: 35-41 - :linenos: - :lineno-start: 35 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp + :language: c++ + :lines: 35-41 + :linenos: + :lineno-start: 35 Like in Autonomous, the Teleop mode has a ``TeleopInit`` and ``TeleopPeriodic`` function. In this example we don't have anything to do in ``TeleopInit``, it is provided for illustration purposes only. In ``TeleopPeriodic``, the code uses the ``ArcadeDrive`` method to map the Y-axis of the ``Joystick`` to forward/back motion of the drive motors and the X-axis to turning motion. Test Mode --------- -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java - :language: java - :lines: 66-72 - :linenos: - :lineno-start: 66 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java + :language: java + :lines: 66-72 + :linenos: + :lineno-start: 66 - .. group-tab:: C++ - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp - :language: c++ - :lines: 43-45 - :linenos: - :lineno-start: 43 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp + :language: c++ + :lines: 43-45 + :linenos: + :lineno-start: 43 Test Mode is used for testing robot functionality. Similar to ``TeleopInit``, the ``TestInit`` and ``TestPeriodic`` methods are provided here for illustrative purposes only. From 5fa5c09b68daf9fa37ad1e52d72fbdbe4f77aacc Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Mon, 23 Oct 2023 21:27:43 -0400 Subject: [PATCH 2/9] fix a silly --- .../vision-processing/wpilibpi/morphological-operations.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/docs/software/vision-processing/wpilibpi/morphological-operations.rst b/source/docs/software/vision-processing/wpilibpi/morphological-operations.rst index 7e62ef1f1d..4681e51383 100644 --- a/source/docs/software/vision-processing/wpilibpi/morphological-operations.rst +++ b/source/docs/software/vision-processing/wpilibpi/morphological-operations.rst @@ -78,7 +78,7 @@ Closing Closing is dilation followed by erosion. This process removes small holes or breaks without affecting the shape of larger features. -.. tab-set-block:: +.. tab-set-code:: .. code-block:: py From f5b6290e42790467e537267d5bca904d710e9892 Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Tue, 24 Oct 2023 07:49:17 -0400 Subject: [PATCH 3/9] fix some errors --- .../robotbuilder-writing-command-code.rst | 7 +++---- .../robotbuilder-writing-subsystem-code.rst | 15 +++++++++------ 2 files changed, 12 insertions(+), 10 deletions(-) diff --git a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-command-code.rst b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-command-code.rst index 2ebef26e47..86cc3f628d 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-command-code.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-command-code.rst @@ -17,9 +17,9 @@ Generated CloseClaw Class .. code-block:: java - :linenos: - :lineno-start: 11 - :emphasize-lines: 42, 53, 59 + :linenos: + :lineno-start: 11 + :emphasize-lines: 42, 53, 59 // ROBOTBUILDER TYPE: Command. @@ -149,4 +149,3 @@ RobotBuilder will generate the class files for the `CloseClaw` command. The comm 1. Start the claw motor moving in the closing direction by calling the ``Close()`` method that was added to the `Claw` subsystem in the `CloseClaw` Initialize method. 2. This command is finished when the limit switch in the `Claw` subsystem is tripped. 3. The ``End()`` method is called when the command is finished and is a place to clean up. In this case, the motor is stopped since the time has run out. - diff --git a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-subsystem-code.rst b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-subsystem-code.rst index cc3b066749..1fe35a782e 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-subsystem-code.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-subsystem-code.rst @@ -13,9 +13,10 @@ The claw at the end of a robot arm is a subsystem operated by a single VictorSPX Adding Subsystem Capabilities ----------------------------- -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: java .. code-block:: java :linenos: @@ -102,7 +103,8 @@ Adding Subsystem Capabilities } - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. code-block:: cpp :linenos: @@ -171,9 +173,10 @@ Notice that member variable called ``motor`` and ``limitswitch`` are created by Adding the Method Declarations to the Header File (C++ Only) ------------------------------------------------------------ -.. tabs:: +.. tab-set:: - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. code-block:: cpp :linenos: @@ -227,4 +230,4 @@ Adding the Method Declarations to the Header File (C++ Only) In addition to adding the methods to the class implementation file, ``Claw.cpp``, the declarations for the methods need to be added to the header file, ``Claw.h``. Those declarations that must be added are shown here. -To add the behavior to the claw subsystem to handle opening and closing you need to :doc:`define commands <../introduction/robotbuilder-creating-command>`. +To add the behavior to the claw subsystem to handle opening and closing you need to :doc:`define commands <../introduction/robotbuilder-creating-command>`. \ No newline at end of file From 613ea9255f3de326c89b80de25ef93fd60a39563 Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Tue, 24 Oct 2023 08:47:08 -0400 Subject: [PATCH 4/9] fix warning --- source/docs/software/basic-programming/reading-stacktraces.rst | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/source/docs/software/basic-programming/reading-stacktraces.rst b/source/docs/software/basic-programming/reading-stacktraces.rst index 21f820171c..42119aa2a1 100644 --- a/source/docs/software/basic-programming/reading-stacktraces.rst +++ b/source/docs/software/basic-programming/reading-stacktraces.rst @@ -324,7 +324,7 @@ For example, consider the following code: When run, you'll see output that looks like this: -.. tab-set-code:: +.. tab-set:: .. tab-item:: Java :sync: tabcode-java From 4d9f2142fada8538e249494622b97ae384301974 Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Tue, 24 Oct 2023 21:38:30 -0400 Subject: [PATCH 5/9] 15 more files --- .../docs/software/commandbased/commands.rst | 248 +++++++++-------- .../convenience-features/event-based.rst | 126 ++++----- .../scheduling-functions.rst | 11 +- .../dashboards/glass/field2d-widget.rst | 32 +-- .../dashboards/glass/mech2d-widget.rst | 103 +++---- .../custom-widgets/creating-plugins.rst | 4 +- .../shuffleboard-displaying-data.rst | 4 +- .../hardware-apis/misc/addressable-leds.rst | 40 +-- .../networktables/nt4-migration-guide.rst | 252 +++++++++--------- .../pathweaver/integrating-robot-program.rst | 6 +- .../apriltag/apriltag-intro.rst | 18 +- .../using-the-cameraserver-on-the-roborio.rst | 41 ++- .../robot-simulation/physics-sim.rst | 24 +- .../robot-simulation/unit-testing.rst | 20 +- .../zero-to-robot/step-2/wpilib-setup.rst | 27 +- 15 files changed, 465 insertions(+), 491 deletions(-) diff --git a/source/docs/software/commandbased/commands.rst b/source/docs/software/commandbased/commands.rst index f1659ee3e1..a2a0697e37 100644 --- a/source/docs/software/commandbased/commands.rst +++ b/source/docs/software/commandbased/commands.rst @@ -40,13 +40,13 @@ Each command should declare any subsystems it controls as requirements. This bac Declaring requirements is done by overriding the ``getRequirements()`` method in the relevant command class, by calling ``addRequirements()``, or by using the ``requirements`` vararg (Java) / ``Requirements`` struct (C++) parameter at the end of the parameter list of most command constructors and factories in the library: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Commands.run(intake::activate, intake); - .. code-tab:: c++ + .. code-block:: c++ frc2::cmd::Run([&intake] { intake.Activate(); }, {&intake}); @@ -61,13 +61,13 @@ The ``runsWhenDisabled()`` method (`Java `__, `C++ `__): -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Command mayRunDuringDisabled = Commands.run(() -> updateTelemetry()).ignoringDisable(true); - .. code-tab:: c++ + .. code-block:: c++ frc2::CommandPtr mayRunDuringDisabled = frc2::cmd::Run([] { UpdateTelemetry(); }).IgnoringDisable(true); @@ -82,13 +82,13 @@ The ``getInterruptionBehavior()`` method (`Java `__, `C++ `__): -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Command noninteruptible = Commands.run(intake::activate, intake).withInterruptBehavior(Command.InterruptBehavior.kCancelIncoming); - .. code-tab:: c++ + .. code-block:: c++ frc2::CommandPtr noninterruptible = frc2::cmd::Run([&intake] { intake.Activate(); }, {&intake}).WithInterruptBehavior(Command::InterruptBehavior::kCancelIncoming); @@ -106,37 +106,40 @@ The most basic commands are actions the robot takes: setting voltage to a motor, The ``runOnce`` factory, backed by the ``InstantCommand`` (`Java `__, `C++ `__) class, creates a command that calls a lambda once, and then finishes. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java - :language: java - :lines: 25-35 - :linenos: - :lineno-start: 25 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java + :language: java + :lines: 25-35 + :linenos: + :lineno-start: 25 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: tabcode-cpp - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h - :language: c++ - :lines: 20-28 - :linenos: - :lineno-start: 20 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h + :language: c++ + :lines: 20-28 + :linenos: + :lineno-start: 20 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp-source - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp - :language: c++ - :lines: 15-25 - :linenos: - :lineno-start: 15 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp + :language: c++ + :lines: 15-25 + :linenos: + :lineno-start: 15 The ``run`` factory, backed by the ``RunCommand`` (`Java `__, `C++ `__) class, creates a command that calls a lambda repeatedly, until interrupted. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // A split-stick arcade command, with forward/backward controlled by the left // hand, and turning controlled by the right. @@ -145,7 +148,7 @@ The ``run`` factory, backed by the ``RunCommand`` (`Java `__, `C++ `__) class, calls one lambda when scheduled, and then a second lambda when interrupted. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Commands.startEnd( // Start a flywheel spinning at 50% power @@ -172,7 +175,7 @@ The ``startEnd`` factory, backed by the ``StartEndCommand`` (`Java `__, `C++ `__) accepts four lambdas that constitute the four command lifecycle methods: a ``Runnable``/``std::function`` for each of ``initialize()`` and ``execute()``, a ``BooleanConsumer``/``std::function`` for ``end()``, and a ``BooleanSupplier``/``std::function`` for ``isFinished()``. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java new FunctionalCommand( // Reset encoders on command start @@ -202,7 +205,7 @@ The ``startEnd`` factory, backed by the ``StartEndCommand`` (`Java `__, `C++ `__) class. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Ends 5 seconds after being scheduled new WaitCommand(5.0) - .. code-tab:: c++ + .. code-block:: c++ // Ends 5 seconds after being scheduled frc2::WaitCommand(5.0_s) To wait until a certain condition becomes ``true``, the library offers the ``Commands.waitUntil(BooleanSupplier)``/``frc2::cmd::WaitUntil(std::function)`` factory, backed by the ``WaitUntilCommand`` class (`Java `__, `C++ `__). -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Ends after m_limitSwitch.get() returns true new WaitUntilCommand(m_limitSwitch::get) - .. code-tab:: c++ + .. code-block:: c++ // Ends after m_limitSwitch.Get() returns true frc2::WaitUntilCommand([&m_limitSwitch] { return m_limitSwitch.Get(); }) @@ -278,54 +281,54 @@ Users may also write custom command classes. As this is significantly more verbo To write a custom command class, subclass the abstract ``Command`` class (`Java `__) or ``CommandHelper`` (`C++ `__), as seen in the command-based template (`Java `__, `C++ `__): -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java + :language: java + :lines: 7-24 + :linenos: + :lineno-start: 7 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java - :language: java - :lines: 7-24 - :linenos: - :lineno-start: 7 - .. group-tab:: C++ - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h - :language: c++ - :lines: 5-31 - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h + :language: c++ + :lines: 5-31 + :linenos: + :lineno-start: 5 Simple Command Example ---------------------- What might a functional command look like in practice? As before, below is a simple command from the HatchBot example project (`Java `__, `C++ `__) that uses the ``HatchSubsystem``: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/GrabHatch.java - :language: java - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/GrabHatch.java + :language: java + :lines: 5- + :linenos: + :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: tabcode-cpp - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.h - :language: c++ - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.h + :language: c++ + :lines: 5- + :linenos: + :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp-source - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/commands/GrabHatch.cpp - :language: c++ - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/commands/GrabHatch.cpp + :language: c++ + :lines: 5- + :linenos: + :lineno-start: 5 Notice that the hatch subsystem used by the command is passed into the command through the command’s constructor. This is a pattern called :term:`dependency injection`, and allows users to avoid declaring their subsystems as global variables. This is widely accepted as a best-practice - the reasoning behind this is discussed in a :doc:`later section `. @@ -333,68 +336,63 @@ Notice also that the above command calls the subsystem method once from initiali What about a more complicated case? Below is a drive command, from the same example project: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: tabcode-java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DefaultDrive.java - :language: java - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DefaultDrive.java + :language: java + :lines: 5- + :linenos: + :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: tabcode-cpp - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.h - :language: c++ - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.h + :language: c++ + :lines: 5- + :linenos: + :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: tabcode-cpp-source - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/commands/DefaultDrive.cpp - :language: c++ - :lines: 5- - :linenos: - :lineno-start: 5 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/aaea85ff165602a612e57a0e8170eaaa43ceec8f/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/commands/DefaultDrive.cpp + :language: c++ + :lines: 5- + :linenos: + :lineno-start: 5 And then usage: -.. tabs:: - - .. group-tab:: Java - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java - :language: java - :lines: 59-67 - :linenos: - :lineno-start: 59 +.. tab-set-code:: - .. group-tab:: C++ + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java + :language: java + :lines: 59-67 + :linenos: + :lineno-start: 59 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp - :language: c++ - :lines: 57-60 - :linenos: - :lineno-start: 57 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp + :language: c++ + :lines: 57-60 + :linenos: + :lineno-start: 57 Notice that this command does not override ``isFinished()``, and thus will never end; this is the norm for commands that are intended to be used as default commands. Once more, this command is rather simple and calls the subsystem method only from one place, and as such, could be more concisely written using factories: -.. tabs:: - - .. group-tab:: Java - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java - :language: java - :lines: 51-60 - :linenos: - :lineno-start: 51 +.. tab-set-code:: - .. group-tab:: C++ + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/RobotContainer.java + :language: java + :lines: 51-60 + :linenos: + :lineno-start: 51 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp - :language: c++ - :lines: 52-58 - :linenos: - :lineno-start: 52 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp + :language: c++ + :lines: 52-58 + :linenos: + :lineno-start: 52 diff --git a/source/docs/software/convenience-features/event-based.rst b/source/docs/software/convenience-features/event-based.rst index ee9b433dad..d983eb0997 100644 --- a/source/docs/software/convenience-features/event-based.rst +++ b/source/docs/software/convenience-features/event-based.rst @@ -10,19 +10,16 @@ EventLoop The ``EventLoop`` class is a "container" for pairs of conditions and actions, which can be polled using the ``poll()``/``Poll()`` method. When polled, every condition will be queried and if it returns ``true`` the action associated with the condition will be executed. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java - :language: java - :lines: 33-33, 87-91 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java + :language: java + :lines: 33-33, 87-91 - .. group-tab:: C++ - - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp - :language: cpp - :lines: 94-94, 81-81 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp + :language: cpp + :lines: 94-94, 81-81 .. warning:: The ``EventLoop``'s ``poll()`` method should be called consistently in a ``*Periodic()`` method. Failure to do this will result in unintended loop behavior. @@ -33,19 +30,16 @@ The ``BooleanEvent`` class represents a boolean condition: a ``BooleanSupplier`` To bind a callback action to the condition, use ``ifHigh()``/``IfHigh()``: -.. tabs:: - - .. group-tab:: Java +.. tab-set-code:: - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java - :language: java - :lines: 72-78 - .. group-tab:: C++ + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java + :language: java + :lines: 72-78 - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp - :language: cpp - :lines: 64-72 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp + :language: cpp + :lines: 64-72 Remember that button binding is *declarative*: bindings only need to be declared once, ideally some time during robot initialization. The library handles everything else. @@ -59,76 +53,62 @@ and() / && The ``and()``/``&&`` composes two ``BooleanEvent`` conditions into a third condition that returns ``true`` only when **both** of the conditions return ``true``. -.. tabs:: - - .. group-tab:: Java - - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java - :language: java - :lines: 44-49 +.. tab-set-code:: - .. group-tab:: C++ + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java + :language: java + :lines: 44-49 - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp - :language: cpp - :lines: 35-40 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp + :language: cpp + :lines: 35-40 or() / || ^^^^^^^^^ The ``or()``/``||`` composes two ``BooleanEvent`` conditions into a third condition that returns ``true`` only when **either** of the conditions return ``true``. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java - :language: java - :lines: 51-57 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java + :language: java + :lines: 51-57 - .. group-tab:: C++ - - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp - :language: cpp - :lines: 42-47 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp + :language: cpp + :lines: 42-47 negate() / ! ^^^^^^^^^^^^ The ``negate()``/``!`` composes one ``BooleanEvent`` condition into another condition that returns the opposite of what the original conditional did. -.. tabs:: - - .. group-tab:: Java +.. tab-set-code:: - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java - :language: java - :lines: 46-47 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java + :language: java + :lines: 46-47 - .. group-tab:: C++ - - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp - :language: cpp - :lines: 37-38 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp + :language: cpp + :lines: 37-38 debounce() / Debounce() ^^^^^^^^^^^^^^^^^^^^^^^ To avoid rapid repeated activation, conditions (especially those originating from digital inputs) can be debounced with the :ref:`WPILib Debouncer class ` using the `debounce` method: -.. tabs:: - - .. group-tab:: Java +.. tab-set-code:: - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java - :language: java - :lines: 71-75 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java + :language: java + :lines: 71-75 - .. group-tab:: C++ - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp - :language: cpp - :lines: 64-69 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp + :language: cpp + :lines: 64-69 rising(), falling() ^^^^^^^^^^^^^^^^^^^ @@ -137,32 +117,30 @@ Often times it is desired to bind an action not to the *current* state of a cond .. warning:: Due to the "memory" these conditions have, do not use the same instance in multiple places. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java - :language: java - :lines: 79-84 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Robot.java + :language: java + :lines: 79-84 - .. group-tab:: C++ - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp - :language: cpp - :lines: 74-78 + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp + :language: cpp + :lines: 74-78 Downcasting ``BooleanEvent`` Objects ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ To convert ``BooleanEvent`` objects to other types, most commonly the ``Trigger`` subclass used for :ref:`binding commands to conditions `, the generic ``castTo()``/``CastTo()`` decorator exists: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Trigger trigger = booleanEvent.castTo(Trigger::new); - .. code-tab:: c++ + .. code-block:: c++ frc2::Trigger trigger = booleanEvent.CastTo(); diff --git a/source/docs/software/convenience-features/scheduling-functions.rst b/source/docs/software/convenience-features/scheduling-functions.rst index ddae346d6a..301e02b89a 100644 --- a/source/docs/software/convenience-features/scheduling-functions.rst +++ b/source/docs/software/convenience-features/scheduling-functions.rst @@ -6,9 +6,10 @@ The ``addPeriodic()`` (Java) / ``AddPeriodic()`` (C++) method takes in a lambda .. note:: The units for the period and offset are seconds in Java. In C++, the :ref:`units library ` can be used to specify a period and offset in any time unit. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -36,7 +37,8 @@ The ``addPeriodic()`` (Java) / ``AddPeriodic()`` (C++) method takes in a lambda } } - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. code-block:: cpp @@ -52,7 +54,8 @@ The ``addPeriodic()`` (Java) / ``AddPeriodic()`` (C++) method takes in a lambda void TeleopPeriodic() override; }; - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. code-block:: cpp diff --git a/source/docs/software/dashboards/glass/field2d-widget.rst b/source/docs/software/dashboards/glass/field2d-widget.rst index a6678648fe..7ef83b5039 100644 --- a/source/docs/software/dashboards/glass/field2d-widget.rst +++ b/source/docs/software/dashboards/glass/field2d-widget.rst @@ -8,8 +8,8 @@ Sending Robot Pose from User Code To send your robot's position (usually obtained by :ref:`odometry ` or a pose estimator), a ``Field2d`` instance must be created in robot code and sent over NetworkTables. The instance must then be updated periodically with the latest robot pose. -.. tabs:: - .. code-tab:: java +.. tab-set-code:: + .. code-block:: java private final Field2d m_field = new Field2d(); @@ -25,7 +25,7 @@ To send your robot's position (usually obtained by :ref:`odometry #include @@ -51,23 +51,19 @@ Sending Trajectories to Field2d Visualizing your trajectory is a great debugging step for verifying that your trajectories are created as intended. Trajectories can be easily visualized in :ref:`Field2d ` using the ``setTrajectory()``/``SetTrajectory()`` functions. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Robot.java + :language: java + :lines: 44-61 + :linenos: + :lineno-start: 44 - .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Robot.java - :language: java - :lines: 44-61 - :linenos: - :lineno-start: 44 - - .. group-tab:: C++ - - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Robot.cpp - :language: cpp - :lines: 18-30 - :linenos: - :lineno-start: 18 + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteController/cpp/Robot.cpp + :language: cpp + :lines: 18-30 + :linenos: + :lineno-start: 18 Viewing Trajectories with Glass ------------------------------- diff --git a/source/docs/software/dashboards/glass/mech2d-widget.rst b/source/docs/software/dashboards/glass/mech2d-widget.rst index 74710b85cf..4b1016bbe3 100644 --- a/source/docs/software/dashboards/glass/mech2d-widget.rst +++ b/source/docs/software/dashboards/glass/mech2d-widget.rst @@ -10,86 +10,71 @@ The ``Mechanism2d`` object is the "canvas" where the mechanism is drawn. The roo In the examples below, an elevator is drawn, with a rotational wrist on top of the elevator. The full Mechanism2d example is available in `Java `__ / `C++ `__ -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java + :language: java + :lines: 43-46 + :linenos: + :lineno-start: 43 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java - :language: java - :lines: 43-46 - :linenos: - :lineno-start: 43 - - .. group-tab:: C++ - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp - :language: cpp - :lines: 59-62 - :linenos: - :lineno-start: 59 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp + :language: cpp + :lines: 59-62 + :linenos: + :lineno-start: 59 Each ``MechanismLigament2d`` object represents a stage of the mechanism. It has a three required parameters, a name, an initial length to draw (relative to the size of the ``Mechanism2d`` object), and an initial angle to draw the ligament in degrees. Ligament angles are relative to the parent ligament, and follow math notation - the same as :ref:`Rotation2d ` (counterclockwise-positive). A ligament based on the root with an angle of zero will point right. Two optional parameters let you change the width (also relative to the size of the Mechanism2d object) and the color. Call ``append()``/``Append()`` on a root node or ligament node to add another node to the figure. In Java, pass a constructed ``MechanismLigament2d`` object to add it. In C++, pass the construction parameters in order to construct and add a ligament. -.. tabs:: - - .. group-tab:: Java - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java - :language: java - :lines: 48-53 - :linenos: - :lineno-start: 48 +.. tab-set-code:: - .. group-tab:: C++ + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java + :language: java + :lines: 48-53 + :linenos: + :lineno-start: 48 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp - :language: cpp - :lines: 63-69 - :linenos: - :lineno-start: 63 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp + :language: cpp + :lines: 63-69 + :linenos: + :lineno-start: 63 Then, publish the ``Mechanism2d`` object to NetworkTables: -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java + :language: java + :lines: 55-56 + :linenos: + :lineno-start: 55 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java - :language: java - :lines: 55-56 - :linenos: - :lineno-start: 55 - .. group-tab:: C++ - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp - :language: cpp - :lines: 36-37 - :linenos: - :lineno-start: 36 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp + :language: cpp + :lines: 36-37 + :linenos: + :lineno-start: 36 .. note:: The ``Mechanism2d`` instance can also be sent using a lower-level NetworkTables API or using the :ref:`Shuffleboard API `. In this case, the ``SmartDashboard`` API was used, meaning that the :guilabel:`Mechanism2d` widget will appear under the ``SmartDashboard`` table name. To manipulate a ligament angle or length, call ``setLength()`` or ``setAngle()`` on the ``MechanismLigament2d`` object. When manipulating ligament length based off of sensor measurements, make sure to add the minimum length to prevent 0-length (and therefore invisible) ligaments. -.. tabs:: - - .. group-tab:: Java - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java - :language: java - :lines: 59-64 - :linenos: - :lineno-start: 59 +.. tab-set-code:: - .. group-tab:: C++ + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mechanism2d/Robot.java + :language: java + :lines: 59-64 + :linenos: + :lineno-start: 59 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp - :language: cpp - :lines: 40-45 - :linenos: - :lineno-start: 40 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp + :language: cpp + :lines: 40-45 + :linenos: + :lineno-start: 40 Viewing the Mechanism2d in Glass -------------------------------- diff --git a/source/docs/software/dashboards/shuffleboard/custom-widgets/creating-plugins.rst b/source/docs/software/dashboards/shuffleboard/custom-widgets/creating-plugins.rst index b8c128c82c..70ac97edb8 100644 --- a/source/docs/software/dashboards/shuffleboard/custom-widgets/creating-plugins.rst +++ b/source/docs/software/dashboards/shuffleboard/custom-widgets/creating-plugins.rst @@ -17,9 +17,9 @@ Create a Custom Plugin ---------------------- In order to define a plugin, the plugin class must be a subclass of `edu.wpi.first.shuffleboard.api.Plugin `_ or one of its subclasses. An example of a plugin class would be as following. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java import edu.wpi.first.shuffleboard.api.plugin.Description; import edu.wpi.first.shuffleboard.api.plugin.Plugin; diff --git a/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-displaying-data.rst b/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-displaying-data.rst index d1ae24aebc..b4078d481b 100644 --- a/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-displaying-data.rst +++ b/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-displaying-data.rst @@ -11,9 +11,9 @@ Often debugging or monitoring the status of a robot involves writing a number of Displaying values in normal operating mode (autonomous or teleop) ----------------------------------------------------------------- -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java protected void execute() { SmartDashboard.putBoolean("Bridge Limit", bridgeTipper.atBridge()); diff --git a/source/docs/software/hardware-apis/misc/addressable-leds.rst b/source/docs/software/hardware-apis/misc/addressable-leds.rst index b2a248cd12..0073db8cc8 100644 --- a/source/docs/software/hardware-apis/misc/addressable-leds.rst +++ b/source/docs/software/hardware-apis/misc/addressable-leds.rst @@ -14,9 +14,10 @@ After the length of the strip has been set, you'll have to create an ``Addressab .. note:: C++ does not have an AddressableLEDBuffer, and instead uses an Array. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/addressableled/Robot.java :language: java @@ -24,7 +25,8 @@ After the length of the strip has been set, you'll have to create an ``Addressab :linenos: :lineno-start: 17 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.h :language: cpp @@ -50,9 +52,10 @@ Using RGB Values RGB stands for Red, Green, and Blue. This is a fairly common color model as it's quite easy to understand. LEDs can be set with the ``setRGB`` method that takes 4 arguments: index of the LED, amount of red, amount of green, amount of blue. The amount of Red, Green, and Blue are integer values between 0-255. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: Java @@ -63,7 +66,8 @@ RGB stands for Red, Green, and Blue. This is a fairly common color model as it's m_led.setData(m_ledBuffer); - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: C++ @@ -83,9 +87,10 @@ HSV stands for Hue, Saturation, and Value. Hue describes the color or tint, satu LEDs can be set with the ``setHSV`` method that takes 4 arguments: index of the LED, hue, saturation, and value. An example is shown below for setting the color of an LED strip to red (hue of 0). -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: Java @@ -96,7 +101,8 @@ LEDs can be set with the ``setHSV`` method that takes 4 arguments: index of the m_led.setData(m_ledBuffer); - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: C++ @@ -115,9 +121,10 @@ Moving outside of the for loop, the ``m_rainbowFirstPixelHue`` then iterates the .. note:: It's good robot practice to keep the ``robotPeriodic()`` method as clean as possible, so we'll create a method for handling setting our LED data. We'll call this method ``rainbow()`` and call it from ``robotPeriodic()``. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/addressableled/Robot.java :language: java @@ -125,7 +132,8 @@ Moving outside of the for loop, the ``m_rainbowFirstPixelHue`` then iterates the :linenos: :lineno-start: 42 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp :language: cpp @@ -135,9 +143,10 @@ Moving outside of the for loop, the ``m_rainbowFirstPixelHue`` then iterates the Now that we have our ``rainbow`` method created, we have to actually call the method and set the data of the LED. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/addressableled/Robot.java :language: java @@ -145,7 +154,8 @@ Now that we have our ``rainbow`` method created, we have to actually call the me :linenos: :lineno-start: 34 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp :language: cpp diff --git a/source/docs/software/networktables/nt4-migration-guide.rst b/source/docs/software/networktables/nt4-migration-guide.rst index 8dcc1b4c0b..7c3347cda2 100644 --- a/source/docs/software/networktables/nt4-migration-guide.rst +++ b/source/docs/software/networktables/nt4-migration-guide.rst @@ -10,188 +10,180 @@ While ``NetworkTableEntry`` can still be used (for backwards compatibility), use NT3 code (was): -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. code-block:: java - .. code-block:: java + public class Example { + final NetworkTableEntry yEntry; + final NetworkTableEntry outEntry; - public class Example { - final NetworkTableEntry yEntry; - final NetworkTableEntry outEntry; + public Example() { + NetworkTableInstance inst = NetworkTableInstance.getDefault(); - public Example() { - NetworkTableInstance inst = NetworkTableInstance.getDefault(); + // get the subtable called "datatable" + NetworkTable datatable = inst.getTable("datatable"); - // get the subtable called "datatable" - NetworkTable datatable = inst.getTable("datatable"); + // get the entry in "datatable" called "Y" + yEntry = datatable.getEntry("Y"); - // get the entry in "datatable" called "Y" - yEntry = datatable.getEntry("Y"); - - // get the entry in "datatable" called "Out" - outEntry = datatable.getEntry("Out"); - } + // get the entry in "datatable" called "Out" + outEntry = datatable.getEntry("Out"); + } - public void periodic() { - // read a double value from Y, and set Out to that value multiplied by 2 - double value = yEntry.getDouble(0.0); // default to 0 - outEntry.setDouble(value * 2); - } + public void periodic() { + // read a double value from Y, and set Out to that value multiplied by 2 + double value = yEntry.getDouble(0.0); // default to 0 + outEntry.setDouble(value * 2); } + } - .. group-tab:: C++ - .. code-block:: cpp + .. code-block:: cpp - class Example { - nt::NetworkTableEntry yEntry; - nt::NetworkTableEntry outEntry; + class Example { + nt::NetworkTableEntry yEntry; + nt::NetworkTableEntry outEntry; - public: - Example() { - nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); + public: + Example() { + nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); - // get the subtable called "datatable" - auto datatable = inst.GetTable("datatable"); + // get the subtable called "datatable" + auto datatable = inst.GetTable("datatable"); - // get the entry in "datatable" called "Y" - yEntry = datatable->GetEntry("Y"); + // get the entry in "datatable" called "Y" + yEntry = datatable->GetEntry("Y"); - // get the entry in "datatable" called "Out" - outEntry = datatable->GetEntry("Out"); - } + // get the entry in "datatable" called "Out" + outEntry = datatable->GetEntry("Out"); + } - void Periodic() { - // read a double value from Y, and set Out to that value multiplied by 2 - double value = yEntry.GetDouble(0.0); // default to 0 - outEntry.SetDouble(value * 2); - } - }; + void Periodic() { + // read a double value from Y, and set Out to that value multiplied by 2 + double value = yEntry.GetDouble(0.0); // default to 0 + outEntry.SetDouble(value * 2); + } + }; - .. group-tab:: Python - .. code-block:: python + .. code-block:: python - class Example: - def __init__(self): - inst = ntcore.NetworkTableInstance.getDefault() + class Example: + def __init__(self): + inst = ntcore.NetworkTableInstance.getDefault() - # get the subtable called "datatable" - datatable = inst.getTable("datatable") + # get the subtable called "datatable" + datatable = inst.getTable("datatable") - # get the entry in "datatable" called "Y" - self.yEntry = datatable.getEntry("Y") + # get the entry in "datatable" called "Y" + self.yEntry = datatable.getEntry("Y") - # get the entry in "datatable" called "Out" - self.outEntry = datatable.getEntry("Out") + # get the entry in "datatable" called "Out" + self.outEntry = datatable.getEntry("Out") - def periodic(self): - # read a double value from Y, and set Out to that value multiplied by 2 - value = self.yEntry.getDouble(0.0) # default to 0 - self.outEntry.setDouble(value * 2) + def periodic(self): + # read a double value from Y, and set Out to that value multiplied by 2 + value = self.yEntry.getDouble(0.0) # default to 0 + self.outEntry.setDouble(value * 2) Recommended NT4 equivalent (should be): -.. tabs:: - - .. group-tab:: Java +.. tab-set-code:: - .. code-block:: java + .. code-block:: java - public class Example { - final DoubleSubscriber ySub; - final DoublePublisher outPub; + public class Example { + final DoubleSubscriber ySub; + final DoublePublisher outPub; - public Example() { - NetworkTableInstance inst = NetworkTableInstance.getDefault(); + public Example() { + NetworkTableInstance inst = NetworkTableInstance.getDefault(); - // get the subtable called "datatable" - NetworkTable datatable = inst.getTable("datatable"); + // get the subtable called "datatable" + NetworkTable datatable = inst.getTable("datatable"); - // subscribe to the topic in "datatable" called "Y" - // default value is 0 - ySub = datatable.getDoubleTopic("Y").subscribe(0.0); + // subscribe to the topic in "datatable" called "Y" + // default value is 0 + ySub = datatable.getDoubleTopic("Y").subscribe(0.0); - // publish to the topic in "datatable" called "Out" - outPub = datatable.getDoubleTopic("Out").publish(); - } + // publish to the topic in "datatable" called "Out" + outPub = datatable.getDoubleTopic("Out").publish(); + } - public void periodic() { - // read a double value from Y, and set Out to that value multiplied by 2 - double value = ySub.get(); - outPub.set(value * 2); - } + public void periodic() { + // read a double value from Y, and set Out to that value multiplied by 2 + double value = ySub.get(); + outPub.set(value * 2); + } - // often not required in robot code, unless this class doesn't exist for - // the lifetime of the entire robot program, in which case close() needs to be - // called to stop subscribing - public void close() { - ySub.close(); - outPub.close(); - } + // often not required in robot code, unless this class doesn't exist for + // the lifetime of the entire robot program, in which case close() needs to be + // called to stop subscribing + public void close() { + ySub.close(); + outPub.close(); } + } - .. group-tab:: C++ - .. code-block:: cpp + .. code-block:: cpp - class Example { - nt::DoubleSubscriber ySub; - nt::DoublePublisher outPub; + class Example { + nt::DoubleSubscriber ySub; + nt::DoublePublisher outPub; - public: - Example() { - nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); + public: + Example() { + nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); - // get the subtable called "datatable" - auto datatable = inst.GetTable("datatable"); + // get the subtable called "datatable" + auto datatable = inst.GetTable("datatable"); - // subscribe to the topic in "datatable" called "Y" - // default value is 0 - ySub = datatable->GetDoubleTopic("Y").Subscribe(0.0); + // subscribe to the topic in "datatable" called "Y" + // default value is 0 + ySub = datatable->GetDoubleTopic("Y").Subscribe(0.0); - // publish to the topic in "datatable" called "Out" - outPub = datatable->GetDoubleTopic("Out").Publish(); - } + // publish to the topic in "datatable" called "Out" + outPub = datatable->GetDoubleTopic("Out").Publish(); + } - void Periodic() { - // read a double value from Y, and set Out to that value multiplied by 2 - double value = ySub.Get(); - outPub.Set(value * 2); - } - }; + void Periodic() { + // read a double value from Y, and set Out to that value multiplied by 2 + double value = ySub.Get(); + outPub.Set(value * 2); + } + }; - .. group-tab:: Python - .. code-block:: python + .. code-block:: python - class Example: - def __init__(self) -> None: - inst = ntcore.NetworkTableInstance.getDefault() + class Example: + def __init__(self) -> None: + inst = ntcore.NetworkTableInstance.getDefault() - # get the subtable called "datatable" - datatable = inst.getTable("datatable") + # get the subtable called "datatable" + datatable = inst.getTable("datatable") - # subscribe to the topic in "datatable" called "Y" - # default value is 0 - self.ySub = datatable.getDoubleTopic("Y").subscribe(0.0) + # subscribe to the topic in "datatable" called "Y" + # default value is 0 + self.ySub = datatable.getDoubleTopic("Y").subscribe(0.0) - # publish to the topic in "datatable" called "Out" - self.outPub = datatable.getDoubleTopic("Out").publish() + # publish to the topic in "datatable" called "Out" + self.outPub = datatable.getDoubleTopic("Out").publish() - def periodic(self): - # read a double value from Y, and set Out to that value multiplied by 2 - value = self.ySub.get() - self.outPub.set(value * 2) + def periodic(self): + # read a double value from Y, and set Out to that value multiplied by 2 + value = self.ySub.get() + self.outPub.set(value * 2) - # often not required in robot code, unless this class doesn't exist for - # the lifetime of the entire robot program, in which case close() needs to be - # called to stop subscribing - def close(self): - self.ySub.close() - self.outPub.close() + # often not required in robot code, unless this class doesn't exist for + # the lifetime of the entire robot program, in which case close() needs to be + # called to stop subscribing + def close(self): + self.ySub.close() + self.outPub.close() Shuffleboard ------------ diff --git a/source/docs/software/pathplanning/pathweaver/integrating-robot-program.rst b/source/docs/software/pathplanning/pathweaver/integrating-robot-program.rst index 2f2455006f..c979489d64 100644 --- a/source/docs/software/pathplanning/pathweaver/integrating-robot-program.rst +++ b/source/docs/software/pathplanning/pathweaver/integrating-robot-program.rst @@ -9,9 +9,9 @@ The ``fromPathweaverJson`` (Java) / ``FromPathweaverJson`` (C++) static methods .. note:: PathWeaver places JSON files in ``src/main/deploy/paths`` which will automatically be placed on the roboRIO file system in ``/home/lvuser/deploy/paths`` and can be accessed using getDeployDirectory as shown below. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java String trajectoryJSON = "paths/YourPath.wpilib.json"; Trajectory trajectory = new Trajectory(); @@ -26,7 +26,7 @@ The ``fromPathweaverJson`` (Java) / ``FromPathweaverJson`` (C++) static methods } } - .. code-tab:: c++ + .. code-block:: c++ #include #include diff --git a/source/docs/software/vision-processing/apriltag/apriltag-intro.rst b/source/docs/software/vision-processing/apriltag/apriltag-intro.rst index d499b7c4a2..94e718db0f 100644 --- a/source/docs/software/vision-processing/apriltag/apriltag-intro.rst +++ b/source/docs/software/vision-processing/apriltag/apriltag-intro.rst @@ -63,30 +63,30 @@ Processing Technique While most FRC teams should not have to implement their own code to identify AprilTags in a camera image, it is useful to know the basics of how the underlying libraries function. -.. tabs:: +.. tab-set:: - .. tab:: Original Image + .. tab-item:: Original Image .. image:: images/orig_img.png :alt: Original, unprocessed image An image from a camera is simply an array of values, corresponding to the color and brightness of each pixel. - .. tab:: Remove Colors + .. tab-item:: Remove Colors .. image:: images/bw_img.png :alt: Image converted to be grey-scale The first step is to convert the image to a grey-scale (brightness-only) image. Color information is not needed to detect the black-and-white tags. - .. tab:: Decimate + .. tab-item:: Decimate .. image:: images/decimate.png :alt: Image converted to a lower resolution The next step is to convert the image to a lower resolution. Working with fewer pixels helps the algorithm work faster. The full-resolution image will be used later to refine early estimates. - .. tab:: Adaptive Threshold + .. tab-item:: Adaptive Threshold .. image:: images/adaptive_threshold.png :alt: Image with adaptive threshold algorithm applied @@ -96,14 +96,14 @@ While most FRC teams should not have to implement their own code to identify Apr The threshold is calculated by looking at the pixel's brightness, compared to a small neighborhood of pixels around it. - .. tab:: Segmentation + .. tab-item:: Segmentation .. image:: images/segmentation.png :alt: Adaptive thresholded image, but with clusters of similar pixels grouped together Next, the known pixels are clumped together. Any clumps which are too small to reasonably be a meaningful part of a tag are discarded. - .. tab:: Quad Detection + .. tab-item:: Quad Detection .. image:: images/detected_quads.png :alt: Image with quadrilateral areas identified and marked @@ -120,7 +120,7 @@ While most FRC teams should not have to implement their own code to identify Apr If all has gone well so far, we are left with a four-sided region of pixels that is likely a valid tag. - .. tab:: Decode ID + .. tab-item:: Decode ID .. image:: images/decode_id.png :alt: Image with AprilTag data decoded into a target identification number. @@ -134,7 +134,7 @@ While most FRC teams should not have to implement their own code to identify Apr It is possible there is no valid tag ID which matches the suspect tag. In this case, the decoding process stops. - .. tab:: Fit External Quad + .. tab-item:: Fit External Quad .. image:: images/fit_ext_quad.png :alt: External quadrilateral fitting process applied to each target diff --git a/source/docs/software/vision-processing/roborio/using-the-cameraserver-on-the-roborio.rst b/source/docs/software/vision-processing/roborio/using-the-cameraserver-on-the-roborio.rst index 60611cfc0f..0de2b2ad27 100644 --- a/source/docs/software/vision-processing/roborio/using-the-cameraserver-on-the-roborio.rst +++ b/source/docs/software/vision-processing/roborio/using-the-cameraserver-on-the-roborio.rst @@ -9,21 +9,19 @@ The following program starts automatic capture of a USB camera like the Microsof .. image:: images/using-the-cameraserver-on-the-roborio/simple-cameraserver-program.png :alt: By going to View then "Add..." then "CameraServer Stream Viewer" SmartDashboard adds a stream viewer widget. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java - :language: java - :lines: 7-20 - :linenos: - :lineno-start: 7 + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java + :language: java + :lines: 7-20 + :linenos: + :lineno-start: 7 - .. group-tab:: C++ - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp - :language: cpp - :lines: 7-8,16-18,20,25-31 + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp + :language: cpp + :lines: 7-8,16-18,20,25-31 Advanced Camera Server Program @@ -31,20 +29,17 @@ Advanced Camera Server Program In the following example a thread created in robotInit() gets the Camera Server instance. Each frame of the video is individually processed, in this case drawing a rectangle on the image using the OpenCV ``rectangle()`` method. The resultant images are then passed to the output stream and sent to the dashboard. You can replace the ``rectangle`` operation with any image processing code that is necessary for your application. You can even annotate the image using OpenCV methods to write targeting information onto the image being sent to the dashboard. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java + :language: java + :lines: 7-65 + :linenos: + :lineno-start: 7 - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java - :language: java - :lines: 7-65 - :linenos: - :lineno-start: 7 - .. group-tab:: C++ - - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp - :language: cpp - :lines: 5-20,23-56,58-61,63-64,69-76 + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp + :language: cpp + :lines: 5-20,23-56,58-61,63-64,69-76 Notice that in these examples, the ``PutVideo()`` method writes the video to a named stream. To view that stream on SmartDashboard or Shuffleboard, select that named stream. In this case that is "Rectangle". diff --git a/source/docs/software/wpilib-tools/robot-simulation/physics-sim.rst b/source/docs/software/wpilib-tools/robot-simulation/physics-sim.rst index 406f90ab32..ba4be23a76 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/physics-sim.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/physics-sim.rst @@ -39,9 +39,10 @@ In the following example, we simulate an elevator given the mass of the moving c .. note:: The elevator and arm simulators will prevent the simulated position from exceeding given minimum or maximum heights or angles. If you wish to simulate a mechanism with infinite rotation or motion, :code:`LinearSystemSim` may be a better option. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2024.1.1-beta-2/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/subsystems/Elevator.java :language: java @@ -49,7 +50,8 @@ In the following example, we simulate an elevator given the mass of the moving c :linenos: :lineno-start: 47 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2024.1.1-beta-2/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/subsystems/Elevator.h :language: cpp @@ -59,9 +61,10 @@ In the following example, we simulate an elevator given the mass of the moving c Next, :code:`teleopPeriodic`/:code:`TeleopPeriodic` (Java/C++) uses a simple PID control loop to drive our elevator to a setpoint 30 inches off the ground. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2024.1.1-beta-2/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/Robot.java :language: java @@ -75,7 +78,8 @@ Next, :code:`teleopPeriodic`/:code:`TeleopPeriodic` (Java/C++) uses a simple PID :linenos: :lineno-start: 99 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2024.1.1-beta-2/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp :language: cpp @@ -95,9 +99,10 @@ Next, :code:`simulationPeriodic`/:code:`SimulationPeriodic` (Java/C++) uses the Finally, the simulated encoder's distance reading is set using the simulated elevator's position, and the robot's battery voltage is set using the estimated current drawn by the elevator. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2024.1.1-beta-2/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/elevatorsimulation/subsystems/Elevator.java :language: java @@ -105,7 +110,8 @@ Finally, the simulated encoder's distance reading is set using the simulated ele :linenos: :lineno-start: 79 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: cpp .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2024.1.1-beta-2/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp :language: cpp diff --git a/source/docs/software/wpilib-tools/robot-simulation/unit-testing.rst b/source/docs/software/wpilib-tools/robot-simulation/unit-testing.rst index 8debd36c57..a24ab60833 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/unit-testing.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/unit-testing.rst @@ -14,20 +14,24 @@ To provide a "clean slate" for each test, we need to have a function to destroy .. note:: Vendors might not support resource closing identically to the way shown here. See your vendor's documentation for more information as to what they support and how. -.. tabs:: - .. group-tab:: Java +.. tab-set:: + .. tab-item:: Java + :sync: Java .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/unittest/subsystems/Intake.java :language: java :lines: 7- - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ + .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/UnitTest/include/subsystems/Intake.h :language: cpp :lines: 7- - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp :language: cpp @@ -46,14 +50,16 @@ Both JUnit and GoogleTest have multiple assertion types; the most common is equa .. note:: Comparison of floating-point values isn't accurate, so comparing them should be done with an acceptable error parameter (``DELTA``). -.. tabs:: - .. group-tab:: Java +.. tab-set:: + .. tab-item:: Java + :sync: Java .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/test/java/edu/wpi/first/wpilibj/examples/unittest/subsystems/IntakeTest.java :language: java :lines: 7- - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp :language: cpp diff --git a/source/docs/zero-to-robot/step-2/wpilib-setup.rst b/source/docs/zero-to-robot/step-2/wpilib-setup.rst index 73c1ef10c0..d527066c6d 100644 --- a/source/docs/zero-to-robot/step-2/wpilib-setup.rst +++ b/source/docs/zero-to-robot/step-2/wpilib-setup.rst @@ -34,9 +34,10 @@ Extracting the Installer When you download the WPILib installer, it is distributed as a disk image file ``.iso`` for Windows, ``.tar.gz`` for Linux, and distributed as a ``DMG`` for MacOS. -.. tabs:: +.. tab-set:: - .. group-tab:: Windows 10+ + .. tab-item:: Windows 10+ + :sync: windows-10 Windows 10+ users can right click on the downloaded disk image and select :guilabel:`Mount` to open it. Then launch ``WPILibInstaller.exe``. @@ -54,7 +55,8 @@ When you download the WPILib installer, it is distributed as a disk image file ` .. note:: After launching the installer, Windows may display a window titled "Windows protected your PC". Click :guilabel:`More info`, then select :guilabel:`Run anyway` to run the installer. - .. group-tab:: macOS + .. tab-item:: macOS + :sync: macos For this release, macOS users will need to have the Xcode Command Line Tools installed before running the installer; we are working on removing this requirement in a future release. This can be done by running ``xcode-select --install`` in the Terminal. @@ -63,7 +65,8 @@ When you download the WPILib installer, it is distributed as a disk image file ` .. image:: images/wpilib-setup/macos-launch.png :alt: Show the macOS screen after double clicking the DMG file. - .. group-tab:: Linux + .. tab-item:: Linux + :sync: linux Linux users should extract the downloaded ``.tar.gz`` and then launch ``WPILibInstaller``. Ubuntu treats executables in the file explorer as shared libraries, so double-clicking won't run them. Run the following commands in a terminal instead with ```` replaced with the version you're installing. @@ -135,14 +138,16 @@ Post-Installation Some operating systems require some final action to complete installation. -.. tabs:: +.. tab-set:: - .. group-tab:: macOS + .. tab-item:: macOS + :sync: macos After installation, the installer opens the WPILib VS Code folder. Drag the VS Code application to the dock. Eject WPILibInstaller image from the desktop. - .. group-tab:: Linux + .. tab-item:: Linux + :sync: linux Some versions of Linux (e.g. Ubuntu 20.04) require you to give the desktop shortcut the ability to launch. Right click on the desktop icon and select Allow Launching. @@ -185,18 +190,18 @@ Uninstalling WPILib is designed to install to different folders for different years, so that it is not necessary to uninstall a previous version before installing this year's WPILib. However, the following instructions can be used to uninstall WPILib if desired. -.. tabs:: +.. tab-set:: - .. tab:: Windows + .. tab-item:: Windows 1. Delete the appropriate wpilib folder (``c:\Users\Public\wpilib\YYYY`` where ``YYYY`` is the year to uninstall) 2. Delete the desktop icons at ``C:\Users\Public\Public Desktop`` - .. tab:: macOS + .. tab-item:: macOS 1. Delete the appropriate wpilib folder (``~/wpilib/YYYY`` where ``YYYY`` is the year to uninstall) - .. tab:: Linux + .. tab-item:: Linux 1. Delete the appropriate wpilib folder (``~/wpilib/YYYY`` where ``YYYY`` is the year to uninstall). eg ``rm -rf ~/wpilib/YYYY`` From 8517fdc154c4bb48ebe7647170a8d01fcf95185a Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Wed, 25 Oct 2023 17:50:56 -0400 Subject: [PATCH 6/9] i'm done!!! --- .../contributing/frc-docs/style-guide.rst | 2 +- .../commandbased/pid-subsystems-commands.rst | 71 +++++++----- .../profile-subsystems-commands.rst | 60 +++++++---- .../profilepid-subsystems-commands.rst | 60 +++++++---- .../structuring-command-based-project.rst | 67 +++++++----- .../docs/software/commandbased/subsystems.rst | 53 +++++---- ...autonomous-program-from-smartdashboard.rst | 76 ++++++++----- .../motors/wpi-drive-classes.rst | 94 ++++++++-------- .../hardware-apis/pneumatics/pressure.rst | 94 +++++++++++----- .../hardware-apis/pneumatics/solenoids.rst | 34 ++++-- .../sensors/ultrasonics-software.rst | 35 +++--- .../networktables/client-side-program.rst | 26 +++-- .../networktables/listening-for-change.rst | 27 +++-- .../networktables/multiple-instances.rst | 18 ++-- .../networktables-networking.rst | 36 ++++--- .../networktables/publish-and-subscribe.rst | 84 ++++++++++----- .../networktables/tables-and-topics.rst | 18 ++-- .../creating-drive-subsystem.rst | 83 ++++++++------ .../creating-following-trajectory.rst | 58 ++++++---- .../entering-constants.rst | 102 ++++++++---------- 20 files changed, 673 insertions(+), 425 deletions(-) diff --git a/source/docs/contributing/frc-docs/style-guide.rst b/source/docs/contributing/frc-docs/style-guide.rst index ca71eb0252..5a3fa0d539 100644 --- a/source/docs/contributing/frc-docs/style-guide.rst +++ b/source/docs/contributing/frc-docs/style-guide.rst @@ -105,7 +105,7 @@ RLI (Remote Literal Include) When possible, instead of using code blocks, an RLI should be used. This pulls code lines directly from GitHub, most commonly using the example programs. This automatically keeps the code up to date with any changes that are made. The format of an RLI is: -.. tab-set-code:: +.. code-block:: ReST .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Robot.java diff --git a/source/docs/software/commandbased/pid-subsystems-commands.rst b/source/docs/software/commandbased/pid-subsystems-commands.rst index da19e2d6b5..8393e026b3 100644 --- a/source/docs/software/commandbased/pid-subsystems-commands.rst +++ b/source/docs/software/commandbased/pid-subsystems-commands.rst @@ -22,15 +22,17 @@ When subclassing ``PIDSubsystem``, users must override two abstract methods to p getMeasurement() ~~~~~~~~~~~~~~~~ -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java :language: java :lines: 84-84 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h :language: cpp @@ -43,15 +45,17 @@ Users should override this method to return whatever sensor reading they wish to useOutput() ~~~~~~~~~~~ -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java :language: java :lines: 77-77 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h :language: cpp @@ -79,14 +83,14 @@ setSetpoint() The ``setSetpoint()`` method can be used to set the setpoint of the ``PIDSubsystem``. The subsystem will automatically track to the setpoint using the defined output: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // The subsystem will track to a setpoint of 5. examplePIDSubsystem.setSetpoint(5); - .. code-tab:: c++ + .. code-block:: c++ // The subsystem will track to a setpoint of 5. examplePIDSubsystem.SetSetpoint(5); @@ -103,9 +107,10 @@ Full PIDSubsystem Example What does a ``PIDSubsystem`` look like when used in practice? The following examples are taken from the FrisbeeBot example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/ShooterSubsystem.java :language: java @@ -113,7 +118,8 @@ What does a ``PIDSubsystem`` look like when used in practice? The following exam :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/ShooterSubsystem.h :language: c++ @@ -121,7 +127,8 @@ What does a ``PIDSubsystem`` look like when used in practice? The following exam :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/subsystems/ShooterSubsystem.cpp :language: c++ @@ -131,15 +138,17 @@ What does a ``PIDSubsystem`` look like when used in practice? The following exam Using a ``PIDSubsystem`` with commands can be very simple: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/RobotContainer.java :language: java :lines: 26-27, 80-87 - .. group-tab:: C++ (Header) + .. tab-item:: C++ + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/RobotContainer.h :language: c++ @@ -147,7 +156,8 @@ Using a ``PIDSubsystem`` with commands can be very simple: :linenos: :lineno-start: 45 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Frisbeebot/cpp/RobotContainer.cpp :language: c++ @@ -169,9 +179,10 @@ A ``PIDCommand`` can be created two ways - by subclassing the ``PIDCommand`` cla In either case, a ``PIDCommand`` is created by passing the necessary parameters to its constructor (if defining a subclass, this can be done with a `super()` call): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java :language: java @@ -179,7 +190,8 @@ In either case, a ``PIDCommand`` is created by passing the necessary parameters :linenos: :lineno-start: 27 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h :language: c++ @@ -225,9 +237,10 @@ Full PIDCommand Example What does a ``PIDCommand`` look like when used in practice? The following examples are from the GyroDriveCommands example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/commands/TurnToAngle.java :language: java @@ -235,7 +248,8 @@ What does a ``PIDCommand`` look like when used in practice? The following exampl :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/commands/TurnToAngle.h :language: c++ @@ -243,7 +257,8 @@ What does a ``PIDCommand`` look like when used in practice? The following exampl :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngle.cpp :language: c++ @@ -253,9 +268,10 @@ What does a ``PIDCommand`` look like when used in practice? The following exampl And, for an :ref:`inlined ` example: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/RobotContainer.java :language: java @@ -263,7 +279,8 @@ And, for an :ref:`inlined `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/ArmSubsystem.java :language: java @@ -98,7 +101,8 @@ What does a ``TrapezoidProfileSubsystem`` look like when used in practice? The :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/ArmSubsystem.h :language: c++ @@ -106,7 +110,8 @@ What does a ``TrapezoidProfileSubsystem`` look like when used in practice? The :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/subsystems/ArmSubsystem.cpp :language: c++ @@ -116,9 +121,10 @@ What does a ``TrapezoidProfileSubsystem`` look like when used in practice? The Using a ``TrapezoidProfileSubsystem`` with commands can be quite simple: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/RobotContainer.java :language: java @@ -126,7 +132,8 @@ Using a ``TrapezoidProfileSubsystem`` with commands can be quite simple: :linenos: :lineno-start: 52 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/cpp/RobotContainer.cpp :language: c++ @@ -150,9 +157,10 @@ A ``TrapezoidProfileCommand`` can be created two ways - by subclassing the ``Tra In either case, a ``TrapezoidProfileCommand`` is created by passing the necessary parameters to its constructor (if defining a subclass, this can be done with a `super()` call): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/main/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java :language: java @@ -160,7 +168,8 @@ In either case, a ``TrapezoidProfileCommand`` is created by passing the necessar :linenos: :lineno-start: 28 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/main/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h :language: c++ @@ -198,9 +207,10 @@ Full TrapezoidProfileCommand Example What does a ``TrapezoidProfileSubsystem`` look like when used in practice? The following examples are taking from the DriveDistanceOffboard example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/commands/DriveDistanceProfiled.java :language: java @@ -208,7 +218,8 @@ What does a ``TrapezoidProfileSubsystem`` look like when used in practice? The :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/main/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/commands/DriveDistanceProfiled.h :language: c++ @@ -216,7 +227,8 @@ What does a ``TrapezoidProfileSubsystem`` look like when used in practice? The :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/main/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/commands/DriveDistanceProfiled.cpp :language: c++ @@ -226,9 +238,10 @@ What does a ``TrapezoidProfileSubsystem`` look like when used in practice? The And, for an :ref:`inlined ` example: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/RobotContainer.java :language: java @@ -236,7 +249,8 @@ And, for an :ref:`inlined `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/ArmSubsystem.java :language: java @@ -117,7 +122,8 @@ What does a PIDSubsystem look like when used in practice? The following examples :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/ArmSubsystem.h :language: c++ @@ -125,7 +131,8 @@ What does a PIDSubsystem look like when used in practice? The following examples :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/subsystems/ArmSubsystem.cpp :language: c++ @@ -135,9 +142,10 @@ What does a PIDSubsystem look like when used in practice? The following examples Using a ``ProfiledPIDSubsystem`` with commands can be very simple: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/RobotContainer.java :language: java @@ -145,7 +153,8 @@ Using a ``ProfiledPIDSubsystem`` with commands can be very simple: :linenos: :lineno-start: 55 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/ArmBot/cpp/RobotContainer.cpp :language: c++ @@ -169,9 +178,10 @@ A ``ProfiledPIDCommand`` can be created two ways - by subclassing the ``Profiled In either case, a ``ProfiledPIDCommand`` is created by passing the necessary parameters to its constructor (if defining a subclass, this can be done with a `super()` call): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java :language: java @@ -179,7 +189,8 @@ In either case, a ``ProfiledPIDCommand`` is created by passing the necessary par :linenos: :lineno-start: 29 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h :language: c++ @@ -225,9 +236,10 @@ Full ProfiledPIDCommand Example What does a ``ProfiledPIDCommand`` look like when used in practice? The following examples are from the GyroDriveCommands example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/commands/TurnToAngleProfiled.java :language: java @@ -235,7 +247,8 @@ What does a ``ProfiledPIDCommand`` look like when used in practice? The followin :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/commands/TurnToAngleProfiled.h :language: c++ @@ -243,7 +256,8 @@ What does a ``ProfiledPIDCommand`` look like when used in practice? The followin :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/cpp/commands/TurnToAngleProfiled.cpp :language: c++ diff --git a/source/docs/software/commandbased/structuring-command-based-project.rst b/source/docs/software/commandbased/structuring-command-based-project.rst index 3f874dc911..79ab7854d6 100644 --- a/source/docs/software/commandbased/structuring-command-based-project.rst +++ b/source/docs/software/commandbased/structuring-command-based-project.rst @@ -16,9 +16,10 @@ Robot As ``Robot`` (`Java `__, `C++ (Header) `__, `C++ (Source) `__) is responsible for the program’s control flow, and command-based is an declarative paradigm designed to minimize the amount of attention the user has to pay to explicit program control flow, the ``Robot`` class of a command-based project should be mostly empty. However, there are a few important things that must be included -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java :language: java @@ -30,9 +31,10 @@ In Java, an instance of ``RobotContainer`` should be constructed during the ``ro In C++, this is not needed as RobotContainer is a value member and will be constructed during the construction of ``Robot``. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java :language: java @@ -40,7 +42,8 @@ In C++, this is not needed as RobotContainer is a value member and will be const :linenos: :lineno-start: 33 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp :language: c++ @@ -50,9 +53,10 @@ In C++, this is not needed as RobotContainer is a value member and will be const The inclusion of the ``CommandScheduler.getInstance().run()`` call in the ``robotPeriodic()`` method is essential; without this call, the scheduler will not execute any scheduled commands. Since ``TimedRobot`` runs with a default main loop frequency of 50Hz, this is the frequency with which periodic command and subsystem methods will be called. It is not recommended for new users to call this method from anywhere else in their code. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java :language: java @@ -60,7 +64,8 @@ The inclusion of the ``CommandScheduler.getInstance().run()`` call in the ``robo :linenos: :lineno-start: 56 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp :language: c++ @@ -70,9 +75,10 @@ The inclusion of the ``CommandScheduler.getInstance().run()`` call in the ``robo The ``autonomousInit()`` method schedules an autonomous command returned by the ``RobotContainer`` instance. The logic for selecting which autonomous command to run can be handled inside of ``RobotContainer``. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java :language: java @@ -80,7 +86,8 @@ The ``autonomousInit()`` method schedules an autonomous command returned by the :linenos: :lineno-start: 71 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp :language: c++ @@ -97,9 +104,10 @@ RobotContainer This class (`Java `__, `C++ (Header) `__, `C++ (Source) `__) is where most of the setup for your command-based robot will take place. In this class, you will define your robot’s subsystems and commands, bind those commands to triggering events (such as buttons), and specify which command you will run in your autonomous routine. There are a few aspects of this class new users may want explanations for: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/RobotContainer.java :language: java @@ -107,7 +115,8 @@ This class (`Java `__, `C++ `__), as seen in the command-based template (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java :language: java @@ -22,7 +23,8 @@ The recommended method to create a subsystem for most users is to subclass the a :linenos: :lineno-start: 7 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h :language: c++ @@ -39,9 +41,10 @@ Simple Subsystem Example What might a functional subsystem look like in practice? Below is a simple pneumatically-actuated hatch mechanism from the HatchBotTraditional example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/HatchSubsystem.java :language: java @@ -49,7 +52,8 @@ What might a functional subsystem look like in practice? Below is a simple pneum :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.h :language: c++ @@ -57,7 +61,8 @@ What might a functional subsystem look like in practice? Below is a simple pneum :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp :language: c++ @@ -69,9 +74,10 @@ Notice that the subsystem hides the presence of the DoubleSolenoid from outside Alternatively, instead of writing ``void`` public methods that are called from commands, we can define the public methods as factories that return a command. Consider the following from the HatchBotInlined example project (`Java `__, `C++ `__): -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java :language: java @@ -79,7 +85,8 @@ Alternatively, instead of writing ``void`` public methods that are called from c :linenos: :lineno-start: 5 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h :language: c++ @@ -87,7 +94,8 @@ Alternatively, instead of writing ``void`` public methods that are called from c :linenos: :lineno-start: 5 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp :language: c++ @@ -104,9 +112,10 @@ Periodic Subsystems have a ``periodic`` method that is called once every scheduler iteration (usually, once every 20 ms). This method is typically used for telemetry and other periodic actions that do not interfere with whatever command is requiring the subsystem. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java :language: java @@ -114,7 +123,8 @@ Subsystems have a ``periodic`` method that is called once every scheduler iterat :linenos: :lineno-start: 117 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h :language: c++ @@ -122,7 +132,8 @@ Subsystems have a ``periodic`` method that is called once every scheduler iterat :linenos: :lineno-start: 30 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/3eb372c25ad6079d6edfbdb4bb099a7bc00e4350/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/cpp/subsystems/DriveSubsystem.cpp :language: c++ @@ -141,23 +152,23 @@ Default Commands Setting a default command for a subsystem is very easy; one simply calls ``CommandScheduler.getInstance().setDefaultCommand()``, or, more simply, the ``setDefaultCommand()`` method of the ``Subsystem`` interface: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java CommandScheduler.getInstance().setDefaultCommand(exampleSubsystem, exampleCommand); - .. code-tab:: c++ + .. code-block:: c++ CommandScheduler.GetInstance().SetDefaultCommand(exampleSubsystem, std::move(exampleCommand)); -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java exampleSubsystem.setDefaultCommand(exampleCommand); - .. code-tab:: c++ + .. code-block:: c++ exampleSubsystem.SetDefaultCommand(std::move(exampleCommand)); diff --git a/source/docs/software/dashboards/smartdashboard/choosing-an-autonomous-program-from-smartdashboard.rst b/source/docs/software/dashboards/smartdashboard/choosing-an-autonomous-program-from-smartdashboard.rst index 32cd9354a0..cfea75ce9e 100644 --- a/source/docs/software/dashboards/smartdashboard/choosing-an-autonomous-program-from-smartdashboard.rst +++ b/source/docs/software/dashboards/smartdashboard/choosing-an-autonomous-program-from-smartdashboard.rst @@ -15,15 +15,17 @@ Creating SendableChooser Object In ``Robot.java`` / ``Robot.h``, create a variable to hold a reference to a ``SendableChooser`` object. Two or more auto modes can be added by creating strings to send to the chooser. Using the ``SendableChooser``, one can choose between them. In this example, ``Default`` and ``My Auto`` are shown as options. You will also need a variable to store which auto has been chosen, ``m_autoSelected``. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java :language: java :lines: 18-21 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h :language: c++ @@ -34,15 +36,17 @@ Setting Up Options The chooser allows you to pick from a list of defined elements, in this case the strings we defined above. In ``robotInit``, add your options created as strings above using ``setDefaultOption`` or ``addOption``. ``setDefaultOption`` will be the one selected by default when the dashboard starts. The ``putData`` function will push it to the dashboard on your driver station computer. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java :language: java :lines: 28-32 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp :language: c++ @@ -53,15 +57,17 @@ Running Autonomous Code Now, in ``autonomousInit`` and ``autonomousPeriodic``, you can use the ``m_autoSelected`` variable to read which option was chosen, and change what happens during the autonomous period. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java :language: java :lines: 54-56, 58-73 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp :language: c++ @@ -78,21 +84,24 @@ Creating the SendableChooser Object In ``RobotContainer``, create a variable to hold a reference to a ``SendableChooser`` object. Two or more commands can be created and stored in new variables. Using the ``SendableChooser``, one can choose between them. In this example, ``SimpleAuto`` and ``ComplexAuto`` are shown as options. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java :language: java :lines: 40-49 - .. group-tab:: C++ (using raw pointers) + .. tab-item:: C++ (using raw pointers) + :sync: C++ (using raw pointers) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.h :language: c++ :lines: 38-44 - .. group-tab:: C++ (using ``CommandPtr``) + .. tab-item:: C++ (using ``CommandPtr``) + :sync: C++ (using ``CommandPtr``) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.h :language: c++ @@ -105,21 +114,24 @@ Imagine that you have two autonomous programs to choose between and they are enc In ``RobotContainer``, create a ``SendableChooser`` object and add instances of the two commands to it. There can be any number of commands, and the one added as a default (``setDefaultOption``), becomes the one that is initially selected. Notice that each command is included in an ``setDefaultOption()`` or ``addOption()`` method call on the ``SendableChooser`` instance. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java :language: java :lines: 69-71 - .. group-tab:: C++ (using raw pointers) + .. tab-item:: C++ (using raw pointers) + :sync: C++ (using raw pointers) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp :language: c++ :lines: 18-20 - .. group-tab:: C++ (using ``CommandPtr``) + .. tab-item:: C++ (using ``CommandPtr``) + :sync: C++ (using ``CommandPtr``) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp :language: c++ @@ -127,14 +139,14 @@ In ``RobotContainer``, create a ``SendableChooser`` object and add instances of Then, publish the chooser to the dashboard: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java // Put the chooser on the dashboard SmartDashboard.putData(m_chooser); - .. code-tab:: c++ + .. code-block:: c++ // Put the chooser on the dashboard frc::SmartDashboard::PutData(&m_chooser); @@ -144,9 +156,10 @@ Starting an Autonomous Command In ``Robot.java``, when the autonomous period starts, the ``SendableChooser`` object is polled to get the selected command and that command must be scheduled. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/RobotContainer.java :language: java @@ -156,7 +169,8 @@ In ``Robot.java``, when the autonomous period starts, the ``SendableChooser`` ob :language: java :lines: 67-68,76-81 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp :language: c++ @@ -173,9 +187,10 @@ In ``Robot.java``, this will run the scheduler every driver station update perio .. note:: Running the scheduler can occur in the ``autonomousPeriodic()`` function or ``robotPeriodic()``, both will function similarly in autonomous mode. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java :language: java @@ -183,7 +198,8 @@ In ``Robot.java``, this will run the scheduler every driver station update perio :linenos: :lineno-start: 40 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp :language: c++ @@ -196,9 +212,10 @@ Canceling the Autonomous Command In ``Robot.java``, when the teleop period begins, the autonomous command will be canceled. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/Robot.java :language: java @@ -206,7 +223,8 @@ In ``Robot.java``, when the teleop period begins, the autonomous command will be :linenos: :lineno-start: 78 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp :language: c++ diff --git a/source/docs/software/hardware-apis/motors/wpi-drive-classes.rst b/source/docs/software/hardware-apis/motors/wpi-drive-classes.rst index 7172315274..5ac574760f 100644 --- a/source/docs/software/hardware-apis/motors/wpi-drive-classes.rst +++ b/source/docs/software/hardware-apis/motors/wpi-drive-classes.rst @@ -34,9 +34,9 @@ Motor Inversion As of 2022, the right side of the drivetrain is **no longer** inverted by default. It is the responsibility of the user to manage proper inversions for their drivetrain. Users can invert motors by calling ``setInverted()``/``SetInverted()`` on their motor objects. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java PWMSparkMax m_motorRight = new PWMSparkMax(0); @@ -45,7 +45,7 @@ As of 2022, the right side of the drivetrain is **no longer** inverted by defaul m_motorRight.setInverted(true); } - .. code-tab:: cpp + .. code-block:: cpp frc::PWMSparkMax m_motorLeft{0}; @@ -54,7 +54,7 @@ As of 2022, the right side of the drivetrain is **no longer** inverted by defaul m_motorRight.SetInverted(true); } - .. code-tab:: python + .. code-block:: python def robotInit(self): self.motorRight = wpilib.PWMSparkMax(0) @@ -86,23 +86,23 @@ The Motor Safety feature operates by maintaining a timer that tracks how long it The Motor Safety interface of motor controllers can be interacted with by the user using the following methods: -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java exampleJaguar.setSafetyEnabled(true); exampleJaguar.setSafetyEnabled(false); exampleJaguar.setExpiration(.1); exampleJaguar.feed() - .. code-tab:: c++ + .. code-block:: c++ exampleJaguar->SetSafetyEnabled(true); exampleJaguar->SetSafetyEnabled(false); exampleJaguar->SetExpiration(.1); exampleJaguar->Feed(); - .. code-tab:: python + .. code-block:: python exampleJaguar.setSafetyEnabled(True) exampleJaguar.setSafetyEnabled(False) @@ -125,9 +125,10 @@ Using the DifferentialDrive class to control Differential Drive robots DifferentialDrive is a method provided for the control of "skid-steer" or "West Coast" drivetrains, such as the Kit of Parts chassis. Instantiating a DifferentialDrive is as simple as so: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -140,7 +141,8 @@ DifferentialDrive is a method provided for the control of "skid-steer" or "West m_left.setInverted(true); // if you want to invert motor outputs, you must do so here } - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. code-block:: cpp @@ -150,7 +152,8 @@ DifferentialDrive is a method provided for the control of "skid-steer" or "West frc::Spark m_right{2}; frc::DifferentialDrive m_drive{m_left, m_right}; - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. code-block:: cpp @@ -158,7 +161,9 @@ DifferentialDrive is a method provided for the control of "skid-steer" or "West m_left.SetInverted(true); // if you want to invert motor outputs, you must do so here } - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python @@ -174,9 +179,10 @@ Multi-Motor DifferentialDrive with MotorControllerGroups Many FRC\ |reg| drivetrains have more than 1 motor on each side. In order to use these with DifferentialDrive, the motors on each side have to be collected into a single MotorController, using the MotorControllerGroup class. The examples below show a 4 motor (2 per side) drivetrain. To extend to more motors, simply create the additional controllers and pass them all into the MotorController group constructor (it takes an arbitrary number of inputs). -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -194,7 +200,8 @@ Many FRC\ |reg| drivetrains have more than 1 motor on each side. In order to use m_left.setInverted(true); // if you want to invert the entire side you can do so here } - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. code-block:: c++ @@ -210,7 +217,8 @@ Many FRC\ |reg| drivetrains have more than 1 motor on each side. In order to use frc::DifferentialDrive m_drive{m_left, m_right}; - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. code-block:: c++ @@ -218,7 +226,9 @@ Many FRC\ |reg| drivetrains have more than 1 motor on each side. In order to use m_left.SetInverted(true); // if you want to invert the entire side you can do so here } - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python @@ -253,9 +263,9 @@ The Arcade Drive mode is used to control the drivetrain using speed/throttle and Like Arcade Drive, the Curvature Drive mode is used to control the drivetrain using speed/throttle and rotation rate. The difference is that the rotation control input controls the radius of curvature instead of rate of heading change, much like the steering wheel of a car. This mode also supports turning in place, which is enabled when the third :code:`boolean` parameter is true. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public void teleopPeriodic() { // Tank drive with a given left and right rates @@ -268,7 +278,7 @@ Like Arcade Drive, the Curvature Drive mode is used to control the drivetrain us myDrive.curvatureDrive(-driveStick.getY(), -driveStick.getX(), driveStick.getButton(1)); } - .. code-tab:: c++ + .. code-block:: c++ void TeleopPeriodic() override { // Tank drive with a given left and right rates @@ -281,7 +291,7 @@ Like Arcade Drive, the Curvature Drive mode is used to control the drivetrain us myDrive.CurvatureDrive(-driveStick.GetY(), -driveStick.GetX(), driveStick.GetButton(1)); } - .. code-tab:: python + .. code-block:: python def teleopPeriodic(self): # Tank drive with a given left and right rates @@ -298,31 +308,25 @@ Using the MecanumDrive class to control Mecanum Drive robots MecanumDrive is a method provided for the control of holonomic drivetrains with Mecanum wheels, such as the Kit of Parts chassis with the mecanum drive upgrade kit, as shown above. Instantiating a MecanumDrive is as simple as so: -.. tabs:: - - .. tab:: Java +.. tab-set-code:: .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java - :language: java - :lines: 24-39 - :linenos: - :lineno-start: 24 - - .. tab:: C++ + :language: java + :lines: 24-39 + :linenos: + :lineno-start: 24 .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp - :language: cpp - :lines: 31-44 - :linenos: - :lineno-start: 31 - - .. tab:: Python + :language: cpp + :lines: 31-44 + :linenos: + :lineno-start: 31 .. remoteliteralinclude:: https://raw.githubusercontent.com/robotpy/examples/2023.1.1.0/mecanum-drive/robot.py - :language: python - :lines: 21-36 - :linenos: - :lineno-start: 21 + :language: python + :lines: 21-36 + :linenos: + :lineno-start: 21 Mecanum Drive Modes ^^^^^^^^^^^^^^^^^^^ @@ -335,9 +339,9 @@ The MecanumDrive class contains two different default modes of driving your robo - drivePolar: Angles are measured counter-clockwise from straight ahead. The speed at which the robot drives (translation) is independent from its angle or rotation rate. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java public void teleopPeriodic() { // Drive using the X, Y, and Z axes of the joystick. @@ -346,7 +350,7 @@ The MecanumDrive class contains two different default modes of driving your robo m_robotDrive.drivePolar(-m_stick.getY(), Rotation2d.fromDegrees(45), 0); } - .. code-tab:: c++ + .. code-block:: c++ void TeleopPeriodic() override { // Drive using the X, Y, and Z axes of the joystick. @@ -355,7 +359,7 @@ The MecanumDrive class contains two different default modes of driving your robo m_robotDrive.drivePolar(-m_stick.GetY(), 45_deg, 0); } - .. code-tab:: python + .. code-block:: python def teleopPeriodic(self): // Drive using the X, Y, and Z axes of the joystick. diff --git a/source/docs/software/hardware-apis/pneumatics/pressure.rst b/source/docs/software/hardware-apis/pneumatics/pressure.rst index 36c80cf274..db98e0d154 100644 --- a/source/docs/software/hardware-apis/pneumatics/pressure.rst +++ b/source/docs/software/hardware-apis/pneumatics/pressure.rst @@ -7,39 +7,55 @@ Pressure is created using a pneumatic compressor and stored in pneumatic tanks. Construct a ``Compressor`` object: -.. tabs:: - .. group-tab:: REV Pneumatic Hub (PH) - .. tabs:: - .. group-tab:: Java +.. tab-set:: + .. tab-item:: REV Pneumatic Hub (PH) + + .. tab-set:: + .. tab-item:: Java + :sync: Java + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java :language: java :lines: 39-40 - .. group-tab:: C++ (Header) + + .. tab-item:: C++ (Header) + :sync: C++ (Header) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.h :language: c++ :lines: 54-55 - .. group-tab:: CTRE Pneumatics Control Module (PCM) - .. tabs:: - .. group-tab:: Java + .. tab-item:: CTRE Pneumatics Control Module (PCM) + + .. tab-set:: + .. tab-item:: Java + :sync: Java + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java :language: java :lines: 26-27 - .. group-tab:: C++ (Header) - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.h - :language: c++ - :lines: 41-42 + + .. tab-item:: C++ (Header) + :sync: C++ (Header) + + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.h + :language: c++ + :lines: 41-42 Querying compressor current and state: -.. tabs:: +.. tab-set:: + + .. tab-item:: Java + :sync: Java - .. group-tab:: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java :language: java :lines: 67-68, 73-74, 79-81 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp :language: c++ :lines: 26-28, 31-32, 35-37 @@ -47,28 +63,36 @@ Querying compressor current and state: Enable/disable digital closed-loop compressor control (enabled by default): -.. tabs:: +.. tab-set:: + + .. tab-item:: Java + :sync: Java - .. group-tab:: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java :language: java :lines: 54-55, 58-61 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Pneumatics.cpp :language: c++ :lines: 12-13, 16-19 The Pneumatic Hub also has methods for enabling compressor control using the REV Analog Pressure Sensor: -.. tabs:: +.. tab-set:: + + .. tab-item:: Java + :sync: Java - .. group-tab:: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java :language: java :lines: 120-124, 127-133 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp :language: c++ :lines: 76-81, 84-90 @@ -84,8 +108,10 @@ Pneumatic Hub The Pneumatic Hub has analog inputs that may be used to read a pressure transducer using the Compressor class. -.. tabs:: - .. group-tab:: Java +.. tab-set:: + .. tab-item:: Java + :sync: Java + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java :language: java :lines: 39-40 @@ -93,12 +119,16 @@ The Pneumatic Hub has analog inputs that may be used to read a pressure transduc :language: java :lines: 59-62 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.h :language: c++ :lines: 54-55 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp :language: c++ :lines: 19-23 @@ -108,9 +138,11 @@ roboRIO A pressure transducer can be connected to the Analog Input ports on the roboRIO, and can be read by the ``AnalogInput`` or ``AnalogPotentiometer`` classes in WPILib. -.. tabs:: +.. tab-set:: + + .. tab-item:: Java + :sync: Java - .. group-tab:: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java :language: java :lines: 16-24 @@ -118,12 +150,16 @@ A pressure transducer can be connected to the Analog Input ports on the roboRIO, :language: java :lines: 40-41 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.h :language: c++ :lines: 30-40 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/c2685629ed0a07016d7ebded3bc8e6f84bd9cdca/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Pneumatics.cpp :language: c++ :lines: 24-26 diff --git a/source/docs/software/hardware-apis/pneumatics/solenoids.rst b/source/docs/software/hardware-apis/pneumatics/solenoids.rst index 0a13751249..b84b2ed554 100644 --- a/source/docs/software/hardware-apis/pneumatics/solenoids.rst +++ b/source/docs/software/hardware-apis/pneumatics/solenoids.rst @@ -12,9 +12,11 @@ Single Solenoids in WPILib Single solenoids in WPILib are controlled using the ``Solenoid`` class (`Java `__ / `C++ `__). To construct a Solenoid object, simply pass the desired port number (assumes default CAN ID) and pneumatics module type or CAN ID, pneumatics module type, and port number to the constructor. To set the value of the solenoid call ``set(true)`` to enable or ``set(false)`` to disable the solenoid output. -.. tabs:: +.. tab-set:: + + .. tab-item:: Java + :sync: Java - .. group-tab:: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java :language: java :lines: 30-32 @@ -26,14 +28,18 @@ Single solenoids in WPILib are controlled using the ``Solenoid`` class (`Java `__ / `C++ `__). These are constructed similarly to the single solenoid but there are now two port numbers to pass to the constructor, a forward channel (first) and a reverse channel (second). The state of the valve can then be set to ``kOff`` (neither output activated), ``kForward`` (forward channel enabled) or ``kReverse`` (reverse channel enabled). Additionally, the CAN ID can be passed to the DoubleSolenoid if teams have a non-default CAN ID. -.. tabs:: +.. tab-set:: + + .. tab-item:: Java + :sync: Java - .. group-tab:: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/solenoid/Robot.java :language: java :lines: 34-37 @@ -60,14 +68,18 @@ Double solenoids are controlled by the ``DoubleSolenoid`` class in WPILib (`Java :linenos: :lineno-start: 100 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.h :language: c++ :lines: 49-52 :linenos: :lineno-start: 49 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp :language: c++ :lines: 54, 56 @@ -82,9 +94,9 @@ Solenoids can be switched from one output to the other (known as toggling) by us .. note:: Since a DoubleSolenoid defaults to off, you will have to set it before it can be toggled. -.. tabs:: +.. tab-set-code:: - .. code-tab:: java + .. code-block:: java Solenoid exampleSingle = new Solenoid(PneumaticsModuleType.CTREPCM, 0); DoubleSolenoid exampleDouble = new DoubleSolenoid(PneumaticsModuleType.CTREPCM, 1, 2); @@ -97,7 +109,7 @@ Solenoids can be switched from one output to the other (known as toggling) by us exampleDouble.toggle(); } - .. code-tab:: c++ + .. code-block:: c++ frc::Solenoid exampleSingle{frc::PneumaticsModuleType::CTREPCM, 0}; frc::DoubleSolenoid exampleDouble{frc::PneumaticsModuleType::CTREPCM, 1, 2}; diff --git a/source/docs/software/hardware-apis/sensors/ultrasonics-software.rst b/source/docs/software/hardware-apis/sensors/ultrasonics-software.rst index 7047c7355b..eefb2502de 100644 --- a/source/docs/software/hardware-apis/sensors/ultrasonics-software.rst +++ b/source/docs/software/hardware-apis/sensors/ultrasonics-software.rst @@ -15,15 +15,17 @@ Ping-response ultrasonics The :code:`Ultrasonic` class (`Java `__, `C++ `__) provides support for ping-response ultrasonics. As ping-response ultrasonics (per the name) require separate pins for both sending the ping and measuring the response, users must specify DIO pin numbers for both output and input when constructing an :code:`Ultrasonic` instance: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java :language: java :lines: 17-18 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Ultrasonic/include/Robot.h :language: cpp @@ -31,15 +33,17 @@ The :code:`Ultrasonic` class (`Java ` is used to automatically convert to any desired length unit: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java :language: java :lines: 29-32 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp :language: cpp @@ -60,21 +64,24 @@ Using ultrasonics in code Ultrasonic sensors are very useful for determining spacing during autonomous routines. For example, the following code from the UltrasonicPID example project (`Java `__, `C++ `__)will move the robot to 1 meter away from the nearest object the sensor detects: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java :language: java :lines: 18-61, 71-71 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/include/Robot.h :language: cpp :lines: 19-51 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp :language: cpp @@ -82,15 +89,17 @@ Ultrasonic sensors are very useful for determining spacing during autonomous rou Additionally, ping-response ultrasonics can be sent to :ref:`Shuffleboard `, where they will be displayed with their own widgets: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java :language: java :lines: 22-24 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. rli:: https://github.com/wpilibsuite/allwpilib/raw/v2023.4.3/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp :language: cpp diff --git a/source/docs/software/networktables/client-side-program.rst b/source/docs/software/networktables/client-side-program.rst index 3ed73285fc..6349e1dc25 100644 --- a/source/docs/software/networktables/client-side-program.rst +++ b/source/docs/software/networktables/client-side-program.rst @@ -7,9 +7,10 @@ If all you need to do is have your robot program communicate with a :term:`COTS` A basic client program looks like the following example. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -60,7 +61,8 @@ A basic client program looks like the following example. } } - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: cpp @@ -88,7 +90,8 @@ A basic client program looks like the following example. } } - .. group-tab:: C++ (handle-based) + .. tab-item:: C++ (Handle-based) + :sync: C++ (Handle-based) .. code-block:: cpp @@ -115,7 +118,8 @@ A basic client program looks like the following example. } } - .. group-tab:: C + .. tab-item:: C + :sync: C .. code-block:: c @@ -141,7 +145,9 @@ A basic client program looks like the following example. } } - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python @@ -178,16 +184,18 @@ Building using Gradle Example build.gradle files are provided in the `StandaloneAppSamples Repository `__ Update the GradleRIO version to correspond to the desired WPILib version. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. rli:: https://raw.githubusercontent.com/wpilibsuite/StandaloneAppSamples/3b64aadee717c9f0566497a40fd0be7d0eaed96d/Java/build.gradle :language: groovy :linenos: :emphasize-lines: 5 - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ Uncomment the appropriate platform as highlighted. diff --git a/source/docs/software/networktables/listening-for-change.rst b/source/docs/software/networktables/listening-for-change.rst index 44a868acc8..1e422e87ea 100644 --- a/source/docs/software/networktables/listening-for-change.rst +++ b/source/docs/software/networktables/listening-for-change.rst @@ -5,9 +5,10 @@ A common use case for :term:`NetworkTables` is where a coprocessor generates val There are a few different ways to detect that a topic's value has changed; the easiest way is to periodically call a subscriber's ``get()``, ``readQueue()``, or ``readQueueValues()`` function from the robot's periodic loop, as shown below: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -54,7 +55,8 @@ There are a few different ways to detect that a topic's value has changed; the e } } - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: cpp @@ -96,7 +98,8 @@ There are a few different ways to detect that a topic's value has changed; the e } }; - .. group-tab:: C++ (handle-based) + .. tab-item:: C++ (Handle-based) + :sync: C++ (Handle-based) .. code-block:: cpp @@ -129,7 +132,9 @@ There are a few different ways to detect that a topic's value has changed; the e } }; - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python @@ -185,9 +190,10 @@ The below example listens to various kinds of events using ``NetworkTableInstanc The ``addListener`` functions in NetworkTableInstance return a listener handle. This can be used to remove the listener later. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -263,7 +269,8 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. } } - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: cpp @@ -342,7 +349,9 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. } }; - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python diff --git a/source/docs/software/networktables/multiple-instances.rst b/source/docs/software/networktables/multiple-instances.rst index 57be38d007..1e35a51c6f 100644 --- a/source/docs/software/networktables/multiple-instances.rst +++ b/source/docs/software/networktables/multiple-instances.rst @@ -11,9 +11,10 @@ The ``NetworkTableInstance`` (`Java `__, `C++ `__, `Python `__) that must be retained to continue subscribing (and publishing). -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -517,7 +530,8 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway } } - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: cpp @@ -566,7 +580,8 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway } }; - .. group-tab:: C++ (handle-based) + .. tab-item:: C++ (Handle-based) + :sync: C++ (Handle-based) .. code-block:: cpp @@ -613,7 +628,8 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway nt::ReleaseEntry(dblEntry); } - .. group-tab:: C + .. tab-item:: C + :sync: C .. code-block:: c @@ -661,7 +677,9 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway // stop subscribing NT_ReleaseEntry(dblEntry); - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python @@ -714,9 +732,10 @@ Using GenericEntry, GenericPublisher, and GenericSubscriber For the most robust code, using the type-specific Publisher, Subscriber, and Entry classes is recommended, but in some cases it may be easier to write code that uses type-specific get and set function calls instead of having the NetworkTables type be exposed via the class (object) type. The ``GenericPublisher`` (`Java `__, `C++ `__, `Python `__), ``GenericSubscriber`` (`Java `__, `C++ `__, `Python `__), and ``GenericEntry`` (`Java `__, `C++ `__, `Python `__) classes enable this approach. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -792,7 +811,8 @@ For the most robust code, using the type-specific Publisher, Subscriber, and Ent } } - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: cpp @@ -861,7 +881,9 @@ For the most robust code, using the type-specific Publisher, Subscriber, and Ent } }; - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python @@ -938,9 +960,10 @@ Subscribing to Multiple Topics While in most cases it's only necessary to subscribe to individual topics, it is sometimes useful (e.g. in dashboard applications) to subscribe and get value updates for changes to multiple topics. Listeners (see :ref:`docs/software/networktables/listening-for-change:listening for changes`) can be used directly, but creating a ``MultiSubscriber`` (`Java `__, `C++ `__) allows specifying subscription options and reusing the same subscriber for multiple listeners. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -984,7 +1007,8 @@ While in most cases it's only necessary to subscribe to individual topics, it is } } - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: cpp @@ -1020,7 +1044,8 @@ While in most cases it's only necessary to subscribe to individual topics, it is } }; - .. group-tab:: C++ (handle-based) + .. tab-item:: C++ (Handle-based) + :sync: C++ (Handle-based) .. code-block:: cpp @@ -1062,7 +1087,8 @@ While in most cases it's only necessary to subscribe to individual topics, it is nt::UnsubscribeMultiple(multiSub); } - .. group-tab:: C + .. tab-item:: C + :sync: C .. code-block:: c @@ -1104,7 +1130,9 @@ While in most cases it's only necessary to subscribe to individual topics, it is // stop subscribing NT_UnsubscribeMultiple(multiSub); - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python diff --git a/source/docs/software/networktables/tables-and-topics.rst b/source/docs/software/networktables/tables-and-topics.rst index 2df4d9692c..c7188b3ff2 100644 --- a/source/docs/software/networktables/tables-and-topics.rst +++ b/source/docs/software/networktables/tables-and-topics.rst @@ -13,9 +13,10 @@ A ``Topic`` (`Java `__, `C++ `__, `Python `__), but there is no check at the Topic level to ensure that the topic's type actually matches. The preferred method to get a type-specific topic to call the appropriate type-specific getter, but it's also possible to directly convert a generic Topic into a type-specific Topic class. Note: the handle-based API does not have a concept of type-specific classes. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. code-block:: java @@ -35,7 +36,8 @@ Having a Topic object or handle does not mean the topic exists or is of the corr Topic genericTopic = inst.getTopic("/datatable/X"); DoubleTopic dblTopic = new DoubleTopic(genericTopic); - .. group-tab:: C++ + .. tab-item:: C++ + :sync: C++ .. code-block:: cpp @@ -55,7 +57,8 @@ Having a Topic object or handle does not mean the topic exists or is of the corr nt::Topic genericTopic = inst.GetTopic("/datatable/X"); nt::DoubleTopic dblTopic{genericTopic}; - .. group-tab:: C++ (handle-based) + .. tab-item:: C++ (Handle-based) + :sync: C++ (Handle-based) .. code-block:: cpp @@ -64,7 +67,8 @@ Having a Topic object or handle does not mean the topic exists or is of the corr // get a topic from a NetworkTableInstance NT_Topic topic = nt::GetTopic(inst, "/datatable/X"); - .. group-tab:: C + .. tab-item:: C + :sync: C .. code-block:: c @@ -73,7 +77,9 @@ Having a Topic object or handle does not mean the topic exists or is of the corr // get a topic from a NetworkTableInstance NT_Topic topic = NT_GetTopic(inst, "/datatable/X"); - .. group-tab:: Python + .. tab-item:: Python + :sync: Python + .. code-block:: python diff --git a/source/docs/software/pathplanning/trajectory-tutorial/creating-drive-subsystem.rst b/source/docs/software/pathplanning/trajectory-tutorial/creating-drive-subsystem.rst index 6e475f27a4..543348f237 100644 --- a/source/docs/software/pathplanning/trajectory-tutorial/creating-drive-subsystem.rst +++ b/source/docs/software/pathplanning/trajectory-tutorial/creating-drive-subsystem.rst @@ -5,9 +5,10 @@ Now that our drive is characterized, it is time to start writing our robot code The full drive class from the RamseteCommand Example Project (`Java `__, `C++ `__) can be seen below. The rest of the article will describe the steps involved in writing this class. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java :language: java @@ -15,7 +16,8 @@ The full drive class from the RamseteCommand Example Project (`Java `__, which has been included in the kit of parts for several years: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java :language: java @@ -124,7 +134,8 @@ The gyroscope measures the rate of change of the robot's heading (which can then :linenos: :lineno-start: 50 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h :language: c++ @@ -137,9 +148,10 @@ Gyroscope Accessor Method To access the current heading measured by the gyroscope, we include the following method: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java :language: java @@ -147,7 +159,8 @@ To access the current heading measured by the gyroscope, we include the followin :linenos: :lineno-start: 177 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp :language: c++ @@ -162,9 +175,10 @@ Now that we have our encoders and gyroscope configured, it is time to set up our First, we create a member instance of the ``DifferentialDriveOdometry`` class: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java :language: java @@ -172,7 +186,8 @@ First, we create a member instance of the ``DifferentialDriveOdometry`` class: :linenos: :lineno-start: 53 - .. group-tab:: C++ (Header) + .. tab-item:: C++ (Header) + :sync: C++ (Header) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h :language: c++ @@ -185,9 +200,10 @@ Updating the Odometry The odometry class must be regularly updated to incorporate new readings from the encoder and gyroscope. We accomplish this inside the subsystem's ``periodic`` method, which is automatically called once per main loop iteration: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java :language: java @@ -195,7 +211,8 @@ The odometry class must be regularly updated to incorporate new readings from th :linenos: :lineno-start: 70 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp :language: c++ @@ -208,9 +225,10 @@ Odometry Accessor Method To access the robot's current computed pose, we include the following method: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java :language: java @@ -218,7 +236,8 @@ To access the robot's current computed pose, we include the following method: :linenos: :lineno-start: 79 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp :language: c++ @@ -233,9 +252,10 @@ Voltage-Based Drive Method Finally, we must include one additional method - a method that allows us to set the voltage to each side of the drive using the ``setVoltage()`` method of the ``MotorController`` interface. The default WPILib drive class does not include this functionality, so we must write it ourselves: -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java :language: java @@ -243,7 +263,8 @@ Finally, we must include one additional method - a method that allows us to set :linenos: :lineno-start: 118 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/subsystems/DriveSubsystem.cpp :language: c++ diff --git a/source/docs/software/pathplanning/trajectory-tutorial/creating-following-trajectory.rst b/source/docs/software/pathplanning/trajectory-tutorial/creating-following-trajectory.rst index 66df332d64..ec040a6c1f 100644 --- a/source/docs/software/pathplanning/trajectory-tutorial/creating-following-trajectory.rst +++ b/source/docs/software/pathplanning/trajectory-tutorial/creating-following-trajectory.rst @@ -5,9 +5,10 @@ With our drive subsystem written, it is now time to generate a trajectory and wr As per the :ref:`standard command-based project structure `, we will do this in the ``getAutonomousCommand`` method of the ``RobotContainer`` class. The full method from the RamseteCommand Example Project (`Java `__, `C++ `__) can be seen below. The rest of the article will break down the different parts of the method in more detail. -.. tabs:: +.. tab-set:: - .. group-tab:: Java + .. tab-item:: Java + :sync: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java :language: java @@ -15,7 +16,9 @@ As per the :ref:`standard command-based project structure `__, `C++ `__) -.. tabs:: +.. tab-set:: + + .. tab-item:: Java + :sync: Java - .. group-tab:: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/RobotContainer.java :language: java @@ -139,7 +159,9 @@ Now that we have a trajectory, we can create a command that, when executed, will :linenos: :lineno-start: 112 - .. group-tab:: C++ (Source) + .. tab-item:: C++ (Source) + :sync: C++ (Source) + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/cpp/RobotContainer.cpp :language: c++ diff --git a/source/docs/software/pathplanning/trajectory-tutorial/entering-constants.rst b/source/docs/software/pathplanning/trajectory-tutorial/entering-constants.rst index 29c2109760..9e63ac8b95 100644 --- a/source/docs/software/pathplanning/trajectory-tutorial/entering-constants.rst +++ b/source/docs/software/pathplanning/trajectory-tutorial/entering-constants.rst @@ -14,46 +14,40 @@ Firstly, we must enter the feedforward and feedback gains which we obtained from .. note:: Feedforward and feedback gains do *not*, in general, transfer across robots. Do *not* use the gains from this tutorial for your own robot. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java + :language: java + :lines: 39-49 + :linenos: + :lineno-start: 39 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java - :language: java - :lines: 39-49 - :linenos: - :lineno-start: 39 - - .. group-tab:: C++ (Header) - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h - :language: c++ - :lines: 47-57 - :linenos: - :lineno-start: 47 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h + :language: c++ + :lines: 47-57 + :linenos: + :lineno-start: 47 DifferentialDriveKinematics --------------------------- Additionally, we must create an instance of the ``DifferentialDriveKinematics`` class, which allows us to use the trackwidth (i.e. horizontal distance between the wheels) of the robot to convert from chassis speeds to wheel speeds. As elsewhere, we keep our units in meters. -.. tabs:: +.. tab-set-code:: - .. group-tab:: Java - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java - :language: java - :lines: 29-31 - :linenos: - :lineno-start: 29 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java + :language: java + :lines: 29-31 + :linenos: + :lineno-start: 29 - .. group-tab:: C++ (Header) - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h - :language: c++ - :lines: 38-39 - :linenos: - :lineno-start: 38 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h + :language: c++ + :lines: 38-39 + :linenos: + :lineno-start: 38 Max Trajectory Velocity/Acceleration ------------------------------------ @@ -62,43 +56,35 @@ We must also decide on a nominal max acceleration and max velocity for the robot .. warning:: Max velocity and acceleration, as defined here, are applied only during trajectory generation. They do not limit the ``RamseteCommand`` itself, which may give values to the ``DriveSubsystem`` that can cause the robot to greatly exceed these velocities and accelerations. -.. tabs:: - - .. group-tab:: Java +.. tab-set-code:: - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java - :language: java - :lines: 57-58 - :linenos: - :lineno-start: 57 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java + :language: java + :lines: 57-58 + :linenos: + :lineno-start: 57 - .. group-tab:: C++ (Header) - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h - :language: c++ - :lines: 61-62 - :linenos: - :lineno-start: 61 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h + :language: c++ + :lines: 61-62 + :linenos: + :lineno-start: 61 Ramsete Parameters ------------------ Finally, we must include a pair of parameters for the RAMSETE controller. The values shown below should work well for most robots, provided distances have been correctly measured in meters - for more information on tuning these values (if it is required), see :ref:`docs/software/advanced-controls/trajectories/ramsete:Constructing the Ramsete Controller Object`. -.. tabs:: - - .. group-tab:: Java - - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java - :language: java - :lines: 60-62 - :linenos: - :lineno-start: 60 +.. tab-set-code:: - .. group-tab:: C++ (Header) + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/Constants.java + :language: java + :lines: 60-62 + :linenos: + :lineno-start: 60 - .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h - :language: c++ - :lines: 64-67 - :linenos: - :lineno-start: 64 + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/Constants.h + :language: c++ + :lines: 64-67 + :linenos: + :lineno-start: 64 From a6ed635fc18b259edb05847b2f9d27f96bccd52f Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Wed, 25 Oct 2023 18:22:02 -0400 Subject: [PATCH 7/9] remove sphinx tabs from config --- source/conf.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/source/conf.py b/source/conf.py index 1225936e8d..2849c393c4 100644 --- a/source/conf.py +++ b/source/conf.py @@ -35,7 +35,6 @@ # extensions coming with Sphinx (named 'sphinx.ext.*') or your custom # ones. extensions = [ - "sphinx_tabs.tabs", "sphinx_design", "sphinx.ext.mathjax", "sphinx.ext.todo", @@ -54,7 +53,6 @@ "notfound.extension", "versionwarning.extension", "sphinx.ext.viewcode", - "sphinx_tabs.tabs", "sphinx-prompt", "sphinx_toolbox.collapse", ] @@ -276,7 +274,6 @@ def setup(app): suppress_warnings = ["epub.unknown_project_files"] -sphinx_tabs_valid_builders = ["epub", "linkcheck"] # Options for translation support ------------------------------------------- From 183d1b194cf1c6ee13785bce1593dbfd422fd666 Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Thu, 26 Oct 2023 07:19:04 -0400 Subject: [PATCH 8/9] Format and lint --- source/conf.py | 1 - .../state-space/state-space-flywheel-walkthrough.rst | 4 ++-- .../advanced-controls/state-space/state-space-observers.rst | 2 +- .../docs/software/basic-programming/reading-stacktraces.rst | 2 +- source/docs/software/commandbased/command-scheduler.rst | 4 ++-- source/docs/software/hardware-apis/pneumatics/pressure.rst | 2 +- source/docs/software/hardware-apis/pneumatics/solenoids.rst | 2 +- .../reading-array-values-published-by-networktables.rst | 2 +- .../robotbuilder/writing-code/robotbuilder-drive-tank.rst | 2 +- .../writing-code/robotbuilder-writing-subsystem-code.rst | 2 +- .../step-4/creating-test-drivetrain-program-cpp-java.rst | 2 +- 11 files changed, 12 insertions(+), 13 deletions(-) diff --git a/source/conf.py b/source/conf.py index 2849c393c4..4c04727305 100644 --- a/source/conf.py +++ b/source/conf.py @@ -275,7 +275,6 @@ def setup(app): suppress_warnings = ["epub.unknown_project_files"] - # Options for translation support ------------------------------------------- gettext_compact = False diff --git a/source/docs/software/advanced-controls/state-space/state-space-flywheel-walkthrough.rst b/source/docs/software/advanced-controls/state-space/state-space-flywheel-walkthrough.rst index 6ad88d9a5f..8846929d27 100644 --- a/source/docs/software/advanced-controls/state-space/state-space-flywheel-walkthrough.rst +++ b/source/docs/software/advanced-controls/state-space/state-space-flywheel-walkthrough.rst @@ -82,13 +82,13 @@ The ``LinearSystem`` class contains methods for easily creating state-space syst .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp :language: cpp :lines: 17 - :linenos: + :linenos: :lineno-start: 17 .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp :language: cpp :lines: 30-46 - :linenos: + :linenos: :lineno-start: 30 diff --git a/source/docs/software/advanced-controls/state-space/state-space-observers.rst b/source/docs/software/advanced-controls/state-space/state-space-observers.rst index 8edeb056e5..dc6fc87413 100644 --- a/source/docs/software/advanced-controls/state-space/state-space-observers.rst +++ b/source/docs/software/advanced-controls/state-space/state-space-observers.rst @@ -97,7 +97,7 @@ Tuning Kalman Filters WPILib's Kalman Filter classes' constructors take a linear system, a vector of process noise standard deviations and measurement noise standard deviations. These are converted to :math:`\mathbf{Q}` and :math:`\mathbf{R}` matrices by filling the diagonals with the square of the standard deviations, or variances, of each state or measurement. By decreasing a state's standard deviation (and therefore its corresponding entry in :math:`\mathbf{Q}`), the filter will distrust incoming measurements more. Similarly, increasing a state's standard deviation will trust incoming measurements more. The same holds for the measurement standard deviations -- decreasing an entry will make the filter more highly trust the incoming measurement for the corresponding state, while increasing it will decrease trust in the measurement. .. tab-set:: - .. tab-item:: Java + .. tab-item:: Java .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceflywheel/Robot.java :language: java diff --git a/source/docs/software/basic-programming/reading-stacktraces.rst b/source/docs/software/basic-programming/reading-stacktraces.rst index 42119aa2a1..46991a814e 100644 --- a/source/docs/software/basic-programming/reading-stacktraces.rst +++ b/source/docs/software/basic-programming/reading-stacktraces.rst @@ -330,7 +330,7 @@ When run, you'll see output that looks like this: :sync: tabcode-java .. code-block:: text - + ********** Robot program starting ********** Error at frc.robot.Robot.robotInit(Robot.java:24): Unhandled exception: java.lang.ArithmeticException: / by zero diff --git a/source/docs/software/commandbased/command-scheduler.rst b/source/docs/software/commandbased/command-scheduler.rst index 343dc5a5f9..6950d3b88b 100644 --- a/source/docs/software/commandbased/command-scheduler.rst +++ b/source/docs/software/commandbased/command-scheduler.rst @@ -53,7 +53,7 @@ This method walks through the following steps: :lines: 114-159 :linenos: :lineno-start: 114 - + The Scheduler Run Sequence -------------------------- @@ -98,7 +98,7 @@ Secondly, the scheduler polls the state of all registered triggers to see if any .. tab-item:: Java :sync: tabcode-java - + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java :language: java :lines: 290-292 diff --git a/source/docs/software/hardware-apis/pneumatics/pressure.rst b/source/docs/software/hardware-apis/pneumatics/pressure.rst index db98e0d154..aff6f0d21f 100644 --- a/source/docs/software/hardware-apis/pneumatics/pressure.rst +++ b/source/docs/software/hardware-apis/pneumatics/pressure.rst @@ -9,7 +9,7 @@ Construct a ``Compressor`` object: .. tab-set:: .. tab-item:: REV Pneumatic Hub (PH) - + .. tab-set:: .. tab-item:: Java :sync: Java diff --git a/source/docs/software/hardware-apis/pneumatics/solenoids.rst b/source/docs/software/hardware-apis/pneumatics/solenoids.rst index b84b2ed554..79822098ff 100644 --- a/source/docs/software/hardware-apis/pneumatics/solenoids.rst +++ b/source/docs/software/hardware-apis/pneumatics/solenoids.rst @@ -79,7 +79,7 @@ Double solenoids are controlled by the ``DoubleSolenoid`` class in WPILib (`Java .. tab-item:: C++ (Source) :sync: C++ (Source) - + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/e9858c10e900d322c3c03eb170ec76c3bcc3a7e0/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp :language: c++ :lines: 54, 56 diff --git a/source/docs/software/networktables/reading-array-values-published-by-networktables.rst b/source/docs/software/networktables/reading-array-values-published-by-networktables.rst index b7e5a37b5a..9a10bc8327 100644 --- a/source/docs/software/networktables/reading-array-values-published-by-networktables.rst +++ b/source/docs/software/networktables/reading-array-values-published-by-networktables.rst @@ -20,7 +20,7 @@ Writing a Program to Access the Topics -------------------------------------- .. tab-set-code:: - + .. code-block:: java DoubleArraySubscriber areasSub; diff --git a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-drive-tank.rst b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-drive-tank.rst index 823b972348..c4832f6bd7 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-drive-tank.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-drive-tank.rst @@ -45,7 +45,7 @@ Create a Method to Write the Motors on the Subsystem .. tab-item:: java :sync: java - + .. code-block:: java :linenos: :lineno-start: 11 diff --git a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-subsystem-code.rst b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-subsystem-code.rst index 1fe35a782e..be71fd4cdc 100644 --- a/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-subsystem-code.rst +++ b/source/docs/software/wpilib-tools/robotbuilder/writing-code/robotbuilder-writing-subsystem-code.rst @@ -230,4 +230,4 @@ Adding the Method Declarations to the Header File (C++ Only) In addition to adding the methods to the class implementation file, ``Claw.cpp``, the declarations for the methods need to be added to the header file, ``Claw.h``. Those declarations that must be added are shown here. -To add the behavior to the claw subsystem to handle opening and closing you need to :doc:`define commands <../introduction/robotbuilder-creating-command>`. \ No newline at end of file +To add the behavior to the claw subsystem to handle opening and closing you need to :doc:`define commands <../introduction/robotbuilder-creating-command>`. diff --git a/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java.rst b/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java.rst index 3be8ca3492..bc1dcce5de 100644 --- a/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java.rst +++ b/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java.rst @@ -80,7 +80,7 @@ Imports/Includes .. tab-item:: C++ :sync: cpp - + .. remoteliteralinclude:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp :language: c++ :lines: 5-10 From a8adcaf032462d00866913df3dac0cef8520ec6b Mon Sep 17 00:00:00 2001 From: GrahamSH Date: Mon, 30 Oct 2023 11:57:45 -0400 Subject: [PATCH 9/9] add to style guide --- .../contributing/frc-docs/style-guide.rst | 46 ++++++++++++++++++- 1 file changed, 45 insertions(+), 1 deletion(-) diff --git a/source/docs/contributing/frc-docs/style-guide.rst b/source/docs/contributing/frc-docs/style-guide.rst index 5a3fa0d539..bc5308490c 100644 --- a/source/docs/contributing/frc-docs/style-guide.rst +++ b/source/docs/contributing/frc-docs/style-guide.rst @@ -107,7 +107,6 @@ When possible, instead of using code blocks, an RLI should be used. This pulls .. code-block:: ReST - .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Robot.java :language: java :lines: 44-61 @@ -123,6 +122,51 @@ When possible, instead of using code blocks, an RLI should be used. This pulls Make sure to link to the raw version of the file on GitHub. There is a handy ``Raw`` button in the top right corner of the page. +Tabs +---- +To create code tabs in an article, you can use the ``.. tab-set-code::`` directive. You can use ``code-block`` and ``rli`` directives inside. The format is: + +.. code-block:: ReST + + .. tab-set-code:: + + .. rli:: https://raw.githubusercontent.com/wpilibsuite/allwpilib/v2023.4.3/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecontroller/Robot.java + :language: java + :lines: 44-61 + :linenos: + :lineno-start: 44 + + + .. code-block:: cpp + // Start the timer. + m_timer.Start(); + + // Send Field2d to SmartDashboard. + frc::SmartDashboard::PutData(&m_field); + + // Reset the drivetrain's odometry to the starting pose of the trajectory. + m_drive.ResetOdometry(m_trajectory.InitialPose()); + + // Send our generated trajectory to Field2d. + m_field.GetObject("traj")->SetTrajectory(m_trajectory); + } + + +If you need to use more than one tab per language, multiple RLIs per language, or text tabs, you can use the ``.. tab-set::`` and ``.. tab-item::`` directive. The format is: + +.. code-block:: ReST + + .. tab-set:: + + ..tab-item:: Title + :sync: sync-id + + Content + +This example uses the sync argument to allow all of the tabs with the same key to be synced together. This means that when you click on a tab, all of the tabs with the same key will open. + +If you have a mix of ``tab-set`` and ``tab-set-code`` directives on a page, you can sync them by setting the sync id on the ``tab-item`` directives to ``tabcode-LANGUAGE``. For example, a java tab would have a sync id of ``tabcode-java``. + Admonitions -----------