From e53db15a2003c4cd36a3e176c117bc4ba0d5dede Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Fri, 6 Sep 2024 10:15:22 -0400 Subject: [PATCH] Fix formatting in md code blocks (#2726) --- .../controllers/profiled-pidcontroller.rst | 14 +- .../controllers/trapezoidal-profiles.rst | 6 +- .../advanced-controls/filters/debouncer.rst | 18 +- .../filters/linear-filter.rst | 6 +- .../filters/median-filter.rst | 2 +- .../filters/slew-rate-limiter.rst | 8 +- .../state-space/state-space-debugging.rst | 2 +- .../state-space/state-space-intro.rst | 22 +- .../creating-routine.rst | 3 +- .../trajectories/constraints.rst | 6 +- .../trajectories/holonomic.rst | 12 +- .../trajectories/ramsete.rst | 12 +- .../trajectories/trajectory-generation.rst | 12 +- .../transforming-trajectories.rst | 6 +- .../trajectories/troubleshooting.rst | 26 +- .../basic-programming/alliancecolor.rst | 2 +- .../basic-programming/coordinate-system.rst | 12 +- .../software/basic-programming/java-units.rst | 2 +- .../software/basic-programming/joystick.rst | 28 +- .../basic-programming/reading-stacktraces.rst | 192 ++++---- .../can-devices/power-distribution-module.rst | 2 +- .../binding-commands-to-triggers.rst | 8 +- .../commandbased/command-compositions.rst | 14 +- .../commandbased/organizing-command-based.rst | 62 +-- .../docs/software/commandbased/subsystems.rst | 20 +- .../scheduling-functions.rst | 12 +- .../glass/command-based-widgets.rst | 6 +- .../dashboards/glass/field2d-widget.rst | 16 +- .../software/dashboards/glass/widgets.rst | 4 +- ...e-labview-dashboard-with-c++-java-code.rst | 16 +- .../shuffleboard-commands-subsystems.rst | 4 +- .../shuffleboard-tuning-pid.rst | 14 +- .../custom-widgets/creating-plugins.rst | 4 +- .../shuffleboard-displaying-data.rst | 2 +- .../getting-started/shuffleboard-tour.rst | 2 +- .../layouts-with-code/configuring-widgets.rst | 4 +- .../layouts-with-code/organizing-widgets.rst | 10 +- .../layouts-with-code/retrieving-data.rst | 18 +- .../layouts-with-code/sending-data.rst | 16 +- .../layouts-with-code/using-tabs.rst | 4 +- ...autonomous-program-from-smartdashboard.rst | 8 +- .../smartdashboard/displaying-expressions.rst | 2 +- ...ying-status-of-commands-and-subsystems.rst | 6 +- .../displaying-LiveWindow-values.rst | 24 +- .../enabling-test-mode.rst | 6 +- .../verifying-smartdashboard-is-working.rst | 8 +- .../hardware-apis/misc/addressable-leds.rst | 8 +- .../motors/using-motor-controllers.rst | 20 +- .../motors/wpi-drive-classes.rst | 22 +- .../hardware-apis/pneumatics/solenoids.rst | 8 +- .../sensors/accelerometers-software.rst | 38 +- .../sensors/analog-inputs-software.rst | 22 +- .../analog-potentiometers-software.rst | 12 +- .../hardware-apis/sensors/counters.rst | 52 +-- .../sensors/digital-inputs-software.rst | 20 +- .../sensors/encoders-software.rst | 76 ++-- .../hardware-apis/sensors/gyros-software.rst | 164 +++---- .../hardware-apis/sensors/limit-switch.rst | 8 +- .../differential-drive-kinematics.rst | 42 +- .../differential-drive-odometry.rst | 10 +- .../intro-and-chassis-speeds.rst | 4 +- .../mecanum-drive-kinematics.rst | 38 +- .../mecanum-drive-odometry.rst | 26 +- .../swerve-drive-kinematics.rst | 70 +-- .../swerve-drive-odometry.rst | 22 +- .../networktables/client-side-program.rst | 28 +- .../networktables/listening-for-change.rst | 94 ++-- .../networktables/multiple-instances.rst | 22 +- .../networktables-networking.rst | 46 +- .../networktables/nt4-migration-guide.rst | 70 +-- .../networktables/publish-and-subscribe.rst | 349 ++++++++------- ...rray-values-published-by-networktables.rst | 28 +- .../software/networktables/robot-program.rst | 38 +- .../networktables/tables-and-topics.rst | 24 +- .../pathweaver/integrating-robot-program.rst | 6 +- source/docs/software/telemetry/datalog.rst | 46 +- .../robot-telemetry-with-annotations.rst | 56 +-- .../robot-telemetry-with-sendable.rst | 2 +- .../introduction/cameraserver-class.rst | 24 +- .../roborio/using-multiple-cameras.rst | 56 +-- .../using-the-cameraserver-on-the-roborio.rst | 4 +- .../wpilibpi/basic-vision-example.rst | 48 +- .../wpilibpi/using-cameraserver.rst | 22 +- .../wpilibpi/working-with-contours.rst | 12 +- .../robot-simulation/device-sim.rst | 2 +- .../drivesim-tutorial/drivetrain-model.rst | 26 +- .../drivesim-tutorial/odometry-simgui.rst | 6 +- .../drivesim-tutorial/simulation-instance.rst | 16 +- .../updating-drivetrain-model.rst | 16 +- .../robot-simulation/simulation-gui.rst | 2 +- ...robotbuilder-writing-pidsubsystem-code.rst | 48 +- .../robotbuilder-created-code.rst | 411 ++++++++++++------ .../writing-code/robotbuilder-drive-tank.rst | 328 +++++++++----- .../robotbuilder-writing-command-code.rst | 165 ++++--- .../robotbuilder-writing-subsystem-code.rst | 148 +++++-- .../docs/yearly-overview/2020-Game-Data.rst | 4 +- ...est-drivetrain-program-cpp-java-python.rst | 24 +- 97 files changed, 1938 insertions(+), 1578 deletions(-) diff --git a/source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst b/source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst index 4a2ae3ada3..5c3c0fc09e 100644 --- a/source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst +++ b/source/docs/software/advanced-controls/controllers/profiled-pidcontroller.rst @@ -121,19 +121,19 @@ The returned setpoint might then be used as in the following example: from wpilib import Timer from wpilib.controller import ProfiledPIDController from wpilib.controller import SimpleMotorFeedforward - def __init__(self): - # Assuming encoder, motor, controller are already defined + def __init__(self): + # Assuming encoder, motor, controller are already defined self.lastSpeed = 0 self.lastTime = Timer.getFPGATimestamp() - # Assuming feedforward is a SimpleMotorFeedforward object + # Assuming feedforward is a SimpleMotorFeedforward object self.feedforward = SimpleMotorFeedforward(ks=0.0, kv=0.0, ka=0.0) - def goToPosition(self, goalPosition: float): - pidVal = self.controller.calculate(self.encoder.getDistance(), goalPosition) + def goToPosition(self, goalPosition: float): + pidVal = self.controller.calculate(self.encoder.getDistance(), goalPosition) acceleration = (self.controller.getSetpoint().velocity - self.lastSpeed) / (Timer.getFPGATimestamp() - self.lastTime) - self.motor.setVoltage( + self.motor.setVoltage( pidVal + self.feedforward.calculate(self.controller.getSetpoint().velocity, acceleration)) - self.lastSpeed = controller.getSetpoint().velocity + self.lastSpeed = controller.getSetpoint().velocity self.lastTime = Timer.getFPGATimestamp() ``` diff --git a/source/docs/software/advanced-controls/controllers/trapezoidal-profiles.rst b/source/docs/software/advanced-controls/controllers/trapezoidal-profiles.rst index 79a4798b18..562bcf0ba0 100644 --- a/source/docs/software/advanced-controls/controllers/trapezoidal-profiles.rst +++ b/source/docs/software/advanced-controls/controllers/trapezoidal-profiles.rst @@ -40,7 +40,7 @@ In order to create a trapezoidal motion profile, we must first impose some const ```python from wpimath.trajectory import TrapezoidProfile - # Creates a new set of trapezoidal motion profile constraints + # Creates a new set of trapezoidal motion profile constraints # Max velocity of 10 meters per second # Max acceleration of 20 meters per second squared TrapezoidProfile.Constraints(10, 20) @@ -66,7 +66,7 @@ Next, we must specify the desired starting and ending states for our mechanisms ```python from wpimath.trajectory import TrapezoidProfile - # Creates a new state with a position of 5 meters + # Creates a new state with a position of 5 meters # and a velocity of 0 meters per second TrapezoidProfile.State(5, 0) ``` @@ -96,7 +96,7 @@ Now that we know how to create a set of constraints and the desired start/end st ```python from wpimath.trajectory import TrapezoidProfile - # Creates a new TrapezoidProfile + # 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 profile = TrapezoidProfile(TrapezoidProfile.Constraints(5, 10)) diff --git a/source/docs/software/advanced-controls/filters/debouncer.rst b/source/docs/software/advanced-controls/filters/debouncer.rst index a1fec9981c..2640ab3a8e 100644 --- a/source/docs/software/advanced-controls/filters/debouncer.rst +++ b/source/docs/software/advanced-controls/filters/debouncer.rst @@ -19,33 +19,33 @@ The WPILib ``Debouncer`` can be configured in three different modes: ```java // Initializes a DigitalInput on DIO 0 DigitalInput input = new DigitalInput(0); - // Creates a Debouncer in "both" mode. + // Creates a Debouncer in "both" mode. Debouncer m_debouncer = new Debouncer(0.1, Debouncer.DebounceType.kBoth); - // So if currently false the signal must go true for at least .1 seconds before being read as a True signal. + // So if currently false the signal must go true for at least .1 seconds before being read as a True signal. if (m_debouncer.calculate(input.get())) { - // Do something now that the DI is True. + // Do something now that the DI is True. } ``` ```c++ // Initializes a DigitalInput on DIO 0 frc::DigitalInput input{0}; - // Creates a Debouncer in "both" mode. + // Creates a Debouncer in "both" mode. frc::Debouncer m_debouncer{100_ms, frc::Debouncer::DebounceType::kBoth}; - // So if currently false the signal must go true for at least .1 seconds before being read as a True signal. + // So if currently false the signal must go true for at least .1 seconds before being read as a True signal. if (m_debouncer.calculate(input.Get())) { - // Do something now that the DI is True. + // Do something now that the DI is True. } ``` ```python from wpilib import DigitalInput from wpimath.filter import Debouncer - # Initializes a DigitalInput on DIO 0 + # Initializes a DigitalInput on DIO 0 self.input = DigitalInput(0) - # Creates a Debouncer in "both" mode with a debounce time of 0.1 seconds + # Creates a Debouncer in "both" mode with a debounce time of 0.1 seconds self.debouncer = Debouncer(0.1, Debouncer.DebounceType.kBoth) - # If currently false, the signal must go true for at least 0.1 seconds before being read as a True signal. + # If currently false, the signal must go true for at least 0.1 seconds before being read as a True signal. if self.debouncer.calculate(self.input.get()): # Do something now that the DI is True. pass diff --git a/source/docs/software/advanced-controls/filters/linear-filter.rst b/source/docs/software/advanced-controls/filters/linear-filter.rst index 320222f0b2..89670dde5f 100644 --- a/source/docs/software/advanced-controls/filters/linear-filter.rst +++ b/source/docs/software/advanced-controls/filters/linear-filter.rst @@ -45,7 +45,7 @@ The ``singlePoleIIR()`` factory method creates a single-pole infinite impulse re ```python from wpimath.filter import LinearFilter - # Creates a new Single-Pole IIR filter + # 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 filter = LinearFilter.singlePoleIIR(0.1, 0.02) @@ -78,7 +78,7 @@ The ``movingAverage`` factory method creates a simple flat moving average filter ```python from wpimath.filter import LinearFilter - # Creates a new flat moving average filter + # Creates a new flat moving average filter # Average will be taken over the last 5 samples filter = LinearFilter.movingAverage(5) ``` @@ -110,7 +110,7 @@ The ``highPass`` factory method creates a simple first-order infinite impulse re ```python from wpimath.filter import LinearFilter - # Creates a new high-pass IIR filter + # 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 filter = LinearFilter.highPass(0.1, 0.02) diff --git a/source/docs/software/advanced-controls/filters/median-filter.rst b/source/docs/software/advanced-controls/filters/median-filter.rst index 86e1fba182..69ea251aaf 100644 --- a/source/docs/software/advanced-controls/filters/median-filter.rst +++ b/source/docs/software/advanced-controls/filters/median-filter.rst @@ -31,7 +31,7 @@ Creating a ``MedianFilter`` is simple: ```python from wpimath.filter import MedianFilter - # Creates a MedianFilter with a window size of 5 samples + # Creates a MedianFilter with a window size of 5 samples filter = MedianFilter(5) ``` 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 a38ceb7f6a..2b091adaf2 100644 --- a/source/docs/software/advanced-controls/filters/slew-rate-limiter.rst +++ b/source/docs/software/advanced-controls/filters/slew-rate-limiter.rst @@ -30,7 +30,7 @@ Creating a SlewRateLimiter is simple: ```python from wpimath.filter import SlewRateLimiter - # Creates a SlewRateLimiter that limits the rate of change of the signal to 0.5 units per second + # Creates a SlewRateLimiter that limits the rate of change of the signal to 0.5 units per second filter = SlewRateLimiter(0.5) ``` @@ -66,21 +66,21 @@ A typical use of a SlewRateLimiter is to limit the acceleration of a robot's dri ```java // Ordinary call with no ramping applied drivetrain.arcadeDrive(forward, turn); - // Slew-rate limits the forward/backward input, limiting forward/backward acceleration + // Slew-rate limits the forward/backward input, limiting forward/backward acceleration drivetrain.arcadeDrive(filter.calculate(forward), turn); ``` ```c++ // Ordinary call with no ramping applied drivetrain.ArcadeDrive(forward, turn); - // Slew-rate limits the forward/backward input, limiting forward/backward acceleration + // Slew-rate limits the forward/backward input, limiting forward/backward acceleration drivetrain.ArcadeDrive(filter.Calculate(forward), turn); ``` ```python # Ordinary call with no ramping applied drivetrain.arcadeDrive(forward, turn) - # Slew-rate limits the forward/backward input, limiting forward/backward acceleration + # Slew-rate limits the forward/backward input, limiting forward/backward acceleration drivetrain.arcadeDrive(filter.calculate(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 7b6bbdff00..4d3929b82f 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 @@ -32,7 +32,7 @@ Reliable data of the :term:`system's ` :term:`state`\s, :term:`input`\s ```python from ntcore import NetworkTableInstance - def robotPeriodic(self): + def robotPeriodic(self): NetworkTableInstance.getDefault().flush() ``` 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 7f5c006b6a..57c29ac63a 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 @@ -174,21 +174,21 @@ For example, we might use the following Q and R for an elevator system with posi ```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}; + 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}; ``` ```python from wpimath.controller import LinearQuadraticRegulator_2_1 from wpimath.system.plant import LinearSystemId - # Example system -- must be changed to match your robot. + # Example system -- must be changed to match your robot. elevatorSystem = LinearSystemId.identifyPositionSystemMeters(5, 0.5) controller = LinearQuadraticRegulator_2_1( elevatorSystem, @@ -199,7 +199,7 @@ For example, we might use the following Q and R for an elevator system with posi # our dt 0.020, ) - ``` + ``` ### LQR: example application diff --git a/source/docs/software/advanced-controls/system-identification/creating-routine.rst b/source/docs/software/advanced-controls/system-identification/creating-routine.rst index fccf613ac9..fd0d7cdb98 100644 --- a/source/docs/software/advanced-controls/system-identification/creating-routine.rst +++ b/source/docs/software/advanced-controls/system-identification/creating-routine.rst @@ -59,7 +59,8 @@ To be able to run the tests, SysIdRoutine exposes test "factories", or functions public Command sysIdQuasistatic(SysIdRoutine.Direction direction) { return routine.quasistatic(direction); } - public Command sysIdDynamic(SysIdRoutine.Direction direction) { + + public Command sysIdDynamic(SysIdRoutine.Direction direction) { return routine.dynamic(direction); } ``` diff --git a/source/docs/software/advanced-controls/trajectories/constraints.rst b/source/docs/software/advanced-controls/trajectories/constraints.rst index b54221b524..89a1837ee6 100644 --- a/source/docs/software/advanced-controls/trajectories/constraints.rst +++ b/source/docs/software/advanced-controls/trajectories/constraints.rst @@ -42,7 +42,7 @@ Users can create their own constraint by implementing the ``TrajectoryConstraint units::meters_per_second_t velocity) override { // code here } - MinMax MinMaxAcceleration(const Pose2d& pose, units::curvature_t curvature, + MinMax MinMaxAcceleration(const Pose2d& pose, units::curvature_t curvature, units::meters_per_second_t speed) override { // code here } @@ -52,7 +52,7 @@ Users can create their own constraint by implementing the ``TrajectoryConstraint from wpimath import units from wpimath.geometry import Pose2d from wpimath.trajectory.constraint import TrajectoryConstraint - class MyConstraint(TrajectoryConstraint): + class MyConstraint(TrajectoryConstraint): def maxVelocity( self, pose: Pose2d, @@ -60,7 +60,7 @@ Users can create their own constraint by implementing the ``TrajectoryConstraint velocity: units.meters_per_second, ) -> units.meters_per_second: ... - def minMaxAcceleration( + def minMaxAcceleration( self, pose: Pose2d, curvature: units.radians_per_meter, diff --git a/source/docs/software/advanced-controls/trajectories/holonomic.rst b/source/docs/software/advanced-controls/trajectories/holonomic.rst index ff162e0159..74ee8778bf 100644 --- a/source/docs/software/advanced-controls/trajectories/holonomic.rst +++ b/source/docs/software/advanced-controls/trajectories/holonomic.rst @@ -39,7 +39,7 @@ The final parameter is a ``ProfiledPIDController`` for the rotation of the robot ProfiledPIDControllerRadians, ) from wpimath.trajectory import TrapezoidProfileRadians - controller = HolonomicDriveController( + controller = HolonomicDriveController( PIDController(1, 0, 0), PIDController(1, 0, 0), ProfiledPIDControllerRadians( @@ -62,7 +62,7 @@ The controller can be updated using the ``Calculate`` (C++) / ``calculate`` (Jav ```java // Sample the trajectory at 3.4 seconds from the beginning. Trajectory.State goal = trajectory.sample(3.4); - // Get the adjusted speeds. Here, we want the robot to be facing + // Get the adjusted speeds. Here, we want the robot to be facing // 70 degrees (in the field-relative coordinate system). ChassisSpeeds adjustedSpeeds = controller.calculate( currentRobotPose, goal, Rotation2d.fromDegrees(70.0)); @@ -71,7 +71,7 @@ The controller can be updated using the ``Calculate`` (C++) / ``calculate`` (Jav ```c++ // Sample the trajectoty at 3.4 seconds from the beginning. const auto goal = trajectory.Sample(3.4_s); - // Get the adjusted speeds. Here, we want the robot to be facing + // Get the adjusted speeds. Here, we want the robot to be facing // 70 degrees (in the field-relative coordinate system). const auto adjustedSpeeds = controller.Calculate( currentRobotPose, goal, 70_deg); @@ -79,9 +79,9 @@ The controller can be updated using the ``Calculate`` (C++) / ``calculate`` (Jav ```python from wpimath.geometry import Rotation2d - # Sample the trajectory at 3.4 seconds from the beginning. + # Sample the trajectory at 3.4 seconds from the beginning. goal = trajectory.sample(3.4) - # Get the adjusted speeds. Here, we want the robot to be facing + # Get the adjusted speeds. Here, we want the robot to be facing # 70 degrees (in the field-relative coordinate system). adjustedSpeeds = controller.calculate( currentRobotPose, goal, Rotation2d.fromDegrees(70.0) @@ -96,7 +96,7 @@ The returned adjusted speeds can be converted into usable speeds using the kinem .. tab-set-code:: ```java SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(adjustedSpeeds); - SwerveModuleState frontLeft = moduleStates[0]; + SwerveModuleState frontLeft = moduleStates[0]; SwerveModuleState frontRight = moduleStates[1]; SwerveModuleState backLeft = moduleStates[2]; SwerveModuleState backRight = moduleStates[3]; diff --git a/source/docs/software/advanced-controls/trajectories/ramsete.rst b/source/docs/software/advanced-controls/trajectories/ramsete.rst index 3363dc2d51..9f54540b6e 100644 --- a/source/docs/software/advanced-controls/trajectories/ramsete.rst +++ b/source/docs/software/advanced-controls/trajectories/ramsete.rst @@ -11,7 +11,7 @@ The Ramsete controller should be initialized with two gains, namely ``b`` and `` // Using the default constructor of RamseteController. Here // the gains are initialized to 2.0 and 0.7. RamseteController controller1 = new RamseteController(); - // Using the secondary constructor of RamseteController where + // Using the secondary constructor of RamseteController where // the user can choose any other gains. RamseteController controller2 = new RamseteController(2.1, 0.8); ``` @@ -20,20 +20,20 @@ The Ramsete controller should be initialized with two gains, namely ``b`` and `` // Using the default constructor of RamseteController. Here // the gains are initialized to 2.0 and 0.7. frc::RamseteController controller1; - // Using the secondary constructor of RamseteController where + // Using the secondary constructor of RamseteController where // the user can choose any other gains. frc::RamseteController controller2{2.1, 0.8}; ``` ```python from wpimath.controller import RamseteController - # Using the default constructor of RamseteController. Here + # Using the default constructor of RamseteController. Here # the gains are initialized to 2.0 and 0.7. controller1 = RamseteController() - # Using the secondary constructor of RamseteController where + # Using the secondary constructor of RamseteController where # the user can choose any other gains. controller2 = RamseteController(2.1, 0.8) - ``` + ``` ## Getting Adjusted Velocities The Ramsete controller returns "adjusted velocities" so that the when the robot tracks these velocities, it accurately reaches the goal point. The controller should be updated periodically with the new goal. The goal comprises of a desired pose, desired linear velocity, and desired angular velocity. Furthermore, the current position of the robot should also be updated periodically. The controller uses these four arguments to return the adjusted linear and angular velocity. Users should command their robot to these linear and angular velocities to achieve optimal trajectory tracking. @@ -47,7 +47,7 @@ The controller can be updated using the ``Calculate`` (C++) / ``calculate`` (Jav ```java Trajectory.State goal = trajectory.sample(3.4); // sample the trajectory at 3.4 seconds from the beginning ChassisSpeeds adjustedSpeeds = controller.calculate(currentRobotPose, goal); - ``` + ``` ```c++ const Trajectory::State goal = trajectory.Sample(3.4_s); // sample the trajectory at 3.4 seconds from the beginning diff --git a/source/docs/software/advanced-controls/trajectories/trajectory-generation.rst b/source/docs/software/advanced-controls/trajectories/trajectory-generation.rst index 8d0d1bcc95..e408bda5a1 100644 --- a/source/docs/software/advanced-controls/trajectories/trajectory-generation.rst +++ b/source/docs/software/advanced-controls/trajectories/trajectory-generation.rst @@ -80,13 +80,13 @@ Trajectories in Java can be combined into a single trajectory using the ``concat List.of(new Translation2d(1, 1), new Translation2d(2, -1)), new Pose2d(3, 0, Rotation2d.fromDegrees(0)), new TrajectoryConfig(Units.feetToMeters(3.0), Units.feetToMeters(3.0))); - var trajectoryTwo = + var trajectoryTwo = TrajectoryGenerator.generateTrajectory( new Pose2d(3, 0, Rotation2d.fromDegrees(0)), List.of(new Translation2d(4, 4), new Translation2d(6, 3)), new Pose2d(6, 0, Rotation2d.fromDegrees(0)), new TrajectoryConfig(Units.feetToMeters(3.0), Units.feetToMeters(3.0))); - var concatTraj = trajectoryOne.concatenate(trajectoryTwo); + var concatTraj = trajectoryOne.concatenate(trajectoryTwo); ``` ```c++ @@ -94,23 +94,23 @@ Trajectories in Java can be combined into a single trajectory using the ``concat frc::Pose2d(0_m, 0_m, 0_rad), {frc::Translation2d(1_m, 1_m), frc::Translation2d(2_m, -1_m)}, frc::Pose2d(3_m, 0_m, 0_rad), frc::TrajectoryConfig(3_fps, 3_fps_sq)); - auto trajectoryTwo = frc::TrajectoryGenerator::GenerateTrajectory( + auto trajectoryTwo = frc::TrajectoryGenerator::GenerateTrajectory( frc::Pose2d(3_m, 0_m, 0_rad), {frc::Translation2d(4_m, 4_m), frc::Translation2d(5_m, 3_m)}, frc::Pose2d(6_m, 0_m, 0_rad), frc::TrajectoryConfig(3_fps, 3_fps_sq)); - auto concatTraj = m_trajectoryOne + m_trajectoryTwo; + auto concatTraj = m_trajectoryOne + m_trajectoryTwo; ``` ```python from wpimath.geometry import Pose2d, Rotation2d, Translation2d from wpimath.trajectory import TrajectoryGenerator, TrajectoryConfig - trajectoryOne = TrajectoryGenerator.generateTrajectory( + trajectoryOne = TrajectoryGenerator.generateTrajectory( Pose2d(0, 0, Rotation2d.fromDegrees(0)), [Translation2d(1, 1), Translation2d(2, -1)], Pose2d(3, 0, Rotation2d.fromDegrees(0)), TrajectoryConfig.fromFps(3.0, 3.0), ) - trajectoryTwo = TrajectoryGenerator.generateTrajectory( + trajectoryTwo = TrajectoryGenerator.generateTrajectory( Pose2d(3, 0, Rotation2d.fromDegrees(0)), [Translation2d(4, 4), Translation2d(6, 3)], Pose2d(6, 0, Rotation2d.fromDegrees(0)), diff --git a/source/docs/software/advanced-controls/trajectories/transforming-trajectories.rst b/source/docs/software/advanced-controls/trajectories/transforming-trajectories.rst index 90704a97eb..867db91533 100644 --- a/source/docs/software/advanced-controls/trajectories/transforming-trajectories.rst +++ b/source/docs/software/advanced-controls/trajectories/transforming-trajectories.rst @@ -24,7 +24,7 @@ For example, a trajectory defined in coordinate system A can be redefined in coo ```python from wpimath.geometry import Pose2d, Rotation2d - bOrigin = Pose2d(3, 3, Rotation2d.fromDegrees(30)) + bOrigin = Pose2d(3, 3, Rotation2d.fromDegrees(30)) bTrajectory = aTrajectory.relativeTo(bOrigin) ``` @@ -53,9 +53,9 @@ For example, one may want to transform a trajectory that begins at (2, 2, 30 deg ```python from wpimath.geometry import Pose2d, Rotation2d - transform = Pose2d(4, 4, Rotation2d.fromDegrees(50)) - trajectory.initialPose() + transform = Pose2d(4, 4, Rotation2d.fromDegrees(50)) - trajectory.initialPose() newTrajectory = trajectory.transformBy(transform) - ``` + ``` .. image:: images/transform-by.png :alt: Coordinate system plot of a transformed trajectory. diff --git a/source/docs/software/advanced-controls/trajectories/troubleshooting.rst b/source/docs/software/advanced-controls/trajectories/troubleshooting.rst index d296fe3923..fdd4ba3e30 100644 --- a/source/docs/software/advanced-controls/trajectories/troubleshooting.rst +++ b/source/docs/software/advanced-controls/trajectories/troubleshooting.rst @@ -61,12 +61,12 @@ If your odometry is bad, then your Ramsete controller may misbehave, because it ```java NetworkTableEntry m_xEntry = NetworkTableInstance.getDefault().getTable("troubleshooting").getEntry("X"); NetworkTableEntry m_yEntry = NetworkTableInstance.getDefault().getTable("troubleshooting").getEntry("Y"); - @Override + @Override public void periodic() { // Update the odometry in the periodic block m_odometry.update(Rotation2d.fromDegrees(getHeading()), m_leftEncoder.getDistance(), m_rightEncoder.getDistance()); - var translation = m_odometry.getPoseMeters().getTranslation(); + var translation = m_odometry.getPoseMeters().getTranslation(); m_xEntry.setNumber(translation.getX()); m_yEntry.setNumber(translation.getY()); } @@ -75,12 +75,12 @@ If your odometry is bad, then your Ramsete controller may misbehave, because it ```c++ NetworkTableEntry m_xEntry = nt::NetworkTableInstance::GetDefault().GetTable("troubleshooting")->GetEntry("X"); NetworkTableEntry m_yEntry = nt::NetworkTableInstance::GetDefault().GetTable("troubleshooting")->GetEntry("Y"); - void DriveSubsystem::Periodic() { + void DriveSubsystem::Periodic() { // Implementation of subsystem periodic method goes here. m_odometry.Update(frc::Rotation2d(units::degree_t(GetHeading())), units::meter_t(m_leftEncoder.GetDistance()), units::meter_t(m_rightEncoder.GetDistance())); - auto translation = m_odometry.GetPose().Translation(); + auto translation = m_odometry.GetPose().Translation(); m_xEntry.SetDouble(translation.X().value()); m_yEntry.SetDouble(translation.Y().value()); } @@ -115,7 +115,7 @@ If your feedforwards are bad then the P controllers for each side of the robot w ```java RamseteController m_disabledRamsete = new RamseteController(); m_disabledRamsete.setEnabled(false); - // Be sure to pass your new disabledRamsete variable + // Be sure to pass your new disabledRamsete variable RamseteCommand ramseteCommand = new RamseteCommand( exampleTrajectory, m_robotDrive::getPose, @@ -127,7 +127,7 @@ If your feedforwards are bad then the P controllers for each side of the robot w ```c++ frc::RamseteController m_disabledRamsete; m_disabledRamsete.SetEnabled(false); - // Be sure to pass your new disabledRamsete variable + // Be sure to pass your new disabledRamsete variable frc2::RamseteCommand ramseteCommand( exampleTrajectory, [this]() { return m_drive.GetPose(); }, @@ -146,7 +146,7 @@ If your feedforwards are bad then the P controllers for each side of the robot w var leftMeasurement = table.getEntry("left_measurement"); var rightReference = table.getEntry("right_reference"); var rightMeasurement = table.getEntry("right_measurement"); - var leftController = new PIDController(kPDriveVel, 0, 0); + var leftController = new PIDController(kPDriveVel, 0, 0); var rightController = new PIDController(kPDriveVel, 0, 0); RamseteCommand ramseteCommand = new RamseteCommand( exampleTrajectory, @@ -160,9 +160,9 @@ If your feedforwards are bad then the P controllers for each side of the robot w // RamseteCommand passes volts to the callback (leftVolts, rightVolts) -> { m_robotDrive.tankDriveVolts(leftVolts, rightVolts); - leftMeasurement.setNumber(m_robotDrive.getWheelSpeeds().leftMetersPerSecond); + leftMeasurement.setNumber(m_robotDrive.getWheelSpeeds().leftMetersPerSecond); leftReference.setNumber(leftController.getSetpoint()); - rightMeasurement.setNumber(m_robotDrive.getWheelSpeeds().rightMetersPerSecond); + rightMeasurement.setNumber(m_robotDrive.getWheelSpeeds().rightMetersPerSecond); rightReference.setNumber(rightController.getSetpoint()); }, m_robotDrive @@ -176,7 +176,7 @@ If your feedforwards are bad then the P controllers for each side of the robot w auto leftMeas = table->GetEntry("left_measurement"); auto rightRef = table->GetEntry("right_reference"); auto rightMeas = table->GetEntry("right_measurement"); - frc::PIDController leftController(DriveConstants::kPDriveVel, 0, 0); + frc::PIDController leftController(DriveConstants::kPDriveVel, 0, 0); frc::PIDController rightController(DriveConstants::kPDriveVel, 0, 0); frc2::RamseteCommand ramseteCommand( exampleTrajectory, [this]() { return m_drive.GetPose(); }, @@ -192,10 +192,10 @@ If your feedforwards are bad then the P controllers for each side of the robot w auto leftMeasurement = leftMeas; auto rightReference = rightRef; auto rightMeasurement = rightMeas; - m_drive.TankDriveVolts(left, right); - leftMeasurement.SetDouble(m_drive.GetWheelSpeeds().left.value()); + m_drive.TankDriveVolts(left, right); + leftMeasurement.SetDouble(m_drive.GetWheelSpeeds().left.value()); leftReference.SetDouble(leftController.GetSetpoint()); - rightMeasurement.SetDouble(m_drive.GetWheelSpeeds().right.value()); + rightMeasurement.SetDouble(m_drive.GetWheelSpeeds().right.value()); rightReference.SetDouble(rightController.GetSetpoint()); }, {&m_drive}); diff --git a/source/docs/software/basic-programming/alliancecolor.rst b/source/docs/software/basic-programming/alliancecolor.rst index 519a628118..87ea884f42 100644 --- a/source/docs/software/basic-programming/alliancecolor.rst +++ b/source/docs/software/basic-programming/alliancecolor.rst @@ -40,7 +40,7 @@ Note that there are three cases: red, blue, and no color yet. It is important t ```Python from wpilib import DriverStation - ally = DriverStation.getAlliance() + ally = DriverStation.getAlliance() if ally is not None: if ally == DriverStation.Alliance.kRed: diff --git a/source/docs/software/basic-programming/coordinate-system.rst b/source/docs/software/basic-programming/coordinate-system.rst index 10495b8f4b..e10316af13 100644 --- a/source/docs/software/basic-programming/coordinate-system.rst +++ b/source/docs/software/basic-programming/coordinate-system.rst @@ -255,10 +255,10 @@ A simple way to deal with field oriented driving is to check the alliance color if (alliance.isPresent() && alliance.get() == Alliance.Red) { invert = -1; } - // Create field relative ChassisSpeeds for controlling Swerve + // Create field relative ChassisSpeeds for controlling Swerve var chassisSpeeds = ChassisSpeeds .fromFieldRelativeSpeeds(xSpeed * invert, ySpeed * invert, zRotation, imu.getRotation2d()); - // Control a mecanum drivetrain + // Control a mecanum drivetrain m_robotDrive.driveCartesian(xSpeed * invert, ySpeed * invert, zRotation, imu.getRotation2d()); ``` @@ -268,10 +268,10 @@ A simple way to deal with field oriented driving is to check the alliance color if (frc::DriverStation::GetAlliance() == frc::DriverStation::Alliance::kRed) { invert = -1; } - // Create field relative ChassisSpeeds for controlling Swerve + // Create field relative ChassisSpeeds for controlling Swerve frc::ChassisSpeeds chassisSpeeds = frc::ChassisSpeeds::FromFieldRelativeSpeeds(xSpeed * invert, ySpeed * invert, zRotation, imu.GetRotation2d()); - // Control a mecanum drivetrain + // Control a mecanum drivetrain m_robotDrive.driveCartesian(xSpeed * invert, ySpeed * invert, zRotation, imu.GetRotation2d()); ``` @@ -280,11 +280,11 @@ A simple way to deal with field oriented driving is to check the alliance color invert = 1 if wpilib.DriverStation.getAlliance() == wpilib.DriverStation.Alliance.kRed: invert = -1 - # Create field relative ChassisSpeeds for controlling Swerve + # Create field relative ChassisSpeeds for controlling Swerve chassis_speeds = wpilib.ChassisSpeeds.FromFieldRelativeSpeeds( xSpeed * invert, ySpeed * invert, zRotation, self.imu.GetAngle() ) - # Control a mecanum drivetrain + # Control a mecanum drivetrain self.robotDrive.driveCartesian(xSpeed * invert, ySpeed * invert, zRotation, self.imu.GetAngle()) ``` diff --git a/source/docs/software/basic-programming/java-units.rst b/source/docs/software/basic-programming/java-units.rst index 7883d3fc50..813d2cd59e 100644 --- a/source/docs/software/basic-programming/java-units.rst +++ b/source/docs/software/basic-programming/java-units.rst @@ -238,7 +238,7 @@ This is because the ``m_lastDistance`` field is a reference to the *same* ``Muta ```java private Measure m_lastDistance; - public Measure calculateDelta(Measure currentDistance) { + public Measure calculateDelta(Measure currentDistance) { if (m_lastDistance == null) { m_lastDistance = currentDistance.copy(); return currentDistance; diff --git a/source/docs/software/basic-programming/joystick.rst b/source/docs/software/basic-programming/joystick.rst index 9a95a7e196..9391316028 100644 --- a/source/docs/software/basic-programming/joystick.rst +++ b/source/docs/software/basic-programming/joystick.rst @@ -114,7 +114,7 @@ An axis can be used with ``.getRawAxis(int index)`` (if not using any of the cla private final PWMSparkMax m_rightMotor = new PWMSparkMax(Constants.kRightMotorPort); private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set); private final GenericHID m_stick = new GenericHID(Constants.kJoystickPort); - m_robotDrive.arcadeDrive(-m_stick.getRawAxis(0), m_stick.getRawAxis(1)); + m_robotDrive.arcadeDrive(-m_stick.getRawAxis(0), m_stick.getRawAxis(1)); ``` ```c++ @@ -123,7 +123,7 @@ An axis can be used with ``.getRawAxis(int index)`` (if not using any of the cla frc::DifferentialDrive m_robotDrive{[&](double output) { m_leftMotor.Set(output); }, [&](double output) { m_rightMotor.Set(output); }}; frc::GenericHID m_stick{Constants::kJoystickPort}; - m_robotDrive.ArcadeDrive(-m_stick.GetRawAxis(0), m_stick.GetRawAxis(1)); + m_robotDrive.ArcadeDrive(-m_stick.GetRawAxis(0), m_stick.GetRawAxis(1)); ``` ```python @@ -131,8 +131,8 @@ An axis can be used with ``.getRawAxis(int index)`` (if not using any of the cla rightMotor = wpilib.PWMVictorSPX(RIGHT_MOTOR_PORT) self.robotDrive = wpilib.drive.DifferentialDrive(leftMotor, rightMotor) self.stick = wpilib.GenericHID(JOYSTICK_PORT) - self.robotDrive.arcadeDrive(-self.stick.getRawAxis(0), self.stick.getRawAxis(1)) - ``` + self.robotDrive.arcadeDrive(-self.stick.getRawAxis(0), self.stick.getRawAxis(1)) + ``` ## Button Usage @@ -149,8 +149,8 @@ Unlike an axis, you will usually want to use the ``pressed`` and ``released`` me if (joystick.getRawButtonReleased(0)) { turnIntakeOff(); // When released the intake turns off } - OR - if (joystick.getRawButton(0)) { + // OR + if (joystick.getRawButton(0)) { turnIntakeOn(); } else { turnIntakeOff(); @@ -164,8 +164,8 @@ Unlike an axis, you will usually want to use the ``pressed`` and ``released`` me if (joystick.GetRawButtonReleased(0)) { turnIntakeOff(); // When released the intake turns off } - OR - if (joystick.GetRawButton(0)) { + // OR + if (joystick.GetRawButton(0)) { turnIntakeOn(); } else { turnIntakeOff(); @@ -175,10 +175,10 @@ Unlike an axis, you will usually want to use the ``pressed`` and ``released`` me ```python if joystick.getRawButtonPressed(0): turnIntakeOn() # When pressed the intake turns on - if joystick.getRawButtonReleased(0): + if joystick.getRawButtonReleased(0): turnIntakeOff() # When released the intake turns off - # OR - if joystick.getRawButton(0): + # OR + if joystick.getRawButton(0): turnIntakeOn() else: turnIntakeOff() @@ -190,7 +190,7 @@ A common request is to toggle something on and off with the press of a button. ```java boolean toggle = false; - if (joystick.getRawButtonPressed(0)) { + if (joystick.getRawButtonPressed(0)) { if (toggle) { // Current state is true so turn off retractIntake(); @@ -205,7 +205,7 @@ A common request is to toggle something on and off with the press of a button. ```c++ bool toggle{false}; - if (joystick.GetRawButtonPressed(0)) { + if (joystick.GetRawButtonPressed(0)) { if (toggle) { // Current state is true so turn off retractIntake(); @@ -220,7 +220,7 @@ A common request is to toggle something on and off with the press of a button. ```python toggle = False - if joystick.getRawButtonPressed(0): + if joystick.getRawButtonPressed(0): if toggle: # current state is True so turn off retractIntake() diff --git a/source/docs/software/basic-programming/reading-stacktraces.rst b/source/docs/software/basic-programming/reading-stacktraces.rst index 9e8fbd3ec3..61109685b0 100644 --- a/source/docs/software/basic-programming/reading-stacktraces.rst +++ b/source/docs/software/basic-programming/reading-stacktraces.rst @@ -160,25 +160,25 @@ For example, consider the following code: ```Java :lineno-start: 19 - PWMSparkMax armMotorCtrl; - @Override + PWMSparkMax armMotorCtrl; + @Override public void robotInit() { - armMotorCtrl.setInverted(true); + armMotorCtrl.setInverted(true); } - ``` + ``` ```C++ :lineno-start: 17 - class Robot : public frc::TimedRobot { - public: - void RobotInit() override { - motorRef->SetInverted(false); - } - private: - frc::PWMVictorSPX m_armMotor{0}; - frc::PWMVictorSPX* motorRef; + class Robot : public frc::TimedRobot { + public: + void RobotInit() override { + motorRef->SetInverted(false); + } + private: + frc::PWMVictorSPX m_armMotor{0}; + frc::PWMVictorSPX* motorRef; }; - ``` + ``` When run, you'll see output that looks like this: @@ -195,11 +195,11 @@ When run, you'll see output that looks like this: at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:373) at edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:463) at frc.robot.Main.main(Main.java:23) - Warning at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:388): The robot program quit unexpectedly. This is usually due to a code error. + Warning at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:388): The robot program quit unexpectedly. This is usually due to a code error. The above stacktrace can help determine where the error occurred. See https://wpilib.org/stacktrace for more information. Error at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:395): The startCompetition() method (or methods called by it) should have handled the exception above. - ``` + ``` Reading the stack trace, you can see that the issue happened inside of the ``robotInit()`` function, on line 23, and the exception involved "Null Pointer". @@ -238,27 +238,27 @@ A functional implementation could look like this: ```Java :lineno-start: 19 - PWMSparkMax armMotorCtrl; - @Override + PWMSparkMax armMotorCtrl; + @Override public void robotInit() { - armMotorCtrl = new PWMSparkMax(0); - armMotorCtrl.setInverted(true); + armMotorCtrl = new PWMSparkMax(0); + armMotorCtrl.setInverted(true); } - ``` + ``` ```C++ :lineno-start: 17 - class Robot : public frc::TimedRobot { - public: - void RobotInit() override { - motorRef = &m_armMotor; - motorRef->SetInverted(false); - } - private: - frc::PWMVictorSPX m_armMotor{0}; - frc::PWMVictorSPX* motorRef; + class Robot : public frc::TimedRobot { + public: + void RobotInit() override { + motorRef = &m_armMotor; + motorRef->SetInverted(false); + } + private: + frc::PWMVictorSPX m_armMotor{0}; + frc::PWMVictorSPX* motorRef; }; - ``` + ``` ### Divide by Zero @@ -271,27 +271,27 @@ For example, consider the following code: ```Java :lineno-start: 18 - int armLengthRatio; + int armLengthRatio; int elbowToWrist_in = 39; int shoulderToElbow_in = 0; //TODO - @Override + @Override public void robotInit() { armLengthRatio = elbowToWrist_in / shoulderToElbow_in; } - ``` + ``` ```C++ :lineno-start: 17 - 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 - }; + 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 + }; ``` When run, you'll see output that looks like this: @@ -309,7 +309,7 @@ When run, you'll see output that looks like this: at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:373) at edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:463) at frc.robot.Main.main(Main.java:23) - Warning at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:388): The robot program quit unexpectedly. This is usually due to a code error. + Warning at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:388): The robot program quit unexpectedly. This is usually due to a code error. The above stacktrace can help determine where the error occurred. See https://wpilib.org/stacktrace for more information. Error at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:395): The startCompetition() method (or methods called by it) should have handled the exception above. @@ -352,27 +352,27 @@ A functional implementation could look like this: ```Java :lineno-start: 18 - int armLengthRatio; + int armLengthRatio; int elbowToWrist_in = 39; int shoulderToElbow_in = 3; - @Override + @Override public void robotInit() { - armLengthRatio = elbowToWrist_in / shoulderToElbow_in; - } - ``` + armLengthRatio = elbowToWrist_in / shoulderToElbow_in; + } + ``` ```C++ :lineno-start: 17 - 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 - }; + 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 + }; ``` 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. @@ -391,28 +391,28 @@ For example, consider the following code: ```Java :lineno-start: 19 - PWMSparkMax leftFrontMotor; + PWMSparkMax leftFrontMotor; PWMSparkMax leftRearMotor; - @Override + @Override public void robotInit() { leftFrontMotor = new PWMSparkMax(0); leftRearMotor = new PWMSparkMax(0); } - ``` + ``` ```C++ :lineno-start: 17 - 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}; - }; - ``` + 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}; + }; + ``` When run, you'll see output that looks like this: @@ -431,7 +431,7 @@ When run, you'll see output that looks like this: at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:373) at edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:463) at frc.robot.Main.main(Main.java:23) - Location of the current allocation: + Location of the current allocation: at edu.wpi.first.hal.PWMJNI.initializePWMPort(Native Method) at edu.wpi.first.wpilibj.PWM.(PWM.java:66) at edu.wpi.first.wpilibj.motorcontrol.PWMMotorController.(PWMMotorController.java:27) @@ -441,7 +441,7 @@ When run, you'll see output that looks like this: at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:373) at edu.wpi.first.wpilibj.RobotBase.startRobot(RobotBase.java:463) at frc.robot.Main.main(Main.java:23) - Warning at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:388): The robot program quit unexpectedly. This is usually due to a code error. + Warning at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:388): The robot program quit unexpectedly. This is usually due to a code error. The above stacktrace can help determine where the error occurred. See https://wpilib.org/stacktrace for more information. Error at edu.wpi.first.wpilibj.RobotBase.runRobot(RobotBase.java:395): The startCompetition() method (or methods called by it) should have handled the exception above. @@ -467,7 +467,7 @@ When run, you'll see output that looks like this: at void frc::impl::RunRobot(wpi::priority_mutex&, Robot**) + 0xa8 [0x13718] at int frc::StartRobot() + 0x3d4 [0x13c9c] at __libc_start_main + 0x114 [0xb57ec580] - Location of the current allocation:: Channel 0 + Location of the current allocation:: Channel 0 at + 0x5fb5c [0xb6e81b5c] at frc::PWM::PWM(int, bool) + 0x334 [0xb6f01e4c] at frc::PWMMotorController::PWMMotorController(std::basic_string_view >, int) + 0x70 [0xb6ef7d50] @@ -475,13 +475,13 @@ When run, you'll see output that looks like this: at void frc::impl::RunRobot(wpi::priority_mutex&, Robot**) + 0xb4 [0x13724] at int frc::StartRobot() + 0x3d4 [0x13c9c] at __libc_start_main + 0x114 [0xb57ec580] - Error at RunRobot: Error: The robot program quit unexpectedly. This is usually due to a code error. + Error at RunRobot: Error: The robot program quit unexpectedly. This is usually due to a code error. The above stacktrace can help determine where the error occurred. See https://wpilib.org/stacktrace for more information. - at void frc::impl::RunRobot(wpi::priority_mutex&, Robot**) + 0x1c8 [0x13838] + at void frc::impl::RunRobot(wpi::priority_mutex&, Robot**) + 0x1c8 [0x13838] at int frc::StartRobot() + 0x3d4 [0x13c9c] at __libc_start_main + 0x114 [0xb57ec580] - terminate called after throwing an instance of 'frc::RuntimeError' + terminate called after throwing an instance of 'frc::RuntimeError' what(): PWM or DIO 0 previously allocated. Location of the previous allocation: at frc::PWM::PWM(int, bool) + 0x50 [0xb6f01b68] @@ -490,8 +490,8 @@ When run, you'll see output that looks like this: at void frc::impl::RunRobot(wpi::priority_mutex&, Robot**) + 0xa8 [0x13718] at int frc::StartRobot() + 0x3d4 [0x13c9c] at __libc_start_main + 0x114 [0xb57ec580] - Location of the current allocation:: Channel 0 - ``` + Location of the current allocation:: Channel 0 + ``` The key thing to notice here is the string, ``PWM or DIO 0 previously allocated.``. That string is your primary clue that something in code has incorrectly "doubled up" on pin 0 usage. @@ -508,27 +508,27 @@ In the example, the left motor controllers are plugged into :term:`PWM` ports `` ```Java :lineno-start: 19 - PWMSparkMax leftFrontMotor; + PWMSparkMax leftFrontMotor; PWMSparkMax leftRearMotor; - @Override + @Override public void robotInit() { - leftFrontMotor = new PWMSparkMax(0); + leftFrontMotor = new PWMSparkMax(0); leftRearMotor = new PWMSparkMax(1); - } - ``` + } + ``` ```C++ :lineno-start: 17 - 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}; - }; + 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}; + }; ``` ### gradlew is not recognized... diff --git a/source/docs/software/can-devices/power-distribution-module.rst b/source/docs/software/can-devices/power-distribution-module.rst index cae385401d..66f6265ac0 100644 --- a/source/docs/software/can-devices/power-distribution-module.rst +++ b/source/docs/software/can-devices/power-distribution-module.rst @@ -22,7 +22,7 @@ To use the either Power Distribution module, create an instance of the :code:`Po ```python from wpilib import PowerDistribution - examplePD = PowerDistribution() + examplePD = PowerDistribution() examplePD = PowerDistribution(0, PowerDistribution.ModuleType.kCTRE) examplePD = PowerDistribution(1, PowerDistribution.ModuleType.kRev) ``` diff --git a/source/docs/software/commandbased/binding-commands-to-triggers.rst b/source/docs/software/commandbased/binding-commands-to-triggers.rst index 69be0a9eb4..cd7a140c13 100644 --- a/source/docs/software/commandbased/binding-commands-to-triggers.rst +++ b/source/docs/software/commandbased/binding-commands-to-triggers.rst @@ -50,12 +50,12 @@ While binding to HID buttons is by far the most common use case, users may want ```java DigitalInput limitSwitch = new DigitalInput(3); // Limit switch on DIO 3 - Trigger exampleTrigger = new Trigger(limitSwitch::get); + Trigger exampleTrigger = new Trigger(limitSwitch::get); ``` ```c++ frc::DigitalInput limitSwitch{3}; // Limit switch on DIO 3 - frc2::Trigger exampleTrigger([&limitSwitch] { return limitSwitch.Get(); }); + frc2::Trigger exampleTrigger([&limitSwitch] { return limitSwitch.Get(); }); ``` ## Trigger Bindings @@ -181,14 +181,14 @@ To avoid rapid repeated activation, triggers (especially those originating from ```java // debounces exampleButton with a 0.1s debounce time, rising edges only exampleButton.debounce(0.1).onTrue(new ExampleCommand()); - // debounces exampleButton with a 0.1s debounce time, both rising and falling edges + // debounces exampleButton with a 0.1s debounce time, both rising and falling edges exampleButton.debounce(0.1, Debouncer.DebounceType.kBoth).onTrue(new ExampleCommand()); ``` ```c++ // debounces exampleButton with a 100ms debounce time, rising edges only exampleButton.Debounce(100_ms).OnTrue(ExampleCommand().ToPtr()); - // debounces exampleButton with a 100ms debounce time, both rising and falling edges + // debounces exampleButton with a 100ms debounce time, both rising and falling edges exampleButton.Debounce(100_ms, Debouncer::DebounceType::Both).OnTrue(ExampleCommand().ToPtr()); ``` diff --git a/source/docs/software/commandbased/command-compositions.rst b/source/docs/software/commandbased/command-compositions.rst index fccbdaa7ab..c222c62710 100644 --- a/source/docs/software/commandbased/command-compositions.rst +++ b/source/docs/software/commandbased/command-compositions.rst @@ -72,7 +72,7 @@ The ``andThen()`` ([Java](https://github.wpilib.org/allwpilib/docs/development/j ```python fooCommand.andThen(barCommand) - ``` + ``` ### Repeating Sequence @@ -91,27 +91,27 @@ There are three types of parallel compositions, differing based on when the comp ```java // Will be a parallel command composition that ends after three seconds with all three commands running their full duration. button.onTrue(Commands.parallel(twoSecCommand, oneSecCommand, threeSecCommand)); - // Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted. + // Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted. button.onTrue(Commands.race(twoSecCommand, oneSecCommand, threeSecCommand)); - // Will be a parallel deadline composition that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished). + // Will be a parallel deadline composition 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)); ``` ```c++ // Will be a parallel command composition 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))); - // Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted. + // Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted. button.OnTrue(frc2::cmd::Race(std::move(twoSecCommand), std::move(oneSecCommand), std::move(threeSecCommand))); - // Will be a parallel deadline composition that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished). + // Will be a parallel deadline composition that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished). button.OnTrue(frc2::cmd::Deadline(std::move(twoSecCommand), std::move(oneSecCommand), std::move(threeSecCommand))); ``` ```python # Will be a parallel command composition that ends after three seconds with all three commands running their full duration. button.onTrue(commands2.cmd.parallel(twoSecCommand, oneSecCommand, threeSecCommand)) - # Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted. + # Will be a parallel race composition that ends after one second with the two and three second commands getting interrupted. button.onTrue(commands2.cmd.race(twoSecCommand, oneSecCommand, threeSecCommand)) - # Will be a parallel deadline composition that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished). + # Will be a parallel deadline composition that ends after two seconds (the deadline) with the three second command getting interrupted (one second command already finished). button.onTrue(commands2.cmd.deadline(twoSecCommand, oneSecCommand, threeSecCommand)) ``` diff --git a/source/docs/software/commandbased/organizing-command-based.rst b/source/docs/software/commandbased/organizing-command-based.rst index 175b1190c3..699022b797 100644 --- a/source/docs/software/commandbased/organizing-command-based.rst +++ b/source/docs/software/commandbased/organizing-command-based.rst @@ -44,9 +44,9 @@ This is sufficient for commands that are only used once. However, for a command ```java // RobotContainer.java intakeButton.whileTrue(Commands.startEnd(() -> intake.set(1.0), () -> intake.set(0), intake)); - Command intakeAndShoot = Commands.startEnd(() -> intake.set(1.0), () -> intake.set(0), intake) + Command intakeAndShoot = Commands.startEnd(() -> intake.set(1.0), () -> intake.set(0), intake) .alongWith(new RunShooter(shooter)); - Command autonomousCommand = Commands.sequence( + Command autonomousCommand = Commands.sequence( Commands.startEnd(() -> intake.set(1.0), () -> intake.set(0.0), intake).withTimeout(5.0), Commands.waitSeconds(3.0), Commands.startEnd(() -> intake.set(1.0), () -> intake.set(0.0), intake).withTimeout(5.0) @@ -55,9 +55,9 @@ This is sufficient for commands that are only used once. However, for a command ```c++ intakeButton.WhileTrue(frc2::cmd::StartEnd([&intake] { intake.Set(1.0); }, [&intake] { intake.Set(0); }, {&intake})); - frc2::CommandPtr intakeAndShoot = frc2::cmd::StartEnd([&intake] { intake.Set(1.0); }, [&intake] { intake.Set(0); }, {&intake}) + frc2::CommandPtr intakeAndShoot = frc2::cmd::StartEnd([&intake] { intake.Set(1.0); }, [&intake] { intake.Set(0); }, {&intake}) .AlongWith(RunShooter(&shooter).ToPtr()); - frc2::CommandPtr autonomousCommand = frc2::cmd::Sequence( + frc2::CommandPtr autonomousCommand = frc2::cmd::Sequence( frc2::cmd::StartEnd([&intake] { intake.Set(1.0); }, [&intake] { intake.Set(0); }, {&intake}).WithTimeout(5.0_s), frc2::cmd::Wait(3.0_s), frc2::cmd::StartEnd([&intake] { intake.Set(1.0); }, [&intake] { intake.Set(0); }, {&intake}).WithTimeout(5.0_s) @@ -78,12 +78,12 @@ For example, a command like the intake-running command is conceptually related t ```java public class Intake extends SubsystemBase { - // [code for motor controllers, configuration, etc.] - // ... - public Command runIntakeCommand() { - // implicitly requires `this` - return this.startEnd(() -> this.set(1.0), () -> this.set(0.0)); - } + // [code for motor controllers, configuration, etc.] + // ... + public Command runIntakeCommand() { + // implicitly requires `this` + return this.startEnd(() -> this.set(1.0), () -> this.set(0.0)); + } } ``` @@ -104,8 +104,8 @@ Using this new factory method in command groups and button bindings is highly ex ```java intakeButton.whileTrue(intake.runIntakeCommand()); - Command intakeAndShoot = intake.runIntakeCommand().alongWith(new RunShooter(shooter)); - Command autonomousCommand = Commands.sequence( + Command intakeAndShoot = intake.runIntakeCommand().alongWith(new RunShooter(shooter)); + Command autonomousCommand = Commands.sequence( intake.runIntakeCommand().withTimeout(5.0), Commands.waitSeconds(3.0), intake.runIntakeCommand().withTimeout(5.0) @@ -114,8 +114,8 @@ Using this new factory method in command groups and button bindings is highly ex ```c++ intakeButton.WhileTrue(intake.RunIntakeCommand()); - frc2::CommandPtr intakeAndShoot = intake.RunIntakeCommand().AlongWith(RunShooter(&shooter).ToPtr()); - frc2::CommandPtr autonomousCommand = frc2::cmd::Sequence( + frc2::CommandPtr intakeAndShoot = intake.RunIntakeCommand().AlongWith(RunShooter(&shooter).ToPtr()); + frc2::CommandPtr autonomousCommand = frc2::cmd::Sequence( intake.RunIntakeCommand().WithTimeout(5.0_s), frc2::cmd::Wait(3.0_s), intake.RunIntakeCommand().WithTimeout(5.0_s) @@ -167,7 +167,7 @@ Instance factory methods work great for single-subsystem commands. However, com ```java public class AutoRoutines { - public static Command driveAndIntake(Drivetrain drivetrain, Intake intake) { + public static Command driveAndIntake(Drivetrain drivetrain, Intake intake) { return Commands.sequence( Commands.parallel( drivetrain.driveCommand(0.5, 0.5), @@ -193,25 +193,25 @@ If we want to avoid the verbosity of adding required subsystems as parameters to ```java public class AutoRoutines { - private Drivetrain drivetrain; - private Intake intake; - public AutoRoutines(Drivetrain drivetrain, Intake intake) { - this.drivetrain = drivetrain; - this.intake = intake; + private Drivetrain drivetrain; + private Intake intake; + public AutoRoutines(Drivetrain drivetrain, Intake intake) { + this.drivetrain = drivetrain; + this.intake = intake; } - public Command driveAndIntake() { + public Command driveAndIntake() { return Commands.sequence( Commands.parallel( drivetrain.driveCommand(0.5, 0.5), intake.runIntakeCommand(1.0) ).withTimeout(5.0), Commands.parallel( - drivetrain.stopCommand(); - intake.stopCommand(); + drivetrain.stopCommand(); + intake.stopCommand(); ) ); } - public Command driveThenIntake() { + public Command driveThenIntake() { return Commands.sequence( drivetrain.driveCommand(0.5, 0.5).withTimeout(5.0), drivetrain.stopCommand(), @@ -232,9 +232,9 @@ Then, elsewhere in our code, we can instantiate an single instance of this class ```java AutoRoutines autoRoutines = new AutoRoutines(this.drivetrain, this.intake); - Command driveAndIntake = autoRoutines.driveAndIntake(); + Command driveAndIntake = autoRoutines.driveAndIntake(); Command driveThenIntake = autoRoutines.driveThenIntake(); - Command drivingAndIntakingSequence = Commands.sequence( + Command drivingAndIntakingSequence = Commands.sequence( autoRoutines.driveAndIntake(), autoRoutines.driveThenIntake() ); @@ -260,7 +260,7 @@ However, it is still possible to ergonomically write a stateful command composit PIDController controller = new PIDController(Constants.kTurnToAngleP, 0, 0); // We can do whatever configuration we want on the created state before returning from the factory controller.setPositionTolerance(Constants.kTurnToAngleTolerance); - // Try to turn at a rate proportional to the heading error until we're at the setpoint, then stop + // Try to turn at a rate proportional to the heading error until we're at the setpoint, then stop return run(() -> arcadeDrive(0,-controller.calculate(gyro.getHeading(), targetDegrees))) .until(controller::atSetpoint) .andThen(runOnce(() -> arcadeDrive(0, 0))); @@ -286,19 +286,19 @@ Returning to our simple intake command from earlier, we could do this by creatin ```java public class RunIntakeCommand extends Command { private Intake m_intake; - public RunIntakeCommand(Intake intake) { + public RunIntakeCommand(Intake intake) { this.m_intake = intake; addRequirements(intake); } - @Override + @Override public void initialize() { m_intake.set(1.0); } - @Override + @Override public void end(boolean interrupted) { m_intake.set(0.0); } - // execute() defaults to do nothing + // execute() defaults to do nothing // isFinished() defaults to return false } ``` diff --git a/source/docs/software/commandbased/subsystems.rst b/source/docs/software/commandbased/subsystems.rst index 61efc033e4..2e602e7bee 100644 --- a/source/docs/software/commandbased/subsystems.rst +++ b/source/docs/software/commandbased/subsystems.rst @@ -36,29 +36,29 @@ The recommended method to create a subsystem for most users is to subclass the a ```python from commands2 import Command from commands2 import Subsystem - class ExampleSubsystem(Subsystem): - def __init__(self): + class ExampleSubsystem(Subsystem): + def __init__(self): """Creates a new ExampleSubsystem.""" super().__init__() - def exampleMethodCommand()->Command: + def exampleMethodCommand()->Command: """ Example command factory method. - :return a command + :return a command """ - return self.runOnce( + return self.runOnce( lambda: # one-time action goes here # ) - def exampleCondition(self)->bool: + def exampleCondition(self)->bool: """ An example method querying a boolean state of the subsystem (for example, a digital sensor). - :return value of some boolean subsystem state, such as a digital sensor. + :return value of some boolean subsystem state, such as a digital sensor. """ - #Query some boolean state, such as a digital sensor. + #Query some boolean state, such as a digital sensor. return False - def periodic(self): + def periodic(self): # This method will be called once per scheduler run pass - def simulationPeriodic(self): + def simulationPeriodic(self): # This method will be called once per scheduler run during simulation pass ``` diff --git a/source/docs/software/convenience-features/scheduling-functions.rst b/source/docs/software/convenience-features/scheduling-functions.rst index 9acb9d37e0..3fbfd53644 100644 --- a/source/docs/software/convenience-features/scheduling-functions.rst +++ b/source/docs/software/convenience-features/scheduling-functions.rst @@ -16,12 +16,12 @@ The ``addPeriodic()`` (Java) / ``AddPeriodic()`` (C++) method takes in a lambda private Encoder m_encoder = new Encoder(1, 2); private Spark m_motor = new Spark(1); private PIDController m_controller = new PIDController(1.0, 0.0, 0.5, 0.01); - public Robot() { + public Robot() { addPeriodic(() -> { m_motor.set(m_controller.calculate(m_encoder.getRate())); }, 0.01, 0.005); } - @Override + @Override public teleopPeriodic() { if (m_joystick.getRawButtonPressed(1)) { if (m_controller.getSetpoint() == 0.0) { @@ -31,7 +31,7 @@ The ``addPeriodic()`` (Java) / ``AddPeriodic()`` (C++) method takes in a lambda } } } - } + } ``` .. tab-item:: C++ (Header) @@ -44,8 +44,8 @@ The ``addPeriodic()`` (Java) / ``AddPeriodic()`` (C++) method takes in a lambda frc::Encoder m_encoder{1, 2}; frc::Spark m_motor{1}; frc::PIDController m_controller{1.0, 0.0, 0.5, 10_ms}; - Robot(); - void TeleopPeriodic() override; + Robot(); + void TeleopPeriodic() override; }; ``` @@ -58,7 +58,7 @@ The ``addPeriodic()`` (Java) / ``AddPeriodic()`` (C++) method takes in a lambda m_motor.Set(m_controller.Calculate(m_encoder.GetRate())); }, 10_ms, 5_ms); } - void Robot::TeleopPeriodic() { + void Robot::TeleopPeriodic() { if (m_joystick.GetRawButtonPressed(1)) { if (m_controller.GetSetpoint() == 0.0) { m_controller.SetSetpoint(30.0); diff --git a/source/docs/software/dashboards/glass/command-based-widgets.rst b/source/docs/software/dashboards/glass/command-based-widgets.rst index 543b7bd6ed..c1ecfcd5cb 100644 --- a/source/docs/software/dashboards/glass/command-based-widgets.rst +++ b/source/docs/software/dashboards/glass/command-based-widgets.rst @@ -14,14 +14,14 @@ The :guilabel:`Command Selector` widget allows you to start and cancel a specif ```c++ #include - ... - MyCommand command{...}; + ... + MyCommand command{...}; frc::SmartDashboard::PutData("My Command", &command); ``` ```python from wpilib import SmartDashboard - command = MyCommand(...) + command = MyCommand(...) SmartDashboard.putData("My Command", command) ``` diff --git a/source/docs/software/dashboards/glass/field2d-widget.rst b/source/docs/software/dashboards/glass/field2d-widget.rst index e676c75fee..7c0b709fbb 100644 --- a/source/docs/software/dashboards/glass/field2d-widget.rst +++ b/source/docs/software/dashboards/glass/field2d-widget.rst @@ -9,28 +9,28 @@ To send your robot's position (usually obtained by :ref:`odometry #include - frc::Field2d m_field; - // Do this in either robot or subsystem init + frc::Field2d m_field; + // Do this in either robot or subsystem init frc::SmartDashboard::PutData("Field", &m_field); - // Do this in either robot periodic or subsystem periodic + // Do this in either robot periodic or subsystem periodic m_field.SetRobotPose(m_odometry.GetPose()); ``` ```python from wpilib import SmartDashboard, Field2d - self.field = Field2d() - # Do this in either robot or subsystem init + self.field = Field2d() + # Do this in either robot or subsystem init SmartDashboard.putData("Field", self.field) - # Do this in either robot periodic or subsystem periodic + # Do this in either robot periodic or subsystem periodic self.field.setRobotPose(self.odometry.getPose()) ``` diff --git a/source/docs/software/dashboards/glass/widgets.rst b/source/docs/software/dashboards/glass/widgets.rst index 9cb331b620..fd1dc84433 100644 --- a/source/docs/software/dashboards/glass/widgets.rst +++ b/source/docs/software/dashboards/glass/widgets.rst @@ -39,7 +39,7 @@ The :guilabel:`Sendable Chooser` widget represents a ``SendableChooser`` instanc ```python from wpilib import SmartDashboard - SmartDashboard.putData("Auto Selector", selector) + SmartDashboard.putData("Auto Selector", selector) ``` .. note:: For more information on creating a ``SendableChooser``, please see :ref:`this document `. @@ -63,7 +63,7 @@ The :guilabel:`PID Controller` widget allows you to quickly tune PID values for ```python from wpilib import SmartDashboard - SmartDashboard.putData("Elevator PID Controller", elevatorPIDController) + SmartDashboard.putData("Elevator PID Controller", elevatorPIDController) ``` This allows you to quickly tune P, I, and D values for various setpoints. 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 ee1bb342dc..36eaf71ef2 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 @@ -66,7 +66,7 @@ Sending to the "Gyro" NetworkTables entry will populate the gyro here. ```python from wpilib import SmartDashboard - SmartDashboard.putNumber("Gyro", self.drivetrain.getHeading()) + SmartDashboard.putNumber("Gyro", self.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. @@ -83,7 +83,7 @@ There are four outputs that show the motor power to the drivetrain. This is con ```python from wpilib import SmartDashboard - SmartDashboard.putNumberArray("RobotDrive Motors", [self.drivetrain.getLeftFront(), self.drivetrain.getRightFront(), self.drivetrain.getLeftBack(), self.drivetrain.getRightBack()]) + SmartDashboard.putNumberArray("RobotDrive Motors", [self.drivetrain.getLeftFront(), self.drivetrain.getRightFront(), self.drivetrain.getLeftBack(), self.drivetrain.getRightBack()]) ``` ## Basic Tab @@ -110,7 +110,7 @@ The strings are labeled top-to-bottom, left-to-right from "DB/String 0" to "DB/S ```python from wpilib import SmartDashboard - SmartDashboard.putString("DB/String 0", "My 21 Char TestString") + SmartDashboard.putString("DB/String 0", "My 21 Char TestString") ``` To read string data entered on the Dashboard: @@ -127,7 +127,7 @@ To read string data entered on the Dashboard: ```python from wpilib import SmartDashboard - dashData = SmartDashboard.getString("DB/String 0", "myDefaultData") + dashData = SmartDashboard.getString("DB/String 0", "myDefaultData") ``` ### Buttons and LEDs @@ -148,7 +148,7 @@ The Buttons and LEDs are boolean values and are labeled top-to-bottom from "DB/B ```python from wpilib import SmartDashboard - SmartDashboard.putBoolean("DB/Button 0", true) + SmartDashboard.putBoolean("DB/Button 0", true) ``` To read from the Buttons: (default value is false) @@ -165,7 +165,7 @@ To read from the Buttons: (default value is false) ```python from wpilib import SmartDashboard - buttonValue = SmartDashboard.getBoolean("DB/Button 0", false) + buttonValue = SmartDashboard.getBoolean("DB/Button 0", false) ``` ### Sliders @@ -186,7 +186,7 @@ The Sliders are bi-directional analog (double) controls/indicators with a range ```python from wpilib import SmartDashboard - SmartDashboard.putNumber("DB/Slider 0", 2.58) + SmartDashboard.putNumber("DB/Slider 0", 2.58) ``` To read values from the Dashboard into the robot program: (default value of 0.0) @@ -203,6 +203,6 @@ To read values from the Dashboard into the robot program: (default value of 0.0) ```python from wpilib import SmartDashboard - dashData = SmartDashboard.getNumber("DB/Slider 0", 0.0) + dashData = 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 369db19261..2786243911 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 @@ -18,7 +18,7 @@ To see the status of a subsystem while the robot is operating in either autonomo ```python from wpilib import SmartDashboard - SmartDashboard.putData(subsystem-reference) + SmartDashboard.putData(subsystem-reference) ``` Shuffleboard will display the subsystem name, the default command associated with this subsystem, and the currently running command. In this example the default command for the Elevator subsystem is called ``AutonomousCommand`` and it is also the current command that is using the Elevator subsystem. @@ -55,7 +55,7 @@ Using commands and subsystems makes very modular robot programs that can easily ```python from wpilib import SmartDashboard - SmartDashboard.putData("ElevatorMove: up", ElevatorMove(2.7)) + SmartDashboard.putData("ElevatorMove: up", ElevatorMove(2.7)) ``` Shuffleboard will display the command name and a button to execute the command. In this way individual commands and command groups can easily be tested without needing special test code in a robot program. In the image below there are a number of commands contained in a Shuffleboard list. Pressing the button once runs the command and pressing it again stops the command. To use this feature the robot must be enabled in teleop mode. 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 fb4f15509e..a4d0e44922 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 @@ -40,9 +40,9 @@ The following example demonstrates how to create a button on your dashboard that ```java ShuffleboardTab tab = Shuffleboard.getTab("Shooter"); GenericEntry shooterEnable = tab.add("Shooter Enable", false).getEntry(); - // Command Example assumed to be in a PIDSubsystem + // Command Example assumed to be in a PIDSubsystem new NetworkButton(shooterEnable).onTrue(new InstantCommand(m_shooter::enable)); - // Timed Robot Example + // Timed Robot Example if (shooterEnable.getBoolean()) { // Calculates the output of the PID algorithm based on the sensor reading // and sends it to a motor @@ -53,9 +53,9 @@ The following example demonstrates how to create a button on your dashboard that ```c++ frc::ShuffleboardTab& tab = frc::Shuffleboard::GetTab("Shooter"); nt::GenericEntry& shooterEnable = *tab.Add("Shooter Enable", false).GetEntry(); - // Command-based assumed to be in a PIDSubsystem + // Command-based assumed to be in a PIDSubsystem frc2::NetworkButton(shooterEnable).OnTrue(frc2::InstantCommand([&] { m_shooter.Enable(); })); - // Timed Robot Example + // Timed Robot Example if (shooterEnable.GetBoolean()) { // Calculates the output of the PID algorithm based on the sensor reading // and sends it to a motor @@ -65,11 +65,11 @@ The following example demonstrates how to create a button on your dashboard that ```python from wpilib.shuffleboard import Shuffleboard - tab = Shuffleboard.getTab("Shooter") + tab = Shuffleboard.getTab("Shooter") shooterEnable = tab.add("Shooter Enable", false).getEntry() - # Command Example assumed to be in a PIDSubsystem + # Command Example assumed to be in a PIDSubsystem NetworkButton(shooterEnable).onTrue(InstantCommand(m_shooter.enable())) - # Timed Robot Example + # Timed Robot Example if (shooterEnable.getBoolean()): # Calculates the output of the PID algorithm based on the sensor reading # and sends it to a motor 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 7206c6d6b2..f204cfd5a6 100644 --- a/source/docs/software/dashboards/shuffleboard/custom-widgets/creating-plugins.rst +++ b/source/docs/software/dashboards/shuffleboard/custom-widgets/creating-plugins.rst @@ -19,9 +19,9 @@ In order to define a plugin, the plugin class must be a subclass of [edu.wpi.fir ```java import edu.wpi.first.shuffleboard.api.plugin.Description; import edu.wpi.first.shuffleboard.api.plugin.Plugin; - @Description(group = "com.example", name = "MyPlugin", version = "1.2.3", summary = "An example plugin") + @Description(group = "com.example", name = "MyPlugin", version = "1.2.3", summary = "An example plugin") public class MyPlugin extends Plugin { - } + } ``` Additional explanations on how these attributes are used, including version numbers can be found [here](https://semver.org/). 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 a38d1422f9..a555a1df5a 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 @@ -37,7 +37,7 @@ Often debugging or monitoring the status of a robot involves writing a number of ```python from wpilib import SmartDashboard - SmartDashboard.putBoolean("Bridge Limit", bridgeTipper.atBridge()) + SmartDashboard.putBoolean("Bridge Limit", bridgeTipper.atBridge()) SmartDashboard.putNumber("Bridge Angle", bridgeTipper.getPosition()) SmartDashboard.putNumber("Swerve Angle", drivetrain.getSwerveAngle()) SmartDashboard.putNumber("Left Drive Encoder", drivetrain.getLeftEncoder()) 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 24db4a77e9..894301312d 100644 --- a/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-tour.rst +++ b/source/docs/software/dashboards/shuffleboard/getting-started/shuffleboard-tour.rst @@ -50,7 +50,7 @@ The easiest way to get data displayed on the dashboard is simply to use methods ```python from wpilib import SmartDashboard - SmartDashboard.putNumber("Joystick X value", joystick1.getX()) + SmartDashboard.putNumber("Joystick X value", joystick1.getX()) ``` to see a field displayed with the label "Joystick X value" and a value of the X value of the joystick. Each time this line of code is executed, a new joystick value will be sent to Shuffleboard. Remember: you must write the joystick value whenever you want to see an updated value. Executing this line once at the start of the program will only display the value once at the time the line of code was executed. 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 05efed4fff..9cb86e277a 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 @@ -25,7 +25,7 @@ Call ``withWidget`` after ``add`` in the call chain: ```python from wpilib.shuffleboard import Shuffleboard from wpilib.shuffleboard import BuiltInWidgets - (Shuffleboard.getTab("Drive") + (Shuffleboard.getTab("Drive") .add("Max Speed", 1) .withWidget(BuiltInWidgets.kNumberSlider) # specify the widget here .getEntry()) @@ -63,7 +63,7 @@ Since the maximum speed only makes sense to be a value from 0 to 1 (full stop to ```python from wpilib.shuffleboard import Shuffleboard from wpilib.shuffleboard import BuiltInWidgets - (Shuffleboard.getTab("Drive") + (Shuffleboard.getTab("Drive") .add("Max Speed", 1) .withWidget(BuiltInWidgets.kNumberSlider) .withProperties(map("min", 0, "max", 1)) # specify widget properties here 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 a53bf4db8e..d647c96963 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 @@ -26,7 +26,7 @@ Call ``withSize`` and ``withPosition`` to set the size and position of the widge ```python from wpilib.shuffleboard import Shuffleboard - (Shuffleboard.getTab("Pre-round") + (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 @@ -51,20 +51,20 @@ If there are many widgets in a tab with related data, it can be useful to place wpi::StringMap> properties{ std::make_pair("Label position", nt::Value::MakeString("HIDDEN")) }; - frc::ShuffleboardLayout& elevatorCommands = frc::Shuffleboard::GetTab("Commands") + frc::ShuffleboardLayout& elevatorCommands = frc::Shuffleboard::GetTab("Commands") .GetLayout("Elevator", frc::BuiltInLayouts::kList) .WithSize(2, 2) .WithProperties(properties); - ElevatorDownCommand* elevatorDown = new ElevatorDownCommand(); + ElevatorDownCommand* elevatorDown = new ElevatorDownCommand(); ElevatorUpCommand* elevatorUp = new ElevatorUpCommand(); - elevatorCommands.Add("Elevator Down", elevatorDown); + elevatorCommands.Add("Elevator Down", elevatorDown); elevatorCommands.Add("Elevator Up", elevatorUp); ``` ```python from wpilib.shuffleboard import Shuffleboard from wpilib.shuffleboard import BuiltInLayouts - (elevatorCommands = Shuffleboard.getTab("Commands") + (elevatorCommands = Shuffleboard.getTab("Commands") .getLayout("Elevator", BuiltInLayouts.kList) .withSize(2, 2) .withProperties(map("Label position", "HIDDEN"))) # hide labels for commands 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 a452f64c10..47a817694c 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 @@ -9,11 +9,11 @@ Unlike ``SmartDashboard.getNumber`` and friends, retrieving data from Shuffleboa private GenericEntry maxSpeed = tab.add("Max Speed", 1) .getEntry(); - private DifferentialDrive robotDrive = ...; - public void drive(double left, double right) { - // Retrieve the maximum speed from the dashboard - double max = maxSpeed.getDouble(1.0); - robotDrive.tankDrive(left * max, right * max); + private DifferentialDrive robotDrive = ...; + public void drive(double left, double right) { + // Retrieve the maximum speed from the dashboard + double max = maxSpeed.getDouble(1.0); + robotDrive.tankDrive(left * max, right * max); } } ``` @@ -22,13 +22,13 @@ Unlike ``SmartDashboard.getNumber`` and friends, retrieving data from Shuffleboa import commands2 import wpilib.drive from wpilib.shuffleboard import Shuffleboard - class DriveSubsystem(commands2.SubsystemBase): + class DriveSubsystem(commands2.SubsystemBase): def __init__(self) -> None: super().__init__() - tab = Shuffleboard.getTab("Drive") + tab = Shuffleboard.getTab("Drive") self.maxSpeed = tab.add("Max Speed", 1).getEntry() - this.robotDrive = ... - def drive(self, left: float, right: float): + this.robotDrive = ... + def drive(self, left: float, right: float): # Retrieve the maximum speed from the dashboard max = self.maxSpeed.getDouble(1.0) self.robotDrive.tankDrive(left * max, right * max) 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 e6153ded05..bc8092034a 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 @@ -18,7 +18,7 @@ Sending simple data (numbers, strings, booleans, and arrays of these) is done by ```python from wpilib.shuffleboard import Shuffleboard - Shuffleboard.getTab("Tab Title").add("Pi", 3.14) + Shuffleboard.getTab("Tab Title").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 @@ -31,19 +31,19 @@ If data needs to be updated (for example, the output of some calculation done on private GenericEntry distanceEntry = tab.add("Distance to target", 0) .getEntry(); - public void calculate() { - double distance = ...; - distanceEntry.setDouble(distance); + public void calculate() { + double distance = ...; + distanceEntry.setDouble(distance); } } ``` ```python from wpilib.shuffleboard import Shuffleboard - def robotInit(self): + def robotInit(self): tab = Shuffleboard.getTab("Vision") self.distanceEntry = tab.add("Distance to target", 0).getEntry() - def teleopPeriodic(self): + def teleopPeriodic(self): distance = self.encoder.getDistance() self.distanceEntry.setDouble(distance) ``` @@ -70,7 +70,7 @@ Simply using `addPersistent` instead of `add` will make the value saved on the r ```python from wpilib.shuffleboard import Shuffleboard - (Shuffleboard.getTab("Drive") + (Shuffleboard.getTab("Drive") .addPersistent("Max Speed", 1.0)) ``` @@ -92,7 +92,7 @@ Analogous to ``SmartDashboard.putData``, any ``Sendable`` object (most sensors, ```python from wpilib.shuffleboard import Shuffleboard - (Shuffleboard.getTab("Tab Title") + (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 bcc888d074..5935307b6c 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 @@ -16,7 +16,7 @@ Creating a new tab ```python from wpilib.shuffleboard import Shuffleboard - tab = Shuffleboard.getTab("Tab Title") + tab = Shuffleboard.getTab("Tab Title") ``` Creating a new tab is as simple as calling a single method on the Shuffleboard class, which will create a new tab on Shuffleboard and return a handle for adding your data to the tab. Calling getTab multiple times with the same tab title will return the same handle each time. @@ -35,7 +35,7 @@ Creating a new tab is as simple as calling a single method on the Shuffleboard c ```python from wpilib.shuffleboard import Shuffleboard - Shuffleboard.selectTab("Tab Title") + Shuffleboard.selectTab("Tab Title") ``` This method lets a tab be selected by title. This is case-sensitive (so "Tab Title" and "Tab title" are two individual tabs), and only works if a tab with that title exists at the time the method is called, so calling ``selectTab("Example")``\ will only have an effect if a tab named "Example" has previously been defined. 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 8372264025..a2623e2f3a 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 @@ -33,7 +33,7 @@ In ``Robot.java`` / ``Robot.h``, create a variable to hold a reference to a ``Se ```python import wpilib - self.defaultAuto = "Default" + self.defaultAuto = "Default" self.customAuto = "My Auto"; self.chooser = wpilib.SendableChooser() ``` @@ -63,7 +63,7 @@ The chooser allows you to pick from a list of defined elements, in this case the ```python from wpilib import SmartDashboard - self.chooser.setDefaultOption("Default Auto", self.defaultAuto) + self.chooser.setDefaultOption("Default Auto", self.defaultAuto) self.chooser.addOption("My Auto", self.customAuto) SmartDashboard.putData("Auto choices", self.chooser) ``` @@ -95,7 +95,7 @@ Now, in ``autonomousInit`` and ``autonomousPeriodic``, you can use the ``m_autoS def autonomousInit(self): self.autoSelected = self.chooser.getSelected() print("Auto selected: " + self.autoSelected) - def autonomousPeriodic(self): + def autonomousPeriodic(self): match self.autoSelected: case self.customAuto: # Put custom auto code here @@ -202,7 +202,7 @@ Then, publish the chooser to the dashboard: ```python from wpilib import SmartDashboard - # Put the chooser on the dashboard + # Put the chooser on the dashboard SmartDashboard.putData(chooser) ``` diff --git a/source/docs/software/dashboards/smartdashboard/displaying-expressions.rst b/source/docs/software/dashboards/smartdashboard/displaying-expressions.rst index ae86cf5ac0..5c741e7a1f 100644 --- a/source/docs/software/dashboards/smartdashboard/displaying-expressions.rst +++ b/source/docs/software/dashboards/smartdashboard/displaying-expressions.rst @@ -34,7 +34,7 @@ ```python from wpilib import SmartDashboard - SmartDashboard.putBoolean("Bridge Limit", bridgeTipper.atBridge()) + SmartDashboard.putBoolean("Bridge Limit", bridgeTipper.atBridge()) SmartDashboard.putNumber("Bridge Angle", bridgeTipper.getPosition()) SmartDashboard.putNumber("Swerve Angle", drivetrain.getSwerveAngle()) SmartDashboard.putNumber("Left Drive Encoder", drivetrain.getLeftEncoder()) 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 60e73296fa..2c628244e7 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 @@ -31,7 +31,7 @@ In the following examples, you'll see what the screen would look like when there ```python from wpilib import SmartDashboard from commands2 import CommandScheduler - SmartDashboard.putData(CommandScheduler.getInstance()) + SmartDashboard.putData(CommandScheduler.getInstance()) ``` You can display the status of the Scheduler (the code that schedules your commands to run). This is easily done by adding a single line to the ``RobotInit`` method in your RobotProgram as shown here. In this example the Scheduler instance is written using the ``putData`` method to SmartDashboard. This line of code produces the display in the previous image. @@ -55,7 +55,7 @@ This is the scheduler status when there are two commands running, ``ExampleComma ```python from wpilib import SmartDashboard - SmartDashboard.putData(exampleSubsystem) + SmartDashboard.putData(exampleSubsystem) ``` In this example we are writing the command instance, ``exampleSubsystem`` and instance of the ``ExampleSubsystem`` class to the SmartDashboard. This causes the display shown in the previous image. The text field will either contain a few dashes, ``---`` indicating that no command is current using this subsystem, or the name of the command currently using this subsystem. @@ -79,7 +79,7 @@ Running commands will "require" subsystems. That is the command is reserving the ```python from wpilib import SmartDashboard - SmartDashboard.putData("Autonomous Command", exampleCommand) + SmartDashboard.putData("Autonomous Command", exampleCommand) ``` This is the code required to create a button for the command on SmartDashboard. Pressing the button will schedule the command. While the command is running, the button label changes from ``start`` to ``cancel`` and pressing the button will cancel the command. 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 87a260f76c..4ece393c33 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 @@ -11,18 +11,18 @@ For each sensor or actuator that is created, set the subsystem name and display ```java Ultrasonic ultrasonic = new Ultrasonic(1, 2); SendableRegistry.setName(ultrasonic, "Arm", "Ultrasonic"); - Jaguar elbow = new Jaguar(1); + Jaguar elbow = new Jaguar(1); SendableRegistry.setName(elbow, "Arm", "Elbow"); - Victor wrist = new Victor(2); + Victor wrist = new Victor(2); SendableRegistry.setName(wrist, "Arm", "Wrist"); ``` ```c++ frc::Ultrasonic ultrasonic{1, 2}; SendableRegistry::SetName(ultrasonic, "Arm", "Ultrasonic"); - frc::Jaguar elbow{1}; + frc::Jaguar elbow{1}; SendableRegistry::SetName(elbow, "Arm", "Elbow"); - frc::Victor wrist{2}; + frc::Victor wrist{2}; SendableRegistry::SetName(wrist, "Arm", "Wrist"); ``` @@ -31,9 +31,9 @@ For each sensor or actuator that is created, set the subsystem name and display from wpiutil import SendableRegistry ultrasonic = Ultrasonic(1, 2) SendableRegistry.setName(ultrasonic, "Arm", "Ultrasonic") - elbow = Jaguar(1) + elbow = Jaguar(1) SendableRegistry.setName(elbow, "Arm", "Elbow") - wrist = Victor(2) + wrist = Victor(2) SendableRegistry.setName(wrist, "Arm", "Wrist") ``` @@ -44,18 +44,18 @@ If your objects are in a ``Subsystem``, this can be simplified using the addChil ```java Ultrasonic ultrasonic = new Ultrasonic(1, 2); addChild("Ultrasonic", ultrasonic); - Jaguar elbow = new Jaguar(1); + Jaguar elbow = new Jaguar(1); addChild("Elbow", elbow); - Victor wrist = new Victor(2); + Victor wrist = new Victor(2); addChild("Wrist", wrist); ``` ```c++ frc::Ultrasonic ultrasonic{1, 2}; AddChild("Ultrasonic", ultrasonic); - frc::Jaguar elbow{1}; + frc::Jaguar elbow{1}; AddChild("Elbow", elbow); - frc::Victor wrist{2}; + frc::Victor wrist{2}; AddChild("Wrist", wrist); ``` @@ -64,9 +64,9 @@ If your objects are in a ``Subsystem``, this can be simplified using the addChil from commands2 import SubsystemBase ultrasonic = Ultrasonic(1, 2) SubsystemBase.addChild("Ultrasonic", ultrasonic) - elbow = Jaguar(1) + elbow = Jaguar(1) SubsystemBase.addChild("Elbow", elbow) - wrist = Victor(2) + wrist = Victor(2) SubsystemBase.addChild("Wrist", wrist) ``` 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 914b75c395..6477f9ae46 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 @@ -38,7 +38,7 @@ To run LiveWindow in Test Mode, the following code is needed in the ``Robot`` cl PWMSparkMax rightDrive; PWMVictorSPX arm; BuiltInAccelerometer accel; - @Override + @Override public void robotInit() { leftDrive = new PWMSparkMax(0); rightDrive = new PWMSparkMax(1); @@ -54,7 +54,7 @@ To run LiveWindow in Test Mode, the following code is needed in the ``Robot`` cl frc::PWMSparkMax rigthDrive{1}; frc::BuiltInAccelerometer accel{}; frc::PWMVictorSPX arm{3}; - void Robot::RobotInit() { + void Robot::RobotInit() { wpi::SendableRegistry::SetName(&arm, "SomeSubsystem", "Arm"); wpi::SendableRegistry::SetName(&accel, "SomeSubsystem", "Accelerometer"); } @@ -63,7 +63,7 @@ To run LiveWindow in Test Mode, the following code is needed in the ``Robot`` cl ```python from wpilib import BuiltInAccelerometer, PWMSparkMax, PWMVictorSPX from wpiutil import SendableRegistry - def robotInit(self) -> None: + def robotInit(self) -> None: leftDrive = PWMSparkMax(0) rightDrive = PWMSparkMax(1) arm = PWMVictorSPX(2) 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 70fca25851..eee94956a5 100644 --- a/source/docs/software/dashboards/smartdashboard/verifying-smartdashboard-is-working.rst +++ b/source/docs/software/dashboards/smartdashboard/verifying-smartdashboard-is-working.rst @@ -23,7 +23,7 @@ SmartDashboard includes a connection indicator widget which will turn red or gre ```java public class Robot extends TimedRobot { double counter = 0.0; - public void teleopPeriodic() { + public void teleopPeriodic() { SmartDashboard.putNumber("Counter", counter++); } } @@ -32,15 +32,15 @@ SmartDashboard includes a connection indicator widget which will turn red or gre ```c++ #include "Robot.h" float counter = 0.0; - void Robot::TeleopPeriodic() { + void Robot::TeleopPeriodic() { frc::SmartDashboard::PutNumber("Counter", counter++); } ``` ```python from wpilib import SmartDashboard - self.counter = 0.0 - def teleopPeriodic(self) -> None: + self.counter = 0.0 + def teleopPeriodic(self) -> None: SmartDashboard.putNumber("Counter", self.counter += 1) ``` diff --git a/source/docs/software/hardware-apis/misc/addressable-leds.rst b/source/docs/software/hardware-apis/misc/addressable-leds.rst index f5628bd09c..d6a5686f36 100644 --- a/source/docs/software/hardware-apis/misc/addressable-leds.rst +++ b/source/docs/software/hardware-apis/misc/addressable-leds.rst @@ -60,7 +60,7 @@ RGB stands for Red, Green, and Blue. This is a fairly common color model as it's // Sets the specified LED to the RGB values for red m_ledBuffer.setRGB(i, 255, 0, 0); } - m_led.setData(m_ledBuffer); + m_led.setData(m_ledBuffer); ``` .. tab-item:: C++ @@ -70,7 +70,7 @@ RGB stands for Red, Green, and Blue. This is a fairly common color model as it's for (int i = 0; i < kLength; i++) { m_ledBuffer[i].SetRGB(255, 0, 0); } - m_led.SetData(m_ledBuffer); + m_led.SetData(m_ledBuffer); ``` ### Using HSV Values @@ -92,7 +92,7 @@ LEDs can be set with the ``setHSV`` method that takes 4 arguments: index of the // Sets the specified LED to the HSV values for red m_ledBuffer.setHSV(i, 0, 100, 100); } - m_led.setData(m_ledBuffer); + m_led.setData(m_ledBuffer); ``` .. tab-item:: C++ @@ -102,7 +102,7 @@ LEDs can be set with the ``setHSV`` method that takes 4 arguments: index of the for (int i = 0; i < kLength; i++) { m_ledBuffer[i].SetHSV(0, 100, 100); } - m_led.SetData(m_ledBuffer); + m_led.SetData(m_ledBuffer); ``` ## Creating a Rainbow Effect 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 bc8d1b6e08..0c96ba54bd 100644 --- a/source/docs/software/hardware-apis/motors/using-motor-controllers.rst +++ b/source/docs/software/hardware-apis/motors/using-motor-controllers.rst @@ -12,24 +12,24 @@ PWM motor controllers can be controlled in the same way as a CAN motor controlle ```java Spark spark = new Spark(0); // 0 is the RIO PWM port this is connected to - spark.set(-0.75); // the % output of the motor, between -1 and 1 - VictorSP victor = new VictorSP(0); // 0 is the RIO PWM port this is connected to - victor.set(0.6); // the % output of the motor, between -1 and 1 + spark.set(-0.75); // the % output of the motor, between -1 and 1 + VictorSP victor = new VictorSP(0); // 0 is the RIO PWM port this is connected to + victor.set(0.6); // the % output of the motor, between -1 and 1 ``` ```c++ frc::Spark spark{0}; // 0 is the RIO PWM port this is connected to - spark.Set(-0.75); // the % output of the motor, between -1 and 1 - frc::VictorSP victor{0}; // 0 is the RIO PWM port this is connected to - victor.Set(0.6); // the % output of the motor, between -1 and 1 + spark.Set(-0.75); // the % output of the motor, between -1 and 1 + frc::VictorSP victor{0}; // 0 is the RIO PWM port this is connected to + victor.Set(0.6); // the % output of the motor, between -1 and 1 ``` ```python spark = wpilib.Spark(0) # 0 is the RIO PWM port this is connected to - spark.set(-0.75) # the % output of the motor, between -1 and 1 - victor = wpilib.VictorSP(0) # 0 is the RIO PWM port this is connected to - victor.set(0.6) # the % output of the motor, between -1 and 1 - ``` + spark.set(-0.75) # the % output of the motor, between -1 and 1 + victor = wpilib.VictorSP(0) # 0 is the RIO PWM port this is connected to + victor.set(0.6) # the % output of the motor, between -1 and 1 + ``` ## CAN Motor Controllers 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 936ca8938c..208fb3bbc8 100644 --- a/source/docs/software/hardware-apis/motors/wpi-drive-classes.rst +++ b/source/docs/software/hardware-apis/motors/wpi-drive-classes.rst @@ -32,7 +32,7 @@ It is the responsibility of the user to manage proper inversions for their drive ```java PWMSparkMax m_motorRight = new PWMSparkMax(0); - @Override + @Override public void robotInit() { m_motorRight.setInverted(true); } @@ -40,7 +40,7 @@ It is the responsibility of the user to manage proper inversions for their drive ```c++ frc::PWMSparkMax m_motorLeft{0}; - public: + public: void RobotInit() override { m_motorRight.SetInverted(true); } @@ -192,11 +192,11 @@ Many FRC\ |reg| drivetrains have more than 1 motor on each side. Classes derived rearLeft = wpilib.Spark(2) left = wpilib.MotorControllerGroup(frontLeft, rearLeft) left.setInverted(True) # if you want to invert the entire side you can do so here - frontRight = wpilib.Spark(3) + frontRight = wpilib.Spark(3) rearRight = wpilib.Spark(4) right = wpilib.MotorControllerGroup(frontLeft, rearLeft) - self.drive = wpilib.drive.DifferentialDrive(left, right) - ``` + self.drive = wpilib.drive.DifferentialDrive(left, right) + ``` ### Drive Modes .. note:: @@ -220,9 +220,9 @@ Like Arcade Drive, the Curvature Drive mode is used to control the drivetrain us public void teleopPeriodic() { // Tank drive with a given left and right rates myDrive.tankDrive(-leftStick.getY(), -rightStick.getY()); - // Arcade drive with a given forward and turn rate + // Arcade drive with a given forward and turn rate myDrive.arcadeDrive(-driveStick.getY(), -driveStick.getX()); - // Curvature drive with a given forward and turn rate, as well as a button for turning in-place. + // Curvature drive with a given forward and turn rate, as well as a button for turning in-place. myDrive.curvatureDrive(-driveStick.getY(), -driveStick.getX(), driveStick.getButton(1)); } ``` @@ -231,9 +231,9 @@ Like Arcade Drive, the Curvature Drive mode is used to control the drivetrain us void TeleopPeriodic() override { // Tank drive with a given left and right rates myDrive.TankDrive(-leftStick.GetY(), -rightStick.GetY()); - // Arcade drive with a given forward and turn rate + // Arcade drive with a given forward and turn rate myDrive.ArcadeDrive(-driveStick.GetY(), -driveStick.GetX()); - // Curvature drive with a given forward and turn rate, as well as a quick-turn button + // Curvature drive with a given forward and turn rate, as well as a quick-turn button myDrive.CurvatureDrive(-driveStick.GetY(), -driveStick.GetX(), driveStick.GetButton(1)); } ``` @@ -242,9 +242,9 @@ Like Arcade Drive, the Curvature Drive mode is used to control the drivetrain us def teleopPeriodic(self): # Tank drive with a given left and right rates self.myDrive.tankDrive(-self.leftStick.getY(), -self.rightStick.getY()) - # Arcade drive with a given forward and turn rate + # Arcade drive with a given forward and turn rate self.myDrive.arcadeDrive(-self.driveStick.getY(), -self.driveStick.getX()) - # Curvature drive with a given forward and turn rate, as well as a button for turning in-place. + # Curvature drive with a given forward and turn rate, as well as a button for turning in-place. self.myDrive.curvatureDrive(-self.driveStick.getY(), -self.driveStick.getX(), self.driveStick.getButton(1)) ``` diff --git a/source/docs/software/hardware-apis/pneumatics/solenoids.rst b/source/docs/software/hardware-apis/pneumatics/solenoids.rst index 5b44c69642..1efca2b8d6 100644 --- a/source/docs/software/hardware-apis/pneumatics/solenoids.rst +++ b/source/docs/software/hardware-apis/pneumatics/solenoids.rst @@ -95,9 +95,9 @@ Solenoids can be switched from one output to the other (known as toggling) by us ```java Solenoid exampleSingle = new Solenoid(PneumaticsModuleType.CTREPCM, 0); DoubleSolenoid exampleDouble = new DoubleSolenoid(PneumaticsModuleType.CTREPCM, 1, 2); - // Initialize the DoubleSolenoid so it knows where to start. Not required for single solenoids. + // Initialize the DoubleSolenoid so it knows where to start. Not required for single solenoids. exampleDouble.set(kReverse); - if (m_controller.getYButtonPressed()) { + if (m_controller.getYButtonPressed()) { exampleSingle.toggle(); exampleDouble.toggle(); } @@ -106,9 +106,9 @@ Solenoids can be switched from one output to the other (known as toggling) by us ```c++ frc::Solenoid exampleSingle{frc::PneumaticsModuleType::CTREPCM, 0}; frc::DoubleSolenoid exampleDouble{frc::PneumaticsModuleType::CTREPCM, 1, 2}; - // Initialize the DoubleSolenoid so it knows where to start. Not required for single solenoids. + // Initialize the DoubleSolenoid so it knows where to start. Not required for single solenoids. exampleDouble.Set(frc::DoubleSolenoid::Value::kReverse); - if (m_controller.GetYButtonPressed()) { + if (m_controller.GetYButtonPressed()) { exampleSingle.Toggle(); exampleDouble.Toggle(); } diff --git a/source/docs/software/hardware-apis/sensors/accelerometers-software.rst b/source/docs/software/hardware-apis/sensors/accelerometers-software.rst index 9dfc0aab00..3d6c3885f2 100644 --- a/source/docs/software/hardware-apis/sensors/accelerometers-software.rst +++ b/source/docs/software/hardware-apis/sensors/accelerometers-software.rst @@ -26,22 +26,22 @@ The :code:`AnalogAccelerometer` class ([Java](https://github.wpilib.org/allwpili ```java // Creates an analog accelerometer on analog input 0 AnalogAccelerometer accelerometer = new AnalogAccelerometer(0); - // Sets the sensitivity of the accelerometer to 1 volt per G + // Sets the sensitivity of the accelerometer to 1 volt per G accelerometer.setSensitivity(1); - // Sets the zero voltage of the accelerometer to 3 volts + // Sets the zero voltage of the accelerometer to 3 volts accelerometer.setZero(3); - // Gets the current acceleration + // Gets the current acceleration double accel = accelerometer.getAcceleration(); ``` ```c++ // Creates an analog accelerometer on analog input 0 frc::AnalogAccelerometer accelerometer{0}; - // Sets the sensitivity of the accelerometer to 1 volt per G + // Sets the sensitivity of the accelerometer to 1 volt per G accelerometer.SetSensitivity(1); - // Sets the zero voltage of the accelerometer to 3 volts + // Sets the zero voltage of the accelerometer to 3 volts accelerometer.SetZero(3); - // Gets the current acceleration + // Gets the current acceleration double accel = accelerometer.GetAcceleration(); ``` @@ -150,17 +150,17 @@ For detecting collisions, it is often more robust to measure the jerk than the a ```java double prevXAccel = 0.0; double prevYAccel = 0.0; - BuiltInAccelerometer accelerometer = new BuiltInAccelerometer(); - @Override + BuiltInAccelerometer accelerometer = new BuiltInAccelerometer(); + @Override public void robotPeriodic() { // Gets the current accelerations in the X and Y directions double xAccel = accelerometer.getX(); double yAccel = accelerometer.getY(); - // Calculates the jerk in the X and Y directions + // Calculates the jerk in the X and Y directions // Divides by .02 because default loop timing is 20ms double xJerk = (xAccel - prevXAccel) / 0.02; double yJerk = (yAccel - prevYAccel) / 0.02; - prevXAccel = xAccel; + prevXAccel = xAccel; prevYAccel = yAccel; } ``` @@ -168,16 +168,16 @@ For detecting collisions, it is often more robust to measure the jerk than the a ```c++ double prevXAccel = 0.0; double prevYAccel = 0.0; - frc::BuiltInAccelerometer accelerometer; - void Robot::RobotPeriodic() { + frc::BuiltInAccelerometer accelerometer; + void Robot::RobotPeriodic() { // Gets the current accelerations in the X and Y directions double xAccel = accelerometer.GetX(); double yAccel = accelerometer.GetY(); - // Calculates the jerk in the X and Y directions + // Calculates the jerk in the X and Y directions // Divides by .02 because default loop timing is 20ms double xJerk = (xAccel - prevXAccel) / 0.02; double yJerk = (yAccel - prevYAccel) / 0.02; - prevXAccel = xAccel; + prevXAccel = xAccel; prevYAccel = yAccel; } ``` @@ -188,9 +188,9 @@ Most accelerometers legal for FRC use are quite noisy, and it is often a good id ```java BuiltInAccelerometer accelerometer = new BuiltInAccelerometer(); - // Create a LinearFilter that will calculate a moving average of the measured X acceleration over the past 10 iterations of the main loop - LinearFilter xAccelFilter = LinearFilter.movingAverage(10); - @Override + // Create a LinearFilter that will calculate a moving average of the measured X acceleration over the past 10 iterations of the main loop + LinearFilter xAccelFilter = LinearFilter.movingAverage(10); + @Override public void robotPeriodic() { // Get the filtered X acceleration double filteredXAccel = xAccelFilter.calculate(accelerometer.getX()); @@ -199,9 +199,9 @@ Most accelerometers legal for FRC use are quite noisy, and it is often a good id ```c++ frc::BuiltInAccelerometer accelerometer; - // Create a LinearFilter that will calculate a moving average of the measured X acceleration over the past 10 iterations of the main loop + // Create a LinearFilter that will calculate a moving average of the measured X acceleration over the past 10 iterations of the main loop auto xAccelFilter = frc::LinearFilter::MovingAverage(10); - void Robot::RobotPeriodic() { + void Robot::RobotPeriodic() { // Get the filtered X acceleration double filteredXAccel = xAccelFilter.Calculate(accelerometer.GetX()); } 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 59b13ada7c..9b50b4f83f 100644 --- a/source/docs/software/hardware-apis/sensors/analog-inputs-software.rst +++ b/source/docs/software/hardware-apis/sensors/analog-inputs-software.rst @@ -147,14 +147,14 @@ Analog input channels 0 and 1 additionally support an accumulator, which integra // Sets the initial value of the accumulator to 0 // This is the "starting point" from which the value will change over time analog.setAccumulatorInitialValue(0); - // Sets the "center" of the accumulator to 0. This value is subtracted from + // Sets the "center" of the accumulator to 0. This value is subtracted from // all measured values prior to accumulation. analog.setAccumulatorCenter(0); - // Returns the number of accumulated samples since the accumulator was last started/reset + // Returns the number of accumulated samples since the accumulator was last started/reset analog.getAccumulatorCount(); - // Returns the value of the accumulator. Return type is long. + // Returns the value of the accumulator. Return type is long. analog.getAccumulatorValue(); - // Resets the accumulator to the initial value + // Resets the accumulator to the initial value analog.resetAccumulator(); ``` @@ -162,14 +162,14 @@ Analog input channels 0 and 1 additionally support an accumulator, which integra // Sets the initial value of the accumulator to 0 // This is the "starting point" from which the value will change over time analog.SetAccumulatorInitialValue(0); - // Sets the "center" of the accumulator to 0. This value is subtracted from + // Sets the "center" of the accumulator to 0. This value is subtracted from // all measured values prior to accumulation. analog.SetAccumulatorCenter(0); - // Returns the number of accumulated samples since the accumulator was last started/reset + // Returns the number of accumulated samples since the accumulator was last started/reset analog.GetAccumulatorCount(); - // Returns the value of the accumulator. Return type is long. + // Returns the value of the accumulator. Return type is long. analog.GetAccumulatorValue(); - // Resets the accumulator to the initial value + // Resets the accumulator to the initial value analog.ResetAccumulator(); ``` @@ -182,9 +182,9 @@ Sometimes, it is necessarily to obtain matched measurements of the count and the ```java // Instantiate an AccumulatorResult object to hold the matched measurements AccumulatorResult result = new AccumulatorResult(); - // Fill the AccumulatorResult with the matched measurements + // Fill the AccumulatorResult with the matched measurements analog.getAccumulatorOutput(result); - // Read the values from the AccumulatorResult + // Read the values from the AccumulatorResult long count = result.count; long value = result.value; ``` @@ -193,7 +193,7 @@ Sometimes, it is necessarily to obtain matched measurements of the count and the // The count and value variables to fill int_64t count; int_64t value; - // Fill the count and value variables with the matched measurements + // Fill the count and value variables with the matched measurements analog.GetAccumulatorOutput(count, value); ``` 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 7d044e811f..457d90e83e 100644 --- a/source/docs/software/hardware-apis/sensors/analog-potentiometers-software.rst +++ b/source/docs/software/hardware-apis/sensors/analog-potentiometers-software.rst @@ -20,14 +20,14 @@ An AnalogPotentiometer can be initialized as follows: // 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) // The "starting point" of the motion, i.e. where the mechanism is located when the potentiometer reads 0v, is 30. - AnalogPotentiometer pot = new AnalogPotentiometer(0, 180, 30); + AnalogPotentiometer pot = new AnalogPotentiometer(0, 180, 30); ``` ```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) // The "starting point" of the motion, i.e. where the mechanism is located when the potentiometer reads 0v, is 30. - frc::AnalogPotentiometer pot{0, 180, 30}; + frc::AnalogPotentiometer pot{0, 180, 30}; ``` ### Customizing the underlying AnalogInput @@ -42,20 +42,20 @@ If the user would like to apply custom settings to the underlying :code:`AnalogI // Initializes an AnalogInput on port 0, and enables 2-bit averaging AnalogInput input = new AnalogInput(0); input.setAverageBits(2); - // Initializes an AnalogPotentiometer with the given AnalogInput + // Initializes an AnalogPotentiometer with the given AnalogInput // The full range of motion (in meaningful external units) is 0-180 (this could be degrees, for instance) // The "starting point" of the motion, i.e. where the mechanism is located when the potentiometer reads 0v, is 30. - AnalogPotentiometer pot = new AnalogPotentiometer(input, 180, 30); + AnalogPotentiometer pot = new AnalogPotentiometer(input, 180, 30); ``` ```c++ // Initializes an AnalogInput on port 0, and enables 2-bit averaging frc::AnalogInput input{0}; input.SetAverageBits(2); - // Initializes an AnalogPotentiometer with the given AnalogInput + // Initializes an AnalogPotentiometer with the given AnalogInput // The full range of motion (in meaningful external units) is 0-180 (this could be degrees, for instance) // The "starting point" of the motion, i.e. where the mechanism is located when the potentiometer reads 0v, is 30. - frc::AnalogPotentiometer pot{input, 180, 30}; + frc::AnalogPotentiometer pot{input, 180, 30}; ``` ### Reading values from the AnalogPotentiometer diff --git a/source/docs/software/hardware-apis/sensors/counters.rst b/source/docs/software/hardware-apis/sensors/counters.rst index 60e58f7f1b..ae842a1313 100644 --- a/source/docs/software/hardware-apis/sensors/counters.rst +++ b/source/docs/software/hardware-apis/sensors/counters.rst @@ -31,12 +31,12 @@ In two-pulse mode, the :code:`Counter` will count up for every edge/pulse on the ```java // Create a new Counter object in two-pulse mode Counter counter = new Counter(Counter.Mode.k2Pulse); - @Override + @Override public void robotInit() { // Set up the input channels for the counter counter.setUpSource(1); counter.setDownSource(2); - // Set the decoding type to 2X + // Set the decoding type to 2X counter.setUpSourceEdge(true, true); counter.setDownSourceEdge(true, true); } @@ -45,11 +45,11 @@ In two-pulse mode, the :code:`Counter` will count up for every edge/pulse on the ```c++ // Create a new Counter object in two-pulse mode frc::Counter counter{frc::Counter::Mode::k2Pulse}; - void Robot::RobotInit() { + void Robot::RobotInit() { // Set up the input channels for the counter counter.SetUpSource(1); counter.SetDownSource(2); - // Set the decoding type to 2X + // Set the decoding type to 2X counter.SetUpSourceEdge(true, true); counter.SetDownSourceEdge(true, true); ``` @@ -63,11 +63,11 @@ In semi-period mode, the :code:`Counter` will count the duration of the pulses o ```java // Create a new Counter object in two-pulse mode Counter counter = new Counter(Counter.Mode.kSemiperiod); - @Override + @Override public void robotInit() { // Set up the input channel for the counter counter.setUpSource(1); - // Set the encoder to count pulse duration from rising edge to falling edge + // Set the encoder to count pulse duration from rising edge to falling edge counter.setSemiPeriodMode(true); } ``` @@ -75,10 +75,10 @@ In semi-period mode, the :code:`Counter` will count the duration of the pulses o ```c++ // Create a new Counter object in two-pulse mode frc::Counter counter{frc::Counter::Mode::kSemiperiod}; - void Robot() { + void Robot() { // Set up the input channel for the counter counter.SetUpSource(1); - // Set the encoder to count pulse duration from rising edge to falling edge + // Set the encoder to count pulse duration from rising edge to falling edge counter.SetSemiPeriodMode(true); ``` @@ -105,13 +105,13 @@ In pulse-length mode, the counter will count either up or down depending on the ```java // Create a new Counter object in two-pulse mode Counter counter = new Counter(Counter.Mode.kPulseLength); - @Override + @Override public void robotInit() { // Set up the input channel for the counter counter.setUpSource(1); - // Set the decoding type to 2X + // Set the decoding type to 2X counter.setUpSourceEdge(true, true); - // Set the counter to count down if the pulses are longer than .05 seconds + // Set the counter to count down if the pulses are longer than .05 seconds counter.setPulseLengthMode(.05) } ``` @@ -119,12 +119,12 @@ In pulse-length mode, the counter will count either up or down depending on the ```c++ // Create a new Counter object in two-pulse mode frc::Counter counter{frc::Counter::Mode::kPulseLength}; - void Robot::RobotInit() { + void Robot::RobotInit() { // Set up the input channel for the counter counter.SetUpSource(1); - // Set the decoding type to 2X + // Set the decoding type to 2X counter.SetUpSourceEdge(true, true); - // Set the counter to count down if the pulses are longer than .05 seconds + // Set the counter to count down if the pulses are longer than .05 seconds counter.SetPulseLengthMode(.05) ``` @@ -137,12 +137,12 @@ In external direction mode, the counter counts either up or down depending on th ```java // Create a new Counter object in two-pulse mode Counter counter = new Counter(Counter.Mode.kExternalDirection); - @Override + @Override public void robotInit() { // Set up the input channels for the counter counter.setUpSource(1); counter.setDownSource(2); - // Set the decoding type to 2X + // Set the decoding type to 2X counter.setUpSourceEdge(true, true); } ``` @@ -150,11 +150,11 @@ In external direction mode, the counter counts either up or down depending on th ```c++ // Create a new Counter object in two-pulse mode frc::Counter counter{frc::Counter::Mode::kExternalDirection}; - void RobotInit() { + void RobotInit() { // Set up the input channels for the counter counter.SetUpSource(1); counter.SetDownSource(2); - // Set the decoding type to 2X + // Set the decoding type to 2X counter.SetUpSourceEdge(true, true); ``` @@ -172,13 +172,13 @@ Apart from the mode-specific configurations, the :code:`Counter` class offers a // Configures the counter to return a distance of 4 for every 256 pulses // Also changes the units of getRate counter.setDistancePerPulse(4./256.); - // Configures the counter to consider itself stopped after .1 seconds + // Configures the counter to consider itself stopped after .1 seconds counter.setMaxPeriod(.1); - // Configures the counter to consider itself stopped when its rate is below 10 + // Configures the counter to consider itself stopped when its rate is below 10 counter.setMinRate(10); - // Reverses the direction of the counter + // Reverses the direction of the counter counter.setReverseDirection(true); - // Configures an counter to average its period measurement over 5 samples + // Configures an counter to average its period measurement over 5 samples // Can be between 1 and 127 samples counter.setSamplesToAverage(5); ``` @@ -187,13 +187,13 @@ Apart from the mode-specific configurations, the :code:`Counter` class offers a // Configures the counter to return a distance of 4 for every 256 pulses // Also changes the units of getRate counter.SetDistancePerPulse(4./256.); - // Configures the counter to consider itself stopped after .1 seconds + // Configures the counter to consider itself stopped after .1 seconds counter.SetMaxPeriod(.1); - // Configures the counter to consider itself stopped when its rate is below 10 + // Configures the counter to consider itself stopped when its rate is below 10 counter.SetMinRate(10); - // Reverses the direction of the counter + // Reverses the direction of the counter counter.SetReverseDirection(true); - // Configures an counter to average its period measurement over 5 samples + // Configures an counter to average its period measurement over 5 samples // Can be between 1 and 127 samples counter.SetSamplesToAverage(5); ``` 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 43a22ef9a3..8738e7131c 100644 --- a/source/docs/software/hardware-apis/sensors/digital-inputs-software.rst +++ b/source/docs/software/hardware-apis/sensors/digital-inputs-software.rst @@ -53,20 +53,20 @@ An :code:`AnalogTrigger` may be initialized as follows. As with :code:`AnalogPo ```java // Initializes an AnalogTrigger on port 0 AnalogTrigger trigger0 = new AnalogTrigger(0); - // Initializes an AnalogInput on port 1 and enables 2-bit oversampling + // Initializes an AnalogInput on port 1 and enables 2-bit oversampling AnalogInput input = new AnalogInput(1); input.setAverageBits(2); - // Initializes an AnalogTrigger using the above input + // Initializes an AnalogTrigger using the above input AnalogTrigger trigger1 = new AnalogTrigger(input); ``` ```c++ // Initializes an AnalogTrigger on port 0 frc::AnalogTrigger trigger0{0}; - // Initializes an AnalogInput on port 1 and enables 2-bit oversampling + // Initializes an AnalogInput on port 1 and enables 2-bit oversampling frc::AnalogInput input{1}; input.SetAverageBits(2); - // Initializes an AnalogTrigger using the above input + // Initializes an AnalogTrigger using the above input frc::AnalogTrigger trigger1{input}; ``` @@ -81,14 +81,14 @@ To convert the analog signal to a digital one, it is necessary to specify at wha ```java // Sets the trigger to enable at a raw value of 3500, and disable at a value of 1000 trigger.setLimitsRaw(1000, 3500); - // Sets the trigger to enable at a voltage of 4 volts, and disable at a value of 1.5 volts + // 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); ``` ```c++ // Sets the trigger to enable at a raw value of 3500, and disable at a value of 1000 trigger.SetLimitsRaw(1000, 3500); - // Sets the trigger to enable at a voltage of 4 volts, and disable at a value of 1.5 volts + // 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); ``` @@ -104,9 +104,9 @@ Nearly all motorized mechanisms (such as arms and elevators) in FRC\ |reg| shoul ```java Spark spark = new Spark(0); - // Limit switch on DIO 2 + // Limit switch on DIO 2 DigitalInput limit = new DigitalInput(2); - public void autonomousPeriodic() { + public void autonomousPeriodic() { // Runs the motor forwards at half speed, unless the limit is pressed if(!limit.get()) { spark.set(.5); @@ -119,9 +119,9 @@ Nearly all motorized mechanisms (such as arms and elevators) in FRC\ |reg| shoul ```c++ // Motor for the mechanism frc::Spark spark{0}; - // Limit switch on DIO 2 + // Limit switch on DIO 2 frc::DigitalInput limit{2}; - void AutonomousPeriodic() { + void AutonomousPeriodic() { // Runs the motor forwards at half speed, unless the limit is pressed if(!limit.Get()) { spark.Set(.5); diff --git a/source/docs/software/hardware-apis/sensors/encoders-software.rst b/source/docs/software/hardware-apis/sensors/encoders-software.rst index aff15e2528..132c3c055f 100644 --- a/source/docs/software/hardware-apis/sensors/encoders-software.rst +++ b/source/docs/software/hardware-apis/sensors/encoders-software.rst @@ -87,13 +87,13 @@ The :code:`Encoder` class offers a number of configuration methods: // Configures the encoder to return a distance of 4 for every 256 pulses // Also changes the units of getRate encoder.setDistancePerPulse(4.0/256.0); - // Configures the encoder to consider itself stopped after .1 seconds + // Configures the encoder to consider itself stopped after .1 seconds encoder.setMaxPeriod(0.1); - // Configures the encoder to consider itself stopped when its rate is below 10 + // Configures the encoder to consider itself stopped when its rate is below 10 encoder.setMinRate(10); - // Reverses the direction of the encoder + // Reverses the direction of the encoder encoder.setReverseDirection(true); - // Configures an encoder to average its period measurement over 5 samples + // Configures an encoder to average its period measurement over 5 samples // Can be between 1 and 127 samples encoder.setSamplesToAverage(5); ``` @@ -102,13 +102,13 @@ The :code:`Encoder` class offers a number of configuration methods: // Configures the encoder to return a distance of 4 for every 256 pulses // Also changes the units of getRate encoder.SetDistancePerPulse(4.0/256.0); - // Configures the encoder to consider itself stopped after .1 seconds + // Configures the encoder to consider itself stopped after .1 seconds encoder.SetMaxPeriod(0.1); - // Configures the encoder to consider itself stopped when its rate is below 10 + // Configures the encoder to consider itself stopped when its rate is below 10 encoder.SetMinRate(10); - // Reverses the direction of the encoder + // Reverses the direction of the encoder encoder.SetReverseDirection(true); - // Configures an encoder to average its period measurement over 5 samples + // Configures an encoder to average its period measurement over 5 samples // Can be between 1 and 127 samples encoder.SetSamplesToAverage(5); ``` @@ -281,7 +281,7 @@ Users can obtain the distance measured by the encoder with the :code:`getDistanc ```c++ // Gets the distance traveled encoder.GetDistance(); - ``` + ``` ### Detecting a Duty Cycle Encoder is Connected @@ -297,7 +297,7 @@ As duty cycle encoders output a continuous set of pulses, it is possible to dete ```c++ // Gets if the encoder is connected encoder.IsConnected(); - ``` + ``` ### Resetting a Duty Cycle Encoder @@ -308,18 +308,18 @@ To reset an encoder so the current distance is 0, call the :code:`reset()` metho ```java // Resets the encoder to read a distance of zero at the current position encoder.reset(); - // get the position offset from when the encoder was reset + // get the position offset from when the encoder was reset encoder.getPositionOffset(); - // set the position offset to half a rotation + // set the position offset to half a rotation encoder.setPositionOffset(0.5); ``` ```c++ // Resets the encoder to read a distance of zero at the current position encoder.Reset(); - // get the position offset from when the encoder was reset + // get the position offset from when the encoder was reset encoder.GetPositionOffset(); - // set the position offset to half a rotation + // set the position offset to half a rotation encoder.SetPositionOffset(0.5); ``` @@ -383,7 +383,7 @@ Users can obtain the distance measured by the encoder with the :code:`getDistanc ```c++ // Gets the distance measured encoder.GetDistance(); - ``` + ``` ### Resetting an Analog Encoder @@ -394,18 +394,18 @@ To reset an analog encoder so the current distance is 0, call the :code:`reset() ```java // Resets the encoder to read a distance of zero at the current position encoder.reset(); - // get the position offset from when the encoder was reset + // get the position offset from when the encoder was reset encoder.getPositionOffset(); - // set the position offset to half a rotation + // set the position offset to half a rotation encoder.setPositionOffset(0.5); ``` ```c++ // Resets the encoder to read a distance of zero at the current position encoder.Reset(); - // get the position offset from when the encoder was reset + // get the position offset from when the encoder was reset encoder.GetPositionOffset(); - // set the position offset to half a rotation + // set the position offset to half a rotation encoder.SetPositionOffset(0.5); ``` @@ -424,25 +424,25 @@ Encoders can be used on a robot drive to create a simple "drive to distance" rou ```java // Creates an encoder on DIO ports 0 and 1 Encoder encoder = new Encoder(0, 1); - // Initialize motor controllers and drive + // Initialize motor controllers and drive Spark leftLeader = new Spark(0); Spark leftFollower = new Spark(1); - Spark rightLeader = new Spark(2); + Spark rightLeader = new Spark(2); Spark rightFollower = new Spark(3); - DifferentialDrive drive = new DifferentialDrive(leftLeader::set, rightLeader::set); - @Override + DifferentialDrive drive = new DifferentialDrive(leftLeader::set, rightLeader::set); + @Override public void robotInit() { // Configures the encoder's distance-per-pulse // The robot moves forward 1 foot per encoder rotation // There are 256 pulses per encoder rotation encoder.setDistancePerPulse(1./256.); - // Invert the right side of the drivetrain. You might have to invert the other side + // Invert the right side of the drivetrain. You might have to invert the other side rightLeader.setInverted(true); - // Configure the followers to follow the leaders + // Configure the followers to follow the leaders leftLeader.addFollower(leftFollower); rightLeader.addFollower(rightFollower); } - @Override + @Override public void autonomousPeriodic() { // Drives forward at half speed until the robot has moved 5 feet, then stops: if(encoder.getDistance() < 5) { @@ -456,25 +456,25 @@ Encoders can be used on a robot drive to create a simple "drive to distance" rou ```c++ // Creates an encoder on DIO ports 0 and 1. frc::Encoder encoder{0, 1}; - // Initialize motor controllers and drive + // Initialize motor controllers and drive frc::Spark leftLeader{0}; frc::Spark leftFollower{1}; - frc::Spark rightLeader{2}; + frc::Spark rightLeader{2}; frc::Spark rightFollower{3}; - frc::DifferentialDrive drive{[&](double output) { leftLeader.Set(output); }, + frc::DifferentialDrive drive{[&](double output) { leftLeader.Set(output); }, [&](double output) { rightLeader.Set(output); }}; void Robot::RobotInit() { // Configures the encoder's distance-per-pulse // The robot moves forward 1 foot per encoder rotation // There are 256 pulses per encoder rotation encoder.SetDistancePerPulse(1.0/256.0); - // Invert the right side of the drivetrain. You might have to invert the other side + // Invert the right side of the drivetrain. You might have to invert the other side rightLeader.SetInverted(true); - // Configure the followers to follow the leaders + // Configure the followers to follow the leaders leftLeader.AddFollower(leftFollower); rightLeader.AddFollower(rightFollower); } - void Robot::AutonomousPeriodic() { + void Robot::AutonomousPeriodic() { // Drives forward at half speed until the robot has moved 5 feet, then stops: if(encoder.GetDistance() < 5) { drive.TankDrive(0.5, 0.5); @@ -494,10 +494,10 @@ Since quadrature encoders measure *relative* distance, it is often important to ```java Encoder encoder = new Encoder(0, 1); - Spark spark = new Spark(0); - // Limit switch on DIO 2 + Spark spark = new Spark(0); + // Limit switch on DIO 2 DigitalInput limit = new DigitalInput(2); - public void autonomousPeriodic() { + public void autonomousPeriodic() { // Runs the motor backwards at half speed until the limit switch is pressed // then turn off the motor and reset the encoder if(!limit.get()) { @@ -511,10 +511,10 @@ Since quadrature encoders measure *relative* distance, it is often important to ```c++ frc::Encoder encoder{0,1}; - frc::Spark spark{0}; - // Limit switch on DIO 2 + frc::Spark spark{0}; + // Limit switch on DIO 2 frc::DigitalInput limit{2}; - void AutonomousPeriodic() { + void AutonomousPeriodic() { // Runs the motor backwards at half speed until the limit switch is pressed // then turn off the motor and reset the encoder if(!limit.Get()) { diff --git a/source/docs/software/hardware-apis/sensors/gyros-software.rst b/source/docs/software/hardware-apis/sensors/gyros-software.rst index 2795961d4b..51827c21b9 100644 --- a/source/docs/software/hardware-apis/sensors/gyros-software.rst +++ b/source/docs/software/hardware-apis/sensors/gyros-software.rst @@ -30,7 +30,7 @@ The ADIS16448 uses the :code:`ADIS16448_IMU` class ([Java](https://github.wpilib ```python from wpilib import ADIS16448_IMU - # ADIS16448 plugged into the MXP port + # ADIS16448 plugged into the MXP port self.gyro = ADIS16448_IMU() ``` @@ -121,7 +121,7 @@ The navX uses the :code:`AHRS` class. See the [navX documentation](https://pdoc ```python import navx - # navX MXP using SPI + # navX MXP using SPI self.gyro = navx.AHRS(SPI.Port.kMXP) ``` @@ -148,7 +148,7 @@ The Pigeon should use the :code:`WPI_PigeonIMU` class. The Pigeon can either be ```python import phoenix5 import ctre.sensors - self.gyro = ctre.WPI_PigeonIMU(0); # Pigeon is on CAN Bus with device ID 0 + self.gyro = ctre.WPI_PigeonIMU(0); # Pigeon is on CAN Bus with device ID 0 # OR (choose one or the other based on your connection) talon = ctre.TalonSRX(0); # TalonSRX is on CAN Bus with device ID 0 self.gyro = ctre.WPI_PigeonIMU(talon) # Pigeon uses the talon created above @@ -168,7 +168,7 @@ Gyros are extremely useful in FRC for both measuring and controlling robot headi ```java // Use gyro declaration from above here - public void robotInit() { + public void robotInit() { // Places a compass indicator for the gyro heading on the dashboard Shuffleboard.getTab("Example tab").add(gyro); } @@ -176,7 +176,7 @@ Gyros are extremely useful in FRC for both measuring and controlling robot headi ```c++ // Use gyro declaration from above here - void Robot::RobotInit() { + void Robot::RobotInit() { // Places a compass indicator for the gyro heading on the dashboard frc::Shuffleboard.GetTab("Example tab").Add(gyro); } @@ -184,9 +184,9 @@ Gyros are extremely useful in FRC for both measuring and controlling robot headi ```python from wpilib.shuffleboard import Shuffleboard - def robotInit(self): + def robotInit(self): # Use gyro declaration from above here - # Places a compass indicator for the gyro heading on the dashboard + # Places a compass indicator for the gyro heading on the dashboard Shuffleboard.getTab("Example tab").add(self.gyro) ``` @@ -206,57 +206,57 @@ The following example shows how to stabilize heading using a simple P loop close ```java // Use gyro declaration from above here - // The gain for a simple P loop + // The gain for a simple P loop double kP = 1; - // Initialize motor controllers and drive + // Initialize motor controllers and drive Spark leftLeader = new Spark(0); Spark leftFollower = new Spark(1); - Spark rightLeader = new Spark(2); + Spark rightLeader = new Spark(2); Spark rightFollower = new Spark(3); - DifferentialDrive drive = new DifferentialDrive(leftLeader::set, rightLeader::set); - @Override + DifferentialDrive drive = new DifferentialDrive(leftLeader::set, rightLeader::set); + @Override public void robotInit() { // Configures the encoder's distance-per-pulse // The robot moves forward 1 foot per encoder rotation // There are 256 pulses per encoder rotation encoder.setDistancePerPulse(1./256.); - // Invert the right side of the drivetrain. You might have to invert the other side + // Invert the right side of the drivetrain. You might have to invert the other side rightLeader.setInverted(true); - // Configure the followers to follow the leaders + // Configure the followers to follow the leaders leftLeader.addFollower(leftFollower); rightLeader.addFollower(rightFollower); } - @Override + @Override public void autonomousPeriodic() { // Setpoint is implicitly 0, since we don't want the heading to change double error = -gyro.getRate(); - // Drives forward continuously at half speed, using the gyro to stabilize the heading + // Drives forward continuously at half speed, using the gyro to stabilize the heading drive.tankDrive(.5 + kP * error, .5 - kP * error); } ``` ```c++ // Use gyro declaration from above here - // The gain for a simple P loop + // The gain for a simple P loop double kP = 1; - // Initialize motor controllers and drive + // Initialize motor controllers and drive frc::Spark leftLeader{0}; frc::Spark leftFollower{1}; - frc::Spark rightLeader{2}; + frc::Spark rightLeader{2}; frc::Spark rightFollower{3}; - frc::DifferentialDrive drive{[&](double output) { leftLeader.Set(output); }, + frc::DifferentialDrive drive{[&](double output) { leftLeader.Set(output); }, [&](double output) { rightLeader.Set(output); }}; - void Robot::RobotInit() { + void Robot::RobotInit() { // Invert the right side of the drivetrain. You might have to invert the other side rightLeader.SetInverted(true); - // Configure the followers to follow the leaders + // Configure the followers to follow the leaders leftLeader.AddFollower(leftFollower); rightLeader.AddFollower(rightFollower); } - void Robot::AutonomousPeriodic() { + void Robot::AutonomousPeriodic() { // Setpoint is implicitly 0, since we don't want the heading to change double error = -gyro.GetRate(); - // Drives forward continuously at half speed, using the gyro to stabilize the heading + // Drives forward continuously at half speed, using the gyro to stabilize the heading drive.TankDrive(.5 + kP * error, .5 - kP * error); } ``` @@ -265,23 +265,23 @@ The following example shows how to stabilize heading using a simple P loop close from wpilib import Spark from wpilib import MotorControllerGroup from wpilib.drive import DifferentialDrive - def robotInit(self): + def robotInit(self): # Use gyro declaration from above here - # The gain for a simple P loop + # The gain for a simple P loop self.kP = 1 - # Initialize motor controllers and drive + # Initialize motor controllers and drive left1 = Spark(0) left2 = Spark(1) right1 = Spark(2) right2 = Spark(3) - leftMotors = MotorControllerGroup(left1, left2) + leftMotors = MotorControllerGroup(left1, left2) rightMotors = MotorControllerGroup(right1, right2) - self.drive = DifferentialDrive(leftMotors, rightMotors) - rightMotors.setInverted(true) - def autonomousPeriodic(self): + self.drive = DifferentialDrive(leftMotors, rightMotors) + rightMotors.setInverted(true) + def autonomousPeriodic(self): # Setpoint is implicitly 0, since we don't want the heading to change error = -self.gyro.getRate() - # Drives forward continuously at half speed, using the gyro to stabilize the heading + # Drives forward continuously at half speed, using the gyro to stabilize the heading self.drive.tankDrive(.5 + self.kP * error, .5 - self.kP * error) ``` @@ -297,59 +297,59 @@ The following example shows how to stabilize heading using a simple P loop close ```java // Use gyro declaration from above here - // The gain for a simple P loop + // The gain for a simple P loop double kP = 1; - // The heading of the robot when starting the motion + // The heading of the robot when starting the motion double heading; - // Initialize motor controllers and drive + // Initialize motor controllers and drive Spark left1 = new Spark(0); Spark left2 = new Spark(1); - Spark right1 = new Spark(2); + Spark right1 = new Spark(2); Spark right2 = new Spark(3); - MotorControllerGroup leftMotors = new MotorControllerGroup(left1, left2); + MotorControllerGroup leftMotors = new MotorControllerGroup(left1, left2); MotorControllerGroup rightMotors = new MotorControllerGroup(right1, right2); - DifferentialDrive drive = new DifferentialDrive(leftMotors, rightMotors); - @Override + DifferentialDrive drive = new DifferentialDrive(leftMotors, rightMotors); + @Override public void robotInit() { rightMotors.setInverted(true); } - @Override + @Override public void autonomousInit() { // Set setpoint to current heading at start of auto heading = gyro.getAngle(); } - @Override + @Override public void autonomousPeriodic() { double error = heading - gyro.getAngle(); - // Drives forward continuously at half speed, using the gyro to stabilize the heading + // Drives forward continuously at half speed, using the gyro to stabilize the heading drive.tankDrive(.5 + kP * error, .5 - kP * error); } ``` ```c++ // Use gyro declaration from above here - // The gain for a simple P loop + // The gain for a simple P loop double kP = 1; - // The heading of the robot when starting the motion + // The heading of the robot when starting the motion double heading; - // Initialize motor controllers and drive + // Initialize motor controllers and drive frc::Spark left1{0}; frc::Spark left2{1}; frc::Spark right1{2}; frc::Spark right2{3}; - frc::MotorControllerGroup leftMotors{left1, left2}; + frc::MotorControllerGroup leftMotors{left1, left2}; frc::MotorControllerGroup rightMotors{right1, right2}; - frc::DifferentialDrive drive{leftMotors, rightMotors}; - void Robot::RobotInit() { + frc::DifferentialDrive drive{leftMotors, rightMotors}; + void Robot::RobotInit() { rightMotors.SetInverted(true); } - void Robot::AutonomousInit() { + void Robot::AutonomousInit() { // Set setpoint to current heading at start of auto heading = gyro.GetAngle(); } - void Robot::AutonomousPeriodic() { + void Robot::AutonomousPeriodic() { double error = heading - gyro.GetAngle(); - // Drives forward continuously at half speed, using the gyro to stabilize the heading + // Drives forward continuously at half speed, using the gyro to stabilize the heading drive.TankDrive(.5 + kP * error, .5 - kP * error); } ``` @@ -358,25 +358,25 @@ The following example shows how to stabilize heading using a simple P loop close from wpilib import Spark from wpilib import MotorControllerGroup from wpilib.drive import DifferentialDrive - def robotInit(self): + def robotInit(self): # Use gyro declaration from above here - # The gain for a simple P loop + # The gain for a simple P loop self.kP = 1 - # Initialize motor controllers and drive + # Initialize motor controllers and drive left1 = Spark(0) left2 = Spark(1) right1 = Spark(2) right2 = Spark(3) - leftMotors = MotorControllerGroup(left1, left2) + leftMotors = MotorControllerGroup(left1, left2) rightMotors = MotorControllerGroup(right1, right2) - self.drive = DifferentialDrive(leftMotors, rightMotors) - rightMotors.setInverted(true) - def autonomousInit(self): + self.drive = DifferentialDrive(leftMotors, rightMotors) + rightMotors.setInverted(true) + def autonomousInit(self): # Set setpoint to current heading at start of auto self.heading = self.gyro.getAngle() def autonomousPeriodic(self): error = self.heading - self.gyro.getAngle() - # Drives forward continuously at half speed, using the gyro to stabilize the heading + # Drives forward continuously at half speed, using the gyro to stabilize the heading self.drive.tankDrive(.5 + self.kP * error, .5 - self.kP * error) ``` @@ -392,48 +392,48 @@ Much like with heading stabilization, this is often accomplished with a PID loop ```java // Use gyro declaration from above here - // The gain for a simple P loop + // The gain for a simple P loop double kP = 0.05; - // Initialize motor controllers and drive + // Initialize motor controllers and drive Spark left1 = new Spark(0); Spark left2 = new Spark(1); - Spark right1 = new Spark(2); + Spark right1 = new Spark(2); Spark right2 = new Spark(3); - MotorControllerGroup leftMotors = new MotorControllerGroup(left1, left2); + MotorControllerGroup leftMotors = new MotorControllerGroup(left1, left2); MotorControllerGroup rightMotors = new MotorControllerGroup(right1, right2); - DifferentialDrive drive = new DifferentialDrive(leftMotors, rightMotors); - @Override + DifferentialDrive drive = new DifferentialDrive(leftMotors, rightMotors); + @Override public void robotInit() { rightMotors.setInverted(true); } - @Override + @Override public void autonomousPeriodic() { // Find the heading error; setpoint is 90 double error = 90 - gyro.getAngle(); - // Turns the robot to face the desired direction + // Turns the robot to face the desired direction drive.tankDrive(kP * error, -kP * error); } ``` ```c++ // Use gyro declaration from above here - // The gain for a simple P loop + // The gain for a simple P loop double kP = 0.05; - // Initialize motor controllers and drive + // Initialize motor controllers and drive frc::Spark left1{0}; frc::Spark left2{1}; frc::Spark right1{2}; frc::Spark right2{3}; - frc::MotorControllerGroup leftMotors{left1, left2}; + frc::MotorControllerGroup leftMotors{left1, left2}; frc::MotorControllerGroup rightMotors{right1, right2}; - frc::DifferentialDrive drive{leftMotors, rightMotors}; - void Robot::RobotInit() { + frc::DifferentialDrive drive{leftMotors, rightMotors}; + void Robot::RobotInit() { rightMotors.SetInverted(true); } - void Robot::AutonomousPeriodic() { + void Robot::AutonomousPeriodic() { // Find the heading error; setpoint is 90 double error = 90 - gyro.GetAngle(); - // Turns the robot to face the desired direction + // Turns the robot to face the desired direction drive.TankDrive(kP * error, -kP * error); } ``` @@ -442,23 +442,23 @@ Much like with heading stabilization, this is often accomplished with a PID loop from wpilib import Spark from wpilib import MotorControllerGroup from wpilib.drive import DifferentialDrive - def robotInit(self): + def robotInit(self): # Use gyro declaration from above here - # The gain for a simple P loop + # The gain for a simple P loop self.kP = 0.05 - # Initialize motor controllers and drive + # Initialize motor controllers and drive left1 = Spark(0) left2 = Spark(1) right1 = Spark(2) right2 = Spark(3) - leftMotors = MotorControllerGroup(left1, left2) + leftMotors = MotorControllerGroup(left1, left2) rightMotors = MotorControllerGroup(right1, right2) - self.drive = DifferentialDrive(leftMotors, rightMotors) - rightMotors.setInverted(true) - def autonomousPeriodic(self): + self.drive = DifferentialDrive(leftMotors, rightMotors) + rightMotors.setInverted(true) + def autonomousPeriodic(self): # Find the heading error; setpoint is 90 error = 90 - self.gyro.getAngle() - # Drives forward continuously at half speed, using the gyro to stabilize the heading + # Drives forward continuously at half speed, using the gyro to stabilize the heading self.drive.tankDrive(self.kP * error, -self.kP * error) ``` diff --git a/source/docs/software/hardware-apis/sensors/limit-switch.rst b/source/docs/software/hardware-apis/sensors/limit-switch.rst index 2d1d6dca77..8f78514634 100644 --- a/source/docs/software/hardware-apis/sensors/limit-switch.rst +++ b/source/docs/software/hardware-apis/sensors/limit-switch.rst @@ -13,11 +13,11 @@ Limit switches can have "normally open" or "normally closed" outputs. This will DigitalInput bottomlimitSwitch = new DigitalInput(1); PWMVictorSPX motor = new PWMVictorSPX(0); Joystick joystick = new Joystick(0); - @Override + @Override public void teleopPeriodic() { setMotorSpeed(joystick.getRawAxis(2)); } - public void setMotorSpeed(double speed) { + public void setMotorSpeed(double speed) { if (speed > 0) { if (toplimitSwitch.get()) { // We are going up and top limit is tripped so stop @@ -43,10 +43,10 @@ Limit switches can have "normally open" or "normally closed" outputs. This will frc::DigitalInput bottomlimitSwitch {1}; frc::PWMVictorSPX motor {0}; frc::Joystick joystick {0}; - void TeleopPeriodic() { + void TeleopPeriodic() { SetMotorSpeed(joystick.GetRawAxis(2)); } - void SetMotorSpeed(double speed) { + void SetMotorSpeed(double speed) { if (speed > 0) { if (toplimitSwitch.Get()) { // We are going up and top limit is tripped so stop 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 045479c68d..79872e21c8 100644 --- a/source/docs/software/kinematics-and-odometry/differential-drive-kinematics.rst +++ b/source/docs/software/kinematics-and-odometry/differential-drive-kinematics.rst @@ -15,24 +15,24 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java / Python) / ``ToWheelSpeeds(Ch // Creating my kinematics object: track width of 27 inches DifferentialDriveKinematics kinematics = new DifferentialDriveKinematics(Units.inchesToMeters(27.0)); - // Example chassis speeds: 2 meters per second linear velocity, + // Example chassis speeds: 2 meters per second linear velocity, // 1 radian per second angular velocity. var chassisSpeeds = new ChassisSpeeds(2.0, 0, 1.0); - // Convert to wheel speeds + // Convert to wheel speeds DifferentialDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(chassisSpeeds); - // Left velocity + // Left velocity double leftVelocity = wheelSpeeds.leftMetersPerSecond; - // Right velocity + // Right velocity double rightVelocity = wheelSpeeds.rightMetersPerSecond; ``` ```c++ // Creating my kinematics object: track width of 27 inches frc::DifferentialDriveKinematics kinematics{27_in}; - // Example chassis speeds: 2 meters per second linear velocity, + // Example chassis speeds: 2 meters per second linear velocity, // 1 radian per second angular velocity. frc::ChassisSpeeds chassisSpeeds{2_mps, 0_mps, 1_rad_per_s}; - // Convert to wheel speeds. Here, we can use C++17's structured bindings + // Convert to wheel speeds. Here, we can use C++17's structured bindings // feature to automatically split the DifferentialDriveWheelSpeeds // struct into left and right velocities. auto [left, right] = kinematics.ToWheelSpeeds(chassisSpeeds); @@ -42,14 +42,14 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java / Python) / ``ToWheelSpeeds(Ch from wpimath.kinematics import DifferentialDriveKinematics from wpimath.kinematics import ChassisSpeeds from wpimath.units import inchesToMeters - # Creating my kinematics object: track width of 27 inches + # Creating my kinematics object: track width of 27 inches kinematics = DifferentialDriveKinematics(Units.inchesToMeters(27.0)) - # Example chassis speeds: 2 meters per second linear velocity, + # Example chassis speeds: 2 meters per second linear velocity, # 1 radian per second angular velocity. chassisSpeeds = ChassisSpeeds(2.0, 0, 1.0) - # Convert to wheel speeds + # Convert to wheel speeds wheelSpeeds = kinematics.toWheelSpeeds(chassisSpeeds) - # Left velocity + # Left velocity leftVelocity = wheelSpeeds.left # Right velocity rightVelocity = wheelSpeeds.right @@ -64,24 +64,24 @@ One can also use the kinematics object to convert individual wheel speeds (left // Creating my kinematics object: track width of 27 inches DifferentialDriveKinematics kinematics = new DifferentialDriveKinematics(Units.inchesToMeters(27.0)); - // Example differential drive wheel speeds: 2 meters per second + // Example differential drive wheel speeds: 2 meters per second // for the left side, 3 meters per second for the right side. var wheelSpeeds = new DifferentialDriveWheelSpeeds(2.0, 3.0); - // Convert to chassis speeds. + // Convert to chassis speeds. ChassisSpeeds chassisSpeeds = kinematics.toChassisSpeeds(wheelSpeeds); - // Linear velocity + // Linear velocity double linearVelocity = chassisSpeeds.vxMetersPerSecond; - // Angular velocity + // Angular velocity double angularVelocity = chassisSpeeds.omegaRadiansPerSecond; ``` ```c++ // Creating my kinematics object: track width of 27 inches frc::DifferentialDriveKinematics kinematics{27_in}; - // Example differential drive wheel speeds: 2 meters per second + // Example differential drive wheel speeds: 2 meters per second // for the left side, 3 meters per second for the right side. frc::DifferentialDriveWheelSpeeds wheelSpeeds{2_mps, 3_mps}; - // Convert to chassis speeds. Here we can use C++17's structured bindings + // Convert to chassis speeds. Here we can use C++17's structured bindings // feature to automatically split the ChassisSpeeds struct into its 3 components. // Note that because a differential drive is non-holonomic, the vy variable // will be equal to zero. @@ -92,16 +92,16 @@ One can also use the kinematics object to convert individual wheel speeds (left from wpimath.kinematics import DifferentialDriveKinematics from wpimath.kinematics import DifferentialDriveWheelSpeeds from wpimath.units import inchesToMeters - # Creating my kinematics object: track width of 27 inches + # Creating my kinematics object: track width of 27 inches kinematics = DifferentialDriveKinematics(inchesToMeters(27.0)) - # Example differential drive wheel speeds: 2 meters per second + # Example differential drive wheel speeds: 2 meters per second # for the left side, 3 meters per second for the right side. wheelSpeeds = DifferentialDriveWheelSpeeds(2.0, 3.0) - # Convert to chassis speeds. + # Convert to chassis speeds. chassisSpeeds = kinematics.toChassisSpeeds(wheelSpeeds) - # Linear velocity + # Linear velocity linearVelocity = chassisSpeeds.vx - # Angular velocity + # Angular velocity angularVelocity = chassisSpeeds.omega ``` 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 bd9e629691..7eb7362f70 100644 --- a/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst +++ b/source/docs/software/kinematics-and-odometry/differential-drive-odometry.rst @@ -40,14 +40,14 @@ The optional argument is the starting pose of your robot on the field (as a ``Po from wpimath.kinematics import DifferentialDriveOdometry from wpimath.geometry import Pose2d from wpimath.geometry import Rotation2d - # Creating my odometry object. Here, + # Creating my odometry object. Here, # our starting pose is 5 meters along the long end of the field and in the # center of the field along the short end, facing forward. m_odometry = DifferentialDriveOdometry( m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance(), Pose2d(5.0, 13.5, Rotation2d())) - ``` + ``` ## Updating the Robot Pose The ``update`` method can be used to update the robot's position on the field. This 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. This method takes in the gyro angle of the robot, along with the left encoder distance and right encoder distance. @@ -61,7 +61,7 @@ The ``update`` method can be used to update the robot's position on the field. T public void periodic() { // Get the rotation of the robot from the gyro. var gyroAngle = m_gyro.getRotation2d(); - // Update the pose + // Update the pose m_pose = m_odometry.update(gyroAngle, m_leftEncoder.getDistance(), m_rightEncoder.getDistance()); @@ -72,7 +72,7 @@ The ``update`` method can be used to update the robot's position on the field. T void Periodic() override { // Get the rotation of the robot from the gyro. frc::Rotation2d gyroAngle = m_gyro.GetRotation2d(); - // Update the pose + // Update the pose m_pose = m_odometry.Update(gyroAngle, units::meter_t{m_leftEncoder.GetDistance()}, units::meter_t{m_rightEncoder.GetDistance()}); @@ -83,7 +83,7 @@ The ``update`` method can be used to update the robot's position on the field. T def periodic(self): # Get the rotation of the robot from the gyro. gyroAngle = m_gyro.getRotation2d() - # Update the pose + # Update the pose m_pose = m_odometry.update(gyroAngle, m_leftEncoder.getDistance(), m_rightEncoder.getDistance()) 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 4c4d40a1f8..902974f060 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 @@ -41,7 +41,7 @@ The constructor for the ``ChassisSpeeds`` object is very straightforward, accept ```python import math from wpimath.kinematics import ChassisSpeeds - # The robot is moving at 3 meters per second forward, 2 meters + # 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. speeds = ChassisSpeeds(3.0, -2.0, math.pi) @@ -78,7 +78,7 @@ The static ``ChassisSpeeds.fromFieldRelativeSpeeds`` (Java / Python) / ``Chassis import math from wpimath.kinematics import ChassisSpeeds from wpimath.geometry import Rotation2d - # The desired field relative speed here is 2 meters per second + # The desired field relative speed here is 2 meters per second # toward the opponent's alliance station wall, and 2 meters per # second toward the left field boundary. The desired rotation # is a quarter of a rotation per second counterclockwise. The current 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 dc4df5a598..f25b923ba0 100644 --- a/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst +++ b/source/docs/software/kinematics-and-odometry/mecanum-drive-kinematics.rst @@ -14,7 +14,7 @@ The ``MecanumDriveKinematics`` class accepts four constructor arguments, with ea Translation2d m_frontRightLocation = new Translation2d(0.381, -0.381); Translation2d m_backLeftLocation = new Translation2d(-0.381, 0.381); Translation2d m_backRightLocation = new Translation2d(-0.381, -0.381); - // Creating my kinematics object using the wheel locations. + // Creating my kinematics object using the wheel locations. MecanumDriveKinematics m_kinematics = new MecanumDriveKinematics( m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation ); @@ -26,7 +26,7 @@ The ``MecanumDriveKinematics`` class accepts four constructor arguments, with ea frc::Translation2d m_frontRightLocation{0.381_m, -0.381_m}; frc::Translation2d m_backLeftLocation{-0.381_m, 0.381_m}; frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m}; - // Creating my kinematics object using the wheel locations. + // Creating my kinematics object using the wheel locations. frc::MecanumDriveKinematics m_kinematics{ m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation}; @@ -35,12 +35,12 @@ The ``MecanumDriveKinematics`` class accepts four constructor arguments, with ea ```python from wpimath.geometry import Translation2d from wpimath.kinematics import MecanumDriveKinematics - # Locations of the wheels relative to the robot center. + # Locations of the wheels relative to the robot center. frontLeftLocation = Translation2d(0.381, 0.381) frontRightLocation = Translation2d(0.381, -0.381) backLeftLocation = Translation2d(-0.381, 0.381) backRightLocation = Translation2d(-0.381, -0.381) - # Creating my kinematics object using the wheel locations. + # Creating my kinematics object using the wheel locations. self.kinematics = MecanumDriveKinematics( frontLeftLocation, frontRightLocation, backLeftLocation, backRightLocation ) @@ -56,9 +56,9 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java / Python) / ``ToWheelSpeeds(Ch // per second to the left, and rotation at 1.5 radians per second // counterclockwise. ChassisSpeeds speeds = new ChassisSpeeds(1.0, 3.0, 1.5); - // Convert to wheel speeds + // Convert to wheel speeds MecanumDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(speeds); - // Get the individual wheel speeds + // Get the individual wheel speeds double frontLeft = wheelSpeeds.frontLeftMetersPerSecond double frontRight = wheelSpeeds.frontRightMetersPerSecond double backLeft = wheelSpeeds.rearLeftMetersPerSecond @@ -70,7 +70,7 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java / Python) / ``ToWheelSpeeds(Ch // per second to the left, and rotation at 1.5 radians per second // counterclockwise. frc::ChassisSpeeds speeds{1_mps, 3_mps, 1.5_rad_per_s}; - // Convert to wheel speeds. Here, we can use C++17's structured + // Convert to wheel speeds. Here, we can use C++17's structured // bindings feature to automatically split up the MecanumDriveWheelSpeeds // struct into it's individual components auto [fl, fr, bl, br] = kinematics.ToWheelSpeeds(speeds); @@ -78,11 +78,11 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java / Python) / ``ToWheelSpeeds(Ch ```python from wpimath.kinematics import ChassisSpeeds - # Example chassis speeds: 1 meter per second forward, 3 meters + # Example chassis speeds: 1 meter per second forward, 3 meters # per second to the left, and rotation at 1.5 radians per second # counterclockwise. speeds = ChassisSpeeds(1.0, 3.0, 1.5) - # Convert to wheel speeds + # Convert to wheel speeds frontLeft, frontRight, backLeft, backRight = self.kinematics.toWheelSpeeds(speeds) ``` @@ -99,7 +99,7 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java / Python) / ``ToWheelSpeeds(Ch // robot angle is 45 degrees. ChassisSpeeds speeds = ChassisSpeeds.fromFieldRelativeSpeeds( 2.0, 2.0, Math.PI / 2.0, Rotation2d.fromDegrees(45.0)); - // Now use this in our kinematics + // Now use this in our kinematics MecanumDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(speeds); ``` @@ -111,7 +111,7 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java / Python) / ``ToWheelSpeeds(Ch // robot angle is 45 degrees. frc::ChassisSpeeds speeds = frc::ChassisSpeeds::FromFieldRelativeSpeeds( 2_mps, 2_mps, units::radians_per_second_t(std::numbers::pi / 2.0), Rotation2d(45_deg)); - // Now use this in our kinematics + // Now use this in our kinematics auto [fl, fr, bl, br] = kinematics.ToWheelSpeeds(speeds); ``` @@ -119,14 +119,14 @@ The ``toWheelSpeeds(ChassisSpeeds speeds)`` (Java / Python) / ``ToWheelSpeeds(Ch from wpimath.kinematics import ChassisSpeeds import math from wpimath.geometry import Rotation2d - # The desired field relative speed here is 2 meters per second + # The desired field relative speed here is 2 meters per second # toward the opponent's alliance station wall, and 2 meters per # second toward the left field boundary. The desired rotation # is a quarter of a rotation per second counterclockwise. The current # robot angle is 45 degrees. speeds = ChassisSpeeds.fromFieldRelativeSpeeds( 2.0, 2.0, math.pi / 2.0, Rotation2d.fromDegrees(45.0)) - # Now use this in our kinematics + # Now use this in our kinematics wheelSpeeds = self.kinematics.toWheelSpeeds(speeds) ``` @@ -145,9 +145,9 @@ One can also use the kinematics object to convert a ``MecanumDriveWheelSpeeds`` ```java // Example wheel speeds var wheelSpeeds = new MecanumDriveWheelSpeeds(-17.67, 20.51, -13.44, 16.26); - // Convert to chassis speeds + // Convert to chassis speeds ChassisSpeeds chassisSpeeds = kinematics.toChassisSpeeds(wheelSpeeds); - // Getting individual speeds + // Getting individual speeds double forward = chassisSpeeds.vxMetersPerSecond; double sideways = chassisSpeeds.vyMetersPerSecond; double angular = chassisSpeeds.omegaRadiansPerSecond; @@ -156,7 +156,7 @@ One can also use the kinematics object to convert a ``MecanumDriveWheelSpeeds`` ```c++ // Example wheel speeds frc::MecanumDriveWheelSpeeds wheelSpeeds{-17.67_mps, 20.51_mps, -13.44_mps, 16.26_mps}; - // Convert to chassis speeds. Here, we can use C++17's structured bindings + // Convert to chassis speeds. Here, we can use C++17's structured bindings // feature to automatically break up the ChassisSpeeds struct into its // three components. auto [forward, sideways, angular] = kinematics.ToChassisSpeeds(wheelSpeeds); @@ -164,11 +164,11 @@ One can also use the kinematics object to convert a ``MecanumDriveWheelSpeeds`` ```python from wpimath.kinematics import MecanumDriveWheelSpeeds - # Example wheel speeds + # Example wheel speeds wheelSpeeds = MecanumDriveWheelSpeeds(-17.67, 20.51, -13.44, 16.26) - # Convert to chassis speeds + # Convert to chassis speeds chassisSpeeds = self.kinematics.toChassisSpeeds(wheelSpeeds) - # Getting individual speeds + # Getting individual speeds forward = chassisSpeeds.vx sideways = chassisSpeeds.vy angular = chassisSpeeds.omega 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 3f2f049cf5..2a6fe09cd7 100644 --- a/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst +++ b/source/docs/software/kinematics-and-odometry/mecanum-drive-odometry.rst @@ -24,11 +24,11 @@ The fourth optional argument is the starting pose of your robot on the field (as Translation2d m_frontRightLocation = new Translation2d(0.381, -0.381); Translation2d m_backLeftLocation = new Translation2d(-0.381, 0.381); Translation2d m_backRightLocation = new Translation2d(-0.381, -0.381); - // Creating my kinematics object using the wheel locations. + // Creating my kinematics object using the wheel locations. MecanumDriveKinematics m_kinematics = new MecanumDriveKinematics( m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation ); - // Creating my odometry object from the kinematics object and the initial wheel positions. + // Creating my odometry object from the kinematics object and the initial wheel positions. // Here, our starting pose is 5 meters along the long end of the field and in the // center of the field along the short end, facing the opposing alliance wall. MecanumDriveOdometry m_odometry = new MecanumDriveOdometry( @@ -48,12 +48,12 @@ The fourth optional argument is the starting pose of your robot on the field (as frc::Translation2d m_frontRightLocation{0.381_m, -0.381_m}; frc::Translation2d m_backLeftLocation{-0.381_m, 0.381_m}; frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m}; - // Creating my kinematics object using the wheel locations. + // Creating my kinematics object using the wheel locations. frc::MecanumDriveKinematics m_kinematics{ m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation }; - // Creating my odometry object from the kinematics object. Here, + // Creating my odometry object from the kinematics object. Here, // our starting pose is 5 meters along the long end of the field and in the // center of the field along the short end, facing forward. frc::MecanumDriveOdometry m_odometry{ @@ -75,16 +75,16 @@ The fourth optional argument is the starting pose of your robot on the field (as from wpimath.kinematics import MecanumDriveWheelPositions from wpimath.geometry import Pose2d from wpimath.geometry import Rotation2d - # Locations of the wheels relative to the robot center. + # Locations of the wheels relative to the robot center. frontLeftLocation = Translation2d(0.381, 0.381) frontRightLocation = Translation2d(0.381, -0.381) backLeftLocation = Translation2d(-0.381, 0.381) backRightLocation = Translation2d(-0.381, -0.381) - # Creating my kinematics object using the wheel locations. + # Creating my kinematics object using the wheel locations. self.kinematics = MecanumDriveKinematics( frontLeftLocation, frontRightLocation, backLeftLocation, backRightLocation ) - # Creating my odometry object from the kinematics object and the initial wheel positions. + # Creating my odometry object from the kinematics object and the initial wheel positions. # Here, our starting pose is 5 meters along the long end of the field and in the # center of the field along the short end, facing the opposing alliance wall. self.odometry = MecanumDriveOdometry( @@ -110,9 +110,9 @@ The ``update`` method of the odometry class updates the robot position on the fi var wheelPositions = new MecanumDriveWheelPositions( m_frontLeftEncoder.getDistance(), m_frontRightEncoder.getDistance(), m_backLeftEncoder.getDistance(), m_backRightEncoder.getDistance()); - // Get the rotation of the robot from the gyro. + // Get the rotation of the robot from the gyro. var gyroAngle = m_gyro.getRotation2d(); - // Update the pose + // Update the pose m_pose = m_odometry.update(gyroAngle, wheelPositions); } ``` @@ -125,9 +125,9 @@ The ``update`` method of the odometry class updates the robot position on the fi units::meter_t{m_frontRightEncoder.GetDistance()}, units::meter_t{m_backLeftEncoder.GetDistance()}, units::meter_t{m_backRightEncoder.GetDistance()}}; - // Get the rotation of the robot from the gyro. + // Get the rotation of the robot from the gyro. frc::Rotation2d gyroAngle = m_gyro.GetRotation2d(); - // Update the pose + // Update the pose m_pose = m_odometry.Update(gyroAngle, wheelPositions); } ``` @@ -139,9 +139,9 @@ The ``update`` method of the odometry class updates the robot position on the fi wheelPositions = MecanumDriveWheelPositions( self.frontLeftEncoder.getDistance(), self.frontRightEncoder.getDistance(), self.backLeftEncoder.getDistance(), self.backRightEncoder.getDistance()) - # Get the rotation of the robot from the gyro. + # Get the rotation of the robot from the gyro. gyroAngle = gyro.getRotation2d() - # Update the pose + # Update the pose self.pose = odometry.update(gyroAngle, wheelPositions) ``` 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 df333afcb9..a3aa1fe551 100644 --- a/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst +++ b/source/docs/software/kinematics-and-odometry/swerve-drive-kinematics.rst @@ -26,7 +26,7 @@ The locations for the modules must be relative to the center of the robot. Posit Translation2d m_frontRightLocation = new Translation2d(0.381, -0.381); Translation2d m_backLeftLocation = new Translation2d(-0.381, 0.381); Translation2d m_backRightLocation = new Translation2d(-0.381, -0.381); - // Creating my kinematics object using the module locations + // Creating my kinematics object using the module locations SwerveDriveKinematics m_kinematics = new SwerveDriveKinematics( m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation ); @@ -38,7 +38,7 @@ The locations for the modules must be relative to the center of the robot. Posit frc::Translation2d m_frontRightLocation{0.381_m, -0.381_m}; frc::Translation2d m_backLeftLocation{-0.381_m, 0.381_m}; frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m}; - // Creating my kinematics object using the module locations. + // Creating my kinematics object using the module locations. frc::SwerveDriveKinematics<4> m_kinematics{ m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation}; @@ -46,14 +46,14 @@ The locations for the modules must be relative to the center of the robot. Posit ```python # Python requires using the right class for the number of modules you have - from wpimath.geometry import Translation2d + from wpimath.geometry import Translation2d from wpimath.kinematics import SwerveDrive4Kinematics - # Locations for the swerve drive modules relative to the robot center. + # Locations for the swerve drive modules relative to the robot center. frontLeftLocation = Translation2d(0.381, 0.381) frontRightLocation = Translation2d(0.381, -0.381) backLeftLocation = Translation2d(-0.381, 0.381) backRightLocation = Translation2d(-0.381, -0.381) - # Creating my kinematics object using the module locations + # Creating my kinematics object using the module locations self.kinematics = SwerveDrive4Kinematics( frontLeftLocation, frontRightLocation, backLeftLocation, backRightLocation ) @@ -71,15 +71,15 @@ The elements in the array that is returned by this method are the same order in // per second to the left, and rotation at 1.5 radians per second // counterclockwise. ChassisSpeeds speeds = new ChassisSpeeds(1.0, 3.0, 1.5); - // Convert to module states + // Convert to module states SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(speeds); - // Front left module state + // Front left module state SwerveModuleState frontLeft = moduleStates[0]; - // Front right module state + // Front right module state SwerveModuleState frontRight = moduleStates[1]; - // Back left module state + // Back left module state SwerveModuleState backLeft = moduleStates[2]; - // Back right module state + // Back right module state SwerveModuleState backRight = moduleStates[3]; ``` @@ -88,7 +88,7 @@ The elements in the array that is returned by this method are the same order in // per second to the left, and rotation at 1.5 radians per second // counterclockwise. frc::ChassisSpeeds speeds{1_mps, 3_mps, 1.5_rad_per_s}; - // Convert to module states. Here, we can use C++17's structured + // Convert to module states. Here, we can use C++17's structured // bindings feature to automatically split up the array into its // individual SwerveModuleState components. auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(speeds); @@ -96,11 +96,11 @@ The elements in the array that is returned by this method are the same order in ```python from wpimath.kinematics import ChassisSpeeds - # Example chassis speeds: 1 meter per second forward, 3 meters + # Example chassis speeds: 1 meter per second forward, 3 meters # per second to the left, and rotation at 1.5 radians per second # counterclockwise. speeds = ChassisSpeeds(1.0, 3.0, 1.5) - # Convert to module states + # Convert to module states frontLeft, frontRight, backLeft, backRight = self.kinematics.toSwerveModuleStates(speeds) ``` @@ -123,7 +123,7 @@ This method takes two parameters: the desired state (usually from the ``toSwerve ```python from wpimath.kinematics import SwerveModuleState from wpimath.geometry import Rotation2d - frontLeftOptimized = SwerveModuleState.optimize(frontLeft, + frontLeftOptimized = SwerveModuleState.optimize(frontLeft, Rotation2d(self.m_turningEncoder.getDistance())) ``` @@ -139,21 +139,21 @@ Cosine compensation has been shown to reduce the amount of "skew" a swerve drive .. tab-set-code:: ```java var currentAngle = new Rotation2d.fromRadians(m_turningEncoder.getDistance()); - var frontLeftOptimized = SwerveModuleState.optimize(frontLeft, currentAngle); + var frontLeftOptimized = SwerveModuleState.optimize(frontLeft, currentAngle); frontLeftOptimized.speedMetersPerSecond *= frontLeftOptimized.angle.minus(currentAngle).getCos(); ``` ```c++ Rotation2d currentAngle(m_turningEncoder.GetDistance()); - auto flOptimized = frc::SwerveModuleState::Optimize(fl, currentAngle); + auto flOptimized = frc::SwerveModuleState::Optimize(fl, currentAngle); flOptimized.speed *= (flOptimized.angle - currentAngle).Cos(); ``` ```python from wpimath.kinematics import SwerveModuleState from wpimath.geometry import Rotation2d - currentAngle = Rotation2d(self.m_turningEncoder.getDistance()) - frontLeftOptimized = SwerveModuleState.optimize(frontLeft, currentAngle) + currentAngle = Rotation2d(self.m_turningEncoder.getDistance()) + frontLeftOptimized = SwerveModuleState.optimize(frontLeft, currentAngle) frontLeftOptimized.speed *= (frontLeftOptimized.angle - currentAngle).cos() ``` @@ -170,7 +170,7 @@ Cosine compensation has been shown to reduce the amount of "skew" a swerve drive // robot angle is 45 degrees. ChassisSpeeds speeds = ChassisSpeeds.fromFieldRelativeSpeeds( 2.0, 2.0, Math.PI / 2.0, Rotation2d.fromDegrees(45.0)); - // Now use this in our kinematics + // Now use this in our kinematics SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(speeds); ``` @@ -182,7 +182,7 @@ Cosine compensation has been shown to reduce the amount of "skew" a swerve drive // robot angle is 45 degrees. frc::ChassisSpeeds speeds = frc::ChassisSpeeds::FromFieldRelativeSpeeds( 2_mps, 2_mps, units::radians_per_second_t(std::numbers::pi / 2.0), Rotation2d(45_deg)); - // Now use this in our kinematics + // Now use this in our kinematics auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(speeds); ``` @@ -190,14 +190,14 @@ Cosine compensation has been shown to reduce the amount of "skew" a swerve drive from wpimath.kinematics import ChassisSpeeds import math from wpimath.geometry import Rotation2d - # The desired field relative speed here is 2 meters per second + # The desired field relative speed here is 2 meters per second # toward the opponent's alliance station wall, and 2 meters per # second toward the left field boundary. The desired rotation # is a quarter of a rotation per second counterclockwise. The current # robot angle is 45 degrees. speeds = ChassisSpeeds.fromFieldRelativeSpeeds( 2.0, 2.0, math.pi / 2.0, Rotation2d.fromDegrees(45.0)) - # Now use this in our kinematics + # Now use this in our kinematics self.moduleStates = self.kinematics.toSwerveModuleStates(speeds) ``` @@ -219,10 +219,10 @@ One can also use the kinematics object to convert an array of ``SwerveModuleStat var frontRightState = new SwerveModuleState(23.43, Rotation2d.fromDegrees(-39.81)); var backLeftState = new SwerveModuleState(54.08, Rotation2d.fromDegrees(-109.44)); var backRightState = new SwerveModuleState(54.08, Rotation2d.fromDegrees(-70.56)); - // Convert to chassis speeds + // Convert to chassis speeds ChassisSpeeds chassisSpeeds = kinematics.toChassisSpeeds( frontLeftState, frontRightState, backLeftState, backRightState); - // Getting individual speeds + // Getting individual speeds double forward = chassisSpeeds.vxMetersPerSecond; double sideways = chassisSpeeds.vyMetersPerSecond; double angular = chassisSpeeds.omegaRadiansPerSecond; @@ -234,7 +234,7 @@ One can also use the kinematics object to convert an array of ``SwerveModuleStat frc::SwerveModuleState frontRightState{23.43_mps, Rotation2d(-39.81_deg)}; frc::SwerveModuleState backLeftState{54.08_mps, Rotation2d(-109.44_deg)}; frc::SwerveModuleState backRightState{54.08_mps, Rotation2d(-70.56_deg)}; - // Convert to chassis speeds. Here, we can use C++17's structured bindings + // Convert to chassis speeds. Here, we can use C++17's structured bindings // feature to automatically break up the ChassisSpeeds struct into its // three components. auto [forward, sideways, angular] = kinematics.ToChassisSpeeds( @@ -244,15 +244,15 @@ One can also use the kinematics object to convert an array of ``SwerveModuleStat ```python from wpimath.kinematics import SwerveModuleState from wpimath.geometry import Rotation2d - # Example module states + # Example module states frontLeftState = SwerveModuleState(23.43, Rotation2d.fromDegrees(-140.19)) frontRightState = SwerveModuleState(23.43, Rotation2d.fromDegrees(-39.81)) backLeftState = SwerveModuleState(54.08, Rotation2d.fromDegrees(-109.44)) backRightState = SwerveModuleState(54.08, Rotation2d.fromDegrees(-70.56)) - # Convert to chassis speeds + # Convert to chassis speeds chassisSpeeds = self.kinematics.toChassisSpeeds( frontLeftState, frontRightState, backLeftState, backRightState) - # Getting individual speeds + # Getting individual speeds forward = chassisSpeeds.vx sideways = chassisSpeeds.vy angular = chassisSpeeds.omega @@ -266,12 +266,12 @@ By recording a set of swerve module states using :ref:`NetworkTables publisher; - public Example() { + public Example() { // Start publishing an array of module states with the "/SwerveStates" key publisher = NetworkTableInstance.getDefault() .getStructArrayTopic("/SwerveStates", SwerveModuleState.struct).publish(); } - public void periodic() { + public void periodic() { // Periodically send a set of module states publisher.set(new SwerveModuleState[] { frontLeftState, @@ -286,13 +286,13 @@ By recording a set of swerve module states using :ref:`NetworkTables publisher - public: + public: Example() { // Start publishing an array of module states with the "/SwerveStates" key publisher = nt::NetworkTableInstance::GetDefault() .GetStructArrayTopic("/SwerveStates").Publish(); } - void Periodic() { + void Periodic() { // Periodically send a set of module states swervePublisher.Set( std::vector{ @@ -309,12 +309,12 @@ By recording a set of swerve module states using :ref:`NetworkTables m_kinematics{ m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation }; - // Creating my odometry object from the kinematics object. Here, + // Creating my odometry object from the kinematics object. Here, // our starting pose is 5 meters along the long end of the field and in the // center of the field along the short end, facing forward. frc::SwerveDriveOdometry<4> m_odometry{m_kinematics, m_gyro.GetRotation2d(), @@ -64,23 +64,23 @@ The fourth optional argument is the starting pose of your robot on the field (as ```python # Python requires using the right class for the number of modules you have # For both the Kinematics and Odometry classes - from wpimath.geometry import Translation2d + from wpimath.geometry import Translation2d from wpimath.kinematics import SwerveDrive4Kinematics from wpimath.kinematics import SwerveDrive4Odometry from wpimath.geometry import Pose2d from wpimath.geometry import Rotation2d - class MyRobot: + class MyRobot: def robotInit(self): # Locations for the swerve drive modules relative to the robot center. frontLeftLocation = Translation2d(0.381, 0.381) frontRightLocation = Translation2d(0.381, -0.381) backLeftLocation = Translation2d(-0.381, 0.381) backRightLocation = Translation2d(-0.381, -0.381) - # Creating my kinematics object using the module locations + # Creating my kinematics object using the module locations self.kinematics = SwerveDrive4Kinematics( frontLeftLocation, frontRightLocation, backLeftLocation, backRightLocation ) - # Creating my odometry object from the kinematics object and the initial wheel positions. + # Creating my odometry object from the kinematics object and the initial wheel positions. # Here, our starting pose is 5 meters along the long end of the field and in the # center of the field along the short end, facing the opposing alliance wall. self.odometry = SwerveDrive4Odometry( @@ -106,7 +106,7 @@ This ``update`` method must be called periodically, preferably in the ``periodic public void periodic() { // Get the rotation of the robot from the gyro. var gyroAngle = m_gyro.getRotation2d(); - // Update the pose + // Update the pose m_pose = m_odometry.update(gyroAngle, new SwerveModulePosition[] { m_frontLeftModule.getPosition(), m_frontRightModule.getPosition(), @@ -119,7 +119,7 @@ This ``update`` method must be called periodically, preferably in the ``periodic void Periodic() override { // Get the rotation of the robot from the gyro. frc::Rotation2d gyroAngle = m_gyro.GetRotation2d(); - // Update the pose + // Update the pose m_pose = m_odometry.Update(gyroAngle, { m_frontLeftModule.GetPosition(), m_frontRightModule.GetPosition(), @@ -133,7 +133,7 @@ This ``update`` method must be called periodically, preferably in the ``periodic def periodic(self): # Get the rotation of the robot from the gyro. self.gyroAngle = self.gyro.getRotation2d() - # Update the pose + # Update the pose self.pose = self.odometry.update(self.gyroAngle, self.frontLeftModule.getPosition(), self.frontRightModule.getPosition(), self.backLeftModule.getPosition(), self.backRightModule.getPosition() diff --git a/source/docs/software/networktables/client-side-program.rst b/source/docs/software/networktables/client-side-program.rst index 321810c6fb..1a781eb848 100644 --- a/source/docs/software/networktables/client-side-program.rst +++ b/source/docs/software/networktables/client-side-program.rst @@ -17,21 +17,21 @@ A basic client program looks like the following example. import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.networktables.NetworkTablesJNI; import edu.wpi.first.util.CombinedRuntimeLoader; - import java.io.IOException; - import edu.wpi.first.cscore.CameraServerJNI; + import java.io.IOException; + import edu.wpi.first.cscore.CameraServerJNI; import edu.wpi.first.math.WPIMathJNI; import edu.wpi.first.util.WPIUtilJNI; - public class Program { + public class Program { public static void main(String[] args) throws IOException { NetworkTablesJNI.Helper.setExtractOnStaticLoad(false); WPIUtilJNI.Helper.setExtractOnStaticLoad(false); WPIMathJNI.Helper.setExtractOnStaticLoad(false); CameraServerJNI.Helper.setExtractOnStaticLoad(false); - CombinedRuntimeLoader.loadLibraries(Program.class, "wpiutiljni", "wpimathjni", "ntcorejni", - "cscorejnicvstatic"); + CombinedRuntimeLoader.loadLibraries(Program.class, "wpiutiljni", "wpimathjni", "ntcorejni", + "cscorejnicvstatic"); new Program().run(); } - public void run() { + public void run() { NetworkTableInstance inst = NetworkTableInstance.getDefault(); NetworkTable table = inst.getTable("datatable"); DoubleSubscriber xSub = table.getDoubleTopic("x").subscribe(0.0); @@ -64,7 +64,7 @@ A basic client program looks like the following example. #include #include #include - int main() { + int main() { auto inst = nt::NetworkTableInstance::GetDefault(); auto table = inst.GetTable("datatable"); auto xSub = table->GetDoubleTopic("x").Subscribe(0.0); @@ -90,7 +90,7 @@ A basic client program looks like the following example. #include #include #include - int main() { + int main() { NT_Inst inst = nt::GetDefaultInstance(); NT_Subscriber xSub = nt::Subscribe(nt::GetTopic(inst, "/datatable/x"), NT_DOUBLE, "double"); @@ -117,7 +117,7 @@ A basic client program looks like the following example. #include #include #include - int main() { + int main() { NT_Instance inst = NT_GetDefaultInstance(); NT_Subscriber xSub = NT_Subscribe(NT_GetTopic(inst, "/datatable/x"), NT_DOUBLE, "double", NULL, 0); @@ -141,9 +141,9 @@ A basic client program looks like the following example. ```python #!/usr/bin/env python3 - import ntcore + import ntcore import time - if __name__ == "__main__": + if __name__ == "__main__": inst = ntcore.NetworkTableInstance.getDefault() table = inst.getTable("datatable") xSub = table.getDoubleTopic("x").subscribe(0) @@ -151,12 +151,12 @@ A basic client program looks like the following example. inst.startClient4("example client") inst.setServerTeam(TEAM) # where TEAM=190, 294, etc, or use inst.setServer("hostname") or similar inst.startDSClient() # recommended if running on DS computer; this gets the robot IP from the DS - while True: + while True: time.sleep(1) - x = xSub.get() + x = xSub.get() y = ySub.get() print(f"X: {x} Y: {y}") - ``` + ``` In this example an instance of NetworkTables is created and subscribers are created to reference the values of "x" and "y" from a table called "datatable". diff --git a/source/docs/software/networktables/listening-for-change.rst b/source/docs/software/networktables/listening-for-change.rst index dac964b8ee..82181e2c62 100644 --- a/source/docs/software/networktables/listening-for-change.rst +++ b/source/docs/software/networktables/listening-for-change.rst @@ -13,33 +13,33 @@ There are a few different ways to detect that a topic's value has changed; the e public class Example { final DoubleSubscriber ySub; double prev; - public Example() { + public Example() { // get the default instance of NetworkTables NetworkTableInstance inst = NetworkTableInstance.getDefault(); - // get the subtable called "datatable" + // get the subtable called "datatable" NetworkTable datatable = inst.getTable("datatable"); - // subscribe to the topic in "datatable" called "Y" + // subscribe to the topic in "datatable" called "Y" ySub = datatable.getDoubleTopic("Y").subscribe(0.0); } - public void periodic() { + public void periodic() { // get() can be used with simple change detection to the previous value double value = ySub.get(); if (value != prev) { prev = value; // save previous value System.out.println("X changed value: " + value); } - // readQueueValues() provides all value changes since the last call; + // readQueueValues() provides all value changes since the last call; // this way it's not possible to miss a change by polling too slowly for (double iterVal : ySub.readQueueValues()) { System.out.println("X changed value: " + iterVal); } - // readQueue() is similar to readQueueValues(), but provides timestamps + // readQueue() is similar to readQueueValues(), but provides timestamps // for each change as well for (TimestampedDouble tsValue : ySub.readQueue()) { System.out.println("X changed value: " + tsValue.value + " at local time " + tsValue.timestamp); } } - // may not be necessary for robot programs if this class lives for + // may not be necessary for robot programs if this class lives for // the length of the program public void close() { ySub.close(); @@ -54,28 +54,28 @@ There are a few different ways to detect that a topic's value has changed; the e class Example { nt::DoubleSubscriber ySub; double prev = 0; - public: + public: Example() { // get the default instance of NetworkTables nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); - // get the subtable called "datatable" + // get the subtable called "datatable" auto datatable = inst.GetTable("datatable"); - // subscribe to the topic in "datatable" called "Y" + // subscribe to the topic in "datatable" called "Y" ySub = datatable->GetDoubleTopic("Y").Subscribe(0.0); } - void Periodic() { + void Periodic() { // Get() can be used with simple change detection to the previous value double value = ySub.Get(); if (value != prev) { prev = value; // save previous value fmt::print("X changed value: {}\n", value); } - // ReadQueueValues() provides all value changes since the last call; + // ReadQueueValues() provides all value changes since the last call; // this way it's not possible to miss a change by polling too slowly for (double iterVal : ySub.ReadQueueValues()) { fmt::print("X changed value: {}\n", iterVal); } - // ReadQueue() is similar to ReadQueueValues(), but provides timestamps + // ReadQueue() is similar to ReadQueueValues(), but provides timestamps // for each change as well for (nt::TimestampedDouble tsValue : ySub.ReadQueue()) { fmt::print("X changed value: {} at local time {}\n", tsValue.value, tsValue.timestamp); @@ -91,21 +91,21 @@ There are a few different ways to detect that a topic's value has changed; the e class Example { NT_Subscriber ySub; double prev = 0; - public: + public: Example() { // get the default instance of NetworkTables NT_Inst inst = nt::GetDefaultInstance(); - // subscribe to the topic in "datatable" called "Y" + // subscribe to the topic in "datatable" called "Y" ySub = nt::Subscribe(nt::GetTopic(inst, "/datatable/Y"), NT_DOUBLE, "double"); } - void Periodic() { + void Periodic() { // Get() can be used with simple change detection to the previous value double value = nt::GetDouble(ySub, 0.0); if (value != prev) { prev = value; // save previous value fmt::print("X changed value: {}\n", value); } - // ReadQueue() provides all value changes since the last call; + // ReadQueue() provides all value changes since the last call; // this way it's not possible to miss a change by polling too slowly for (nt::TimestampedDouble value : nt::ReadQueueDouble(ySub)) { fmt::print("X changed value: {} at local time {}\n", tsValue.value, tsValue.timestamp); @@ -121,21 +121,21 @@ There are a few different ways to detect that a topic's value has changed; the e ```python class Example: def __init__(self) -> None: - # get the default instance of NetworkTables + # get the default instance of NetworkTables inst = ntcore.NetworkTableInstance.getDefault() - # get the subtable called "datatable" + # get the subtable called "datatable" datatable = inst.getTable("datatable") - # subscribe to the topic in "datatable" called "Y" + # subscribe to the topic in "datatable" called "Y" self.ySub = datatable.getDoubleTopic("Y").subscribe(0.0) - self.prev = 0 - def periodic(self): + self.prev = 0 + def periodic(self): # get() can be used with simple change detection to the previous value value = self.ySub.get() if value != self.prev: self.prev = value # save previous value print("X changed value: " + value) - # readQueue() provides all value changes since the last call; + # readQueue() provides all value changes since the last call; # this way it's not possible to miss a change by polling too slowly for tsValue in self.ySub.readQueue(): print(f"X changed value: {tsValue.value} at local time {tsValue.time}") @@ -177,10 +177,10 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. int connListenerHandle; int valueListenerHandle; int topicListenerHandle; - public Example() { + public Example() { // get the default instance of NetworkTables NetworkTableInstance inst = NetworkTableInstance.getDefault(); - // add a connection listener; the first parameter will cause the + // add a connection listener; the first parameter will cause the // callback to be called immediately for any current connections connListenerHandle = inst.addConnectionListener(true, event -> { if (event.is(NetworkTableEvent.Kind.kConnected)) { @@ -189,11 +189,11 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. System.out.println("Disconnected from " + event.connInfo.remote_id); } }); - // get the subtable called "datatable" + // get the subtable called "datatable" NetworkTable datatable = inst.getTable("datatable"); - // subscribe to the topic in "datatable" called "Y" + // subscribe to the topic in "datatable" called "Y" ySub = datatable.getDoubleTopic("Y").subscribe(0.0); - // add a listener to only value changes on the Y subscriber + // add a listener to only value changes on the Y subscriber valueListenerHandle = inst.addListener( ySub, EnumSet.of(NetworkTableEvent.Kind.kValueAll), @@ -202,7 +202,7 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. // could check value.isDouble() here too yValue.set(event.valueData.value.getDouble()); }); - // add a listener to see when new topics are published within datatable + // add a listener to see when new topics are published within datatable // the string array is an array of topic name prefixes. topicListenerHandle = inst.addListener( new String[] { datatable.getPath() + "/" }, @@ -214,7 +214,7 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. } }); } - public void periodic() { + public void periodic() { // get the latest value by reading the AtomicReference; set it to null // when we read to ensure we only get value changes Double value = yValue.getAndSet(null); @@ -222,7 +222,7 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. System.out.println("got new value " + value); } } - // may not be needed for robot programs if this class exists for the + // may not be needed for robot programs if this class exists for the // lifetime of the program public void close() { NetworkTableInstance inst = NetworkTableInstance.getDefault(); @@ -248,11 +248,11 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. NT_Listener connListenerHandle; NT_Listener valueListenerHandle; NT_Listener topicListenerHandle; - public: + public: Example() { // get the default instance of NetworkTables nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); - // add a connection listener; the first parameter will cause the + // add a connection listener; the first parameter will cause the // callback to be called immediately for any current connections connListenerHandle = inst.AddConnectionListener(true, [] (const nt::Event& event) { if (event.Is(nt::EventFlags::kConnected)) { @@ -261,11 +261,11 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. fmt::print("Disconnected from {}\n", event.GetConnectionInfo()->remote_id); } }); - // get the subtable called "datatable" + // get the subtable called "datatable" auto datatable = inst.GetTable("datatable"); - // subscribe to the topic in "datatable" called "Y" + // subscribe to the topic in "datatable" called "Y" ySub = datatable.GetDoubleTopic("Y").Subscribe(0.0); - // add a listener to only value changes on the Y subscriber + // add a listener to only value changes on the Y subscriber valueListenerHandle = inst.AddListener( ySub, nt::EventFlags::kValueAll, @@ -276,7 +276,7 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. yValue = event.GetValueData()->value.GetDouble(); yValueUpdated = true; }); - // add a listener to see when new topics are published within datatable + // add a listener to see when new topics are published within datatable // the string array is an array of topic name prefixes. topicListenerHandle = inst.AddListener( {{fmt::format("{}/", datatable->GetPath())}}, @@ -288,7 +288,7 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. } }); } - void Periodic() { + void Periodic() { // get the latest value by reading the value; set it to false // when we read to ensure we only get value changes wpi::scoped_lock lock{mutex}; @@ -297,7 +297,7 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. fmt::print("got new value {}\n", yValue); } } - ~Example() { + ~Example() { nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); inst.RemoveListener(connListenerHandle); inst.RemoveListener(valueListenerHandle); @@ -313,14 +313,14 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. ```python import ntcore import threading - class Example: + class Example: def __init__(self) -> None: - # get the default instance of NetworkTables + # get the default instance of NetworkTables inst = ntcore.NetworkTableInstance.getDefault() - # Use a mutex to ensure thread safety + # Use a mutex to ensure thread safety self.lock = threading.Lock() self.yValue = None - # add a connection listener; the first parameter will cause the + # add a connection listener; the first parameter will cause the # callback to be called immediately for any current connections def _connect_cb(event: ntcore.Event): if event.is_(ntcore.EventFlags.kConnected): @@ -328,11 +328,11 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. elif event.is_(ntcore.EventFlags.kDisconnected): print("Disconnected from", event.data.remote_id) self.connListenerHandle = inst.addConnectionListener(True, _connect_cb) - # get the subtable called "datatable" + # get the subtable called "datatable" datatable = inst.getTable("datatable") - # subscribe to the topic in "datatable" called "Y" + # subscribe to the topic in "datatable" called "Y" self.ySub = datatable.getDoubleTopic("Y").subscribe(0.0) - # add a listener to only value changes on the Y subscriber + # add a listener to only value changes on the Y subscriber def _on_ysub(event: ntcore.Event): # can only get doubles because it's a DoubleSubscriber, but # could check value.isDouble() here too @@ -341,7 +341,7 @@ The ``addListener`` functions in NetworkTableInstance return a listener handle. self.valueListenerHandle = inst.addListener( self.ySub, ntcore.EventFlags.kValueAll, _on_ysub ) - # add a listener to see when new topics are published within datatable + # add a listener to see when new topics are published within datatable # the string array is an array of topic name prefixes. def _on_pub(event: ntcore.Event): if event.is_(ntcore.EventFlags.kPublish): diff --git a/source/docs/software/networktables/multiple-instances.rst b/source/docs/software/networktables/multiple-instances.rst index 71a80db937..614b7fb2e6 100644 --- a/source/docs/software/networktables/multiple-instances.rst +++ b/source/docs/software/networktables/multiple-instances.rst @@ -18,9 +18,9 @@ Destroying a NetworkTableInstance frees all resources related to the instance. A ```java // get the default NetworkTable instance NetworkTableInstance defaultInst = NetworkTableInstance.getDefault(); - // create a NetworkTable instance + // create a NetworkTable instance NetworkTableInstance inst = NetworkTableInstance.create(); - // destroy a NetworkTable instance + // destroy a NetworkTable instance inst.close(); ``` @@ -30,9 +30,9 @@ Destroying a NetworkTableInstance frees all resources related to the instance. A ```c++ // get the default NetworkTable instance nt::NetworkTableInstance defaultInst = nt::NetworkTableInstance::GetDefault(); - // create a NetworkTable instance + // create a NetworkTable instance nt::NetworkTableInstance inst = nt::NetworkTableInstance::Create(); - // destroy a NetworkTable instance; NetworkTableInstance objects are not RAII + // destroy a NetworkTable instance; NetworkTableInstance objects are not RAII nt::NetworkTableInstance::Destroy(inst); ``` @@ -42,9 +42,9 @@ Destroying a NetworkTableInstance frees all resources related to the instance. A ```c++ // get the default NetworkTable instance NT_Instance defaultInst = nt::GetDefaultInstance(); - // create a NetworkTable instance + // create a NetworkTable instance NT_Instance inst = nt::CreateInstance(); - // destroy a NetworkTable instance + // destroy a NetworkTable instance nt::DestroyInstance(inst); ``` @@ -54,9 +54,9 @@ Destroying a NetworkTableInstance frees all resources related to the instance. A ```c // get the default NetworkTable instance NT_Instance defaultInst = NT_GetDefaultInstance(); - // create a NetworkTable instance + // create a NetworkTable instance NT_Instance inst = NT_CreateInstance(); - // destroy a NetworkTable instance + // destroy a NetworkTable instance NT_DestroyInstance(inst); ``` @@ -66,11 +66,11 @@ Destroying a NetworkTableInstance frees all resources related to the instance. A ```python import ntcore - # get the default NetworkTable instance + # get the default NetworkTable instance defaultInst = ntcore.NetworkTableInstance.getDefault() - # create a NetworkTable instance + # create a NetworkTable instance inst = ntcore.NetworkTableInstance.create() - # destroy a NetworkTable instance + # destroy a NetworkTable instance ntcore.NetworkTableInstance.destroy(inst) ``` diff --git a/source/docs/software/networktables/networktables-networking.rst b/source/docs/software/networktables/networktables-networking.rst index e99555d18e..67aa39ec83 100644 --- a/source/docs/software/networktables/networktables-networking.rst +++ b/source/docs/software/networktables/networktables-networking.rst @@ -44,9 +44,9 @@ The advantage of the robot program being the server is that it's at a known netw ```python import ntcore - inst = ntcore.NetworkTableInstance.getDefault() + inst = ntcore.NetworkTableInstance.getDefault() inst.startServer() - ``` + ``` ## Starting a NetworkTables Client @@ -57,13 +57,13 @@ The advantage of the robot program being the server is that it's at a known netw ```java NetworkTableInstance inst = NetworkTableInstance.getDefault(); - // start a NT4 client + // start a NT4 client inst.startClient4("example client"); - // connect to a roboRIO with team number TEAM + // connect to a roboRIO with team number TEAM inst.setServerTeam(TEAM); - // starting a DS client will try to get the roboRIO address from the DS application + // starting a DS client will try to get the roboRIO address from the DS application inst.startDSClient(); - // connect to a specific host/port + // connect to a specific host/port inst.setServer("host", NetworkTableInstance.kDefaultPort4) ``` @@ -72,13 +72,13 @@ The advantage of the robot program being the server is that it's at a known netw ```c++ nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); - // start a NT4 client + // start a NT4 client inst.StartClient4("example client"); - // connect to a roboRIO with team number TEAM + // connect to a roboRIO with team number TEAM inst.SetServerTeam(TEAM); - // starting a DS client will try to get the roboRIO address from the DS application + // starting a DS client will try to get the roboRIO address from the DS application inst.StartDSClient(); - // connect to a specific host/port + // connect to a specific host/port inst.SetServer("host", NT_DEFAULT_PORT4) ``` @@ -87,13 +87,13 @@ The advantage of the robot program being the server is that it's at a known netw ```c++ NT_Inst inst = nt::GetDefaultInstance(); - // start a NT4 client + // start a NT4 client nt::StartClient4(inst, "example client"); - // connect to a roboRIO with team number TEAM + // connect to a roboRIO with team number TEAM nt::SetServerTeam(inst, TEAM); - // starting a DS client will try to get the roboRIO address from the DS application + // starting a DS client will try to get the roboRIO address from the DS application nt::StartDSClient(inst); - // connect to a specific host/port + // connect to a specific host/port nt::SetServer(inst, "host", NT_DEFAULT_PORT4) ``` @@ -102,13 +102,13 @@ The advantage of the robot program being the server is that it's at a known netw ```c NT_Inst inst = NT_GetDefaultInstance(); - // start a NT4 client + // start a NT4 client NT_StartClient4(inst, "example client"); - // connect to a roboRIO with team number TEAM + // connect to a roboRIO with team number TEAM NT_SetServerTeam(inst, TEAM); - // starting a DS client will try to get the roboRIO address from the DS application + // starting a DS client will try to get the roboRIO address from the DS application NT_StartDSClient(inst); - // connect to a specific host/port + // connect to a specific host/port NT_SetServer(inst, "host", NT_DEFAULT_PORT4) ``` @@ -118,14 +118,14 @@ The advantage of the robot program being the server is that it's at a known netw ```python import ntcore - inst = ntcore.NetworkTableInstance.getDefault() - # start a NT4 client + inst = ntcore.NetworkTableInstance.getDefault() + # start a NT4 client inst.startClient4("example client") - # connect to a roboRIO with team number TEAM + # connect to a roboRIO with team number TEAM inst.setServerTeam(TEAM) - # starting a DS client will try to get the roboRIO address from the DS application + # starting a DS client will try to get the roboRIO address from the DS application inst.startDSClient() - # connect to a specific host/port + # connect to a specific host/port inst.setServer("host", ntcore.NetworkTableInstance.kDefaultPort4) ``` diff --git a/source/docs/software/networktables/nt4-migration-guide.rst b/source/docs/software/networktables/nt4-migration-guide.rst index 4be0d0c372..b4adc26f9e 100644 --- a/source/docs/software/networktables/nt4-migration-guide.rst +++ b/source/docs/software/networktables/nt4-migration-guide.rst @@ -14,60 +14,60 @@ NT3 code (was): public class Example { final NetworkTableEntry yEntry; final NetworkTableEntry outEntry; - public Example() { + public Example() { NetworkTableInstance inst = NetworkTableInstance.getDefault(); - // get the subtable called "datatable" + // get the subtable called "datatable" NetworkTable datatable = inst.getTable("datatable"); - // get the entry in "datatable" called "Y" + // get the entry in "datatable" called "Y" yEntry = datatable.getEntry("Y"); - // get the entry in "datatable" called "Out" + // get the entry in "datatable" called "Out" outEntry = datatable.getEntry("Out"); } - public void periodic() { + 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); } } - ``` + ``` ```c++ class Example { nt::NetworkTableEntry yEntry; nt::NetworkTableEntry outEntry; - public: + public: Example() { nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); - // get the subtable called "datatable" + // get the subtable called "datatable" auto datatable = inst.GetTable("datatable"); - // get the entry in "datatable" called "Y" + // get the entry in "datatable" called "Y" yEntry = datatable->GetEntry("Y"); - // get the entry in "datatable" called "Out" + // get the entry in "datatable" called "Out" outEntry = datatable->GetEntry("Out"); } - void Periodic() { + 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); } }; - ``` + ``` ```python class Example: def __init__(self): inst = ntcore.NetworkTableInstance.getDefault() - # get the subtable called "datatable" + # get the subtable called "datatable" datatable = inst.getTable("datatable") - # get the entry in "datatable" called "Y" + # get the entry in "datatable" called "Y" self.yEntry = datatable.getEntry("Y") - # get the entry in "datatable" called "Out" + # get the entry in "datatable" called "Out" self.outEntry = datatable.getEntry("Out") - def periodic(self): + 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): @@ -77,22 +77,22 @@ Recommended NT4 equivalent (should be): public class Example { final DoubleSubscriber ySub; final DoublePublisher outPub; - public Example() { + public Example() { NetworkTableInstance inst = NetworkTableInstance.getDefault(); - // get the subtable called "datatable" + // get the subtable called "datatable" NetworkTable datatable = inst.getTable("datatable"); - // subscribe to the topic in "datatable" called "Y" + // 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" + // publish to the topic in "datatable" called "Out" outPub = datatable.getDoubleTopic("Out").publish(); } - public void periodic() { + 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 + // 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() { @@ -100,47 +100,47 @@ Recommended NT4 equivalent (should be): outPub.close(); } } - ``` + ``` ```c++ class Example { nt::DoubleSubscriber ySub; nt::DoublePublisher outPub; - public: + public: Example() { nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); - // get the subtable called "datatable" + // get the subtable called "datatable" auto datatable = inst.GetTable("datatable"); - // subscribe to the topic in "datatable" called "Y" + // 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" + // publish to the topic in "datatable" called "Out" outPub = datatable->GetDoubleTopic("Out").Publish(); } - void Periodic() { + 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); } }; - ``` + ``` ```python class Example: def __init__(self) -> None: inst = ntcore.NetworkTableInstance.getDefault() - # get the subtable called "datatable" + # get the subtable called "datatable" datatable = inst.getTable("datatable") - # subscribe to the topic in "datatable" called "Y" + # 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" + # publish to the topic in "datatable" called "Out" self.outPub = datatable.getDoubleTopic("Out").publish() - def periodic(self): + 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 + # 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): diff --git a/source/docs/software/networktables/publish-and-subscribe.rst b/source/docs/software/networktables/publish-and-subscribe.rst index bcd62e81ac..d5396ae040 100644 --- a/source/docs/software/networktables/publish-and-subscribe.rst +++ b/source/docs/software/networktables/publish-and-subscribe.rst @@ -19,34 +19,34 @@ Publishing values is done via a ``set()`` operation. By default, this operation public class Example { // the publisher is an instance variable so its lifetime matches that of the class final DoublePublisher dblPub; - public Example(DoubleTopic dblTopic) { + public Example(DoubleTopic dblTopic) { // start publishing; the return value must be retained (in this case, via // an instance variable) dblPub = dblTopic.publish(); - // publish options may be specified using PubSubOption + // publish options may be specified using PubSubOption dblPub = dblTopic.publish(PubSubOption.keepDuplicates(true)); - // publishEx provides additional options such as setting initial + // publishEx provides additional options such as setting initial // properties and using a custom type string. Using a custom type string for // types other than raw and string is not recommended. The properties string // must be a JSON map. dblPub = dblTopic.publishEx("double", "{\"myprop\": 5}"); } - public void periodic() { + public void periodic() { // publish a default value dblPub.setDefault(0.0); - // publish a value with current timestamp + // publish a value with current timestamp dblPub.set(1.0); dblPub.set(2.0, 0); // 0 = use current time - // publish a value with a specific timestamp; NetworkTablesJNI.now() can + // publish a value with a specific timestamp; NetworkTablesJNI.now() can // be used to get the current time. On the roboRIO, this is the same as // the FPGA timestamp (e.g. RobotController.getFPGATime()) long time = NetworkTablesJNI.now(); dblPub.set(3.0, time); - // publishers also implement the appropriate Consumer functional interface; + // publishers also implement the appropriate Consumer functional interface; // this example assumes void myFunc(DoubleConsumer func) exists myFunc(dblPub); } - // often not required in robot code, unless this class doesn't exist for + // 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 publishing public void close() { @@ -64,26 +64,26 @@ Publishing values is done via a ``set()`` operation. By default, this operation // the publisher is an instance variable so its lifetime matches that of the class // publishing is automatically stopped when dblPub is destroyed by the class destructor nt::DoublePublisher dblPub; - public: + public: explicit Example(nt::DoubleTopic dblTopic) { // start publishing; the return value must be retained (in this case, via // an instance variable) dblPub = dblTopic.Publish(); - // publish options may be specified using PubSubOptions + // publish options may be specified using PubSubOptions dblPub = dblTopic.Publish({.keepDuplicates = true}); - // PublishEx provides additional options such as setting initial + // PublishEx provides additional options such as setting initial // properties and using a custom type string. Using a custom type string for // types other than raw and string is not recommended. The properties must // be a JSON map. dblPub = dblTopic.PublishEx("double", {{"myprop", 5}}); } - void Periodic() { + void Periodic() { // publish a default value dblPub.SetDefault(0.0); - // publish a value with current timestamp + // publish a value with current timestamp dblPub.Set(1.0); dblPub.Set(2.0, 0); // 0 = use current time - // publish a value with a specific timestamp; nt::Now() can + // publish a value with a specific timestamp; nt::Now() can // be used to get the current time. int64_t time = nt::Now(); dblPub.Set(3.0, time); @@ -99,30 +99,30 @@ Publishing values is done via a ``set()`` operation. By default, this operation // the publisher is an instance variable, but since it's a handle, it's // not automatically released, so we need a destructor NT_Publisher dblPub; - public: + public: explicit Example(NT_Topic dblTopic) { // start publishing. It's recommended that the type string be standard // for all types except string and raw. dblPub = nt::Publish(dblTopic, NT_DOUBLE, "double"); - // publish options may be specified using PubSubOptions + // publish options may be specified using PubSubOptions dblPub = nt::Publish(dblTopic, NT_DOUBLE, "double", {.keepDuplicates = true}); - // PublishEx allows setting initial properties. The + // PublishEx allows setting initial properties. The // properties must be a JSON map. dblPub = nt::PublishEx(dblTopic, NT_DOUBLE, "double", {{"myprop", 5}}); } - void Periodic() { + void Periodic() { // publish a default value nt::SetDefaultDouble(dblPub, 0.0); - // publish a value with current timestamp + // publish a value with current timestamp nt::SetDouble(dblPub, 1.0); nt::SetDouble(dblPub, 2.0, 0); // 0 = use current time - // publish a value with a specific timestamp; nt::Now() can + // publish a value with a specific timestamp; nt::Now() can // be used to get the current time. int64_t time = nt::Now(); nt::SetDouble(dblPub, 3.0, time); } - ~Example() { + ~Example() { // stop publishing nt::Unpublish(dblPub); } @@ -134,29 +134,29 @@ Publishing values is done via a ``set()`` operation. By default, this operation ```c // This code assumes that a NT_Topic dblTopic variable already exists - // start publishing. It's recommended that the type string be standard + // start publishing. It's recommended that the type string be standard // for all types except string and raw. NT_Publisher dblPub = NT_Publish(dblTopic, NT_DOUBLE, "double", NULL, 0); - // publish options may be specified + // publish options may be specified struct NT_PubSubOptions options; memset(&options, 0, sizeof(options)); options.structSize = sizeof(options); options.keepDuplicates = 1; // true NT_Publisher dblPub = NT_Publish(dblTopic, NT_DOUBLE, "double", &options); - // PublishEx allows setting initial properties. The properties string must + // PublishEx allows setting initial properties. The properties string must // be a JSON map. NT_Publisher dblPub = NT_PublishEx(dblTopic, NT_DOUBLE, "double", "{\"myprop\", 5}", NULL, 0); - // publish a default value + // publish a default value NT_SetDefaultDouble(dblPub, 0.0); - // publish a value with current timestamp + // publish a value with current timestamp NT_SetDouble(dblPub, 1.0); NT_SetDouble(dblPub, 2.0, 0); // 0 = use current time - // publish a value with a specific timestamp; NT_Now() can + // publish a value with a specific timestamp; NT_Now() can // be used to get the current time. int64_t time = NT_Now(); NT_SetDouble(dblPub, 3.0, time); - // stop publishing + // stop publishing NT_Unpublish(dblPub); ``` @@ -167,33 +167,33 @@ Publishing values is done via a ``set()`` operation. By default, this operation ```python class Example: def __init__(self, dblTopic: ntcore.DoubleTopic): - # start publishing; the return value must be retained (in this case, via + # start publishing; the return value must be retained (in this case, via # an instance variable) self.dblPub = dblTopic.publish() - # publish options may be specified using PubSubOption + # publish options may be specified using PubSubOption self.dblPub = dblTopic.publish(ntcore.PubSubOptions(keepDuplicates=True)) - # publishEx provides additional options such as setting initial + # publishEx provides additional options such as setting initial # properties and using a custom type string. Using a custom type string for # types other than raw and string is not recommended. The properties string # must be a JSON map. self.dblPub = dblTopic.publishEx("double", '{"myprop": 5}') - def periodic(self): + def periodic(self): # publish a default value self.dblPub.setDefault(0.0) - # publish a value with current timestamp + # publish a value with current timestamp self.dblPub.set(1.0) self.dblPub.set(2.0, 0) # 0 = use current time - # publish a value with a specific timestamp with microsecond resolution. + # publish a value with a specific timestamp with microsecond resolution. # On the roboRIO, this is the same as the FPGA timestamp (e.g. # RobotController.getFPGATime()) self.dblPub.set(3.0, ntcore._now()) - # often not required in robot code, unless this class doesn't exist for + # 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 publishing def close(self): # stop publishing self.dblPub.close() - ``` + ``` ## Subscribing to a Topic @@ -210,34 +210,34 @@ Subscribers have a range of different ways to read received values. It's possibl public class Example { // the subscriber is an instance variable so its lifetime matches that of the class final DoubleSubscriber dblSub; - public Example(DoubleTopic dblTopic) { + public Example(DoubleTopic dblTopic) { // start subscribing; the return value must be retained. // the parameter is the default value if no value is available when get() is called dblSub = dblTopic.subscribe(0.0); - // subscribe options may be specified using PubSubOption + // subscribe options may be specified using PubSubOption dblSub = dblTopic.subscribe(0.0, PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10)); - // subscribeEx provides the options of using a custom type string. + // subscribeEx provides the options of using a custom type string. // Using a custom type string for types other than raw and string is not recommended. dblSub = dblTopic.subscribeEx("double", 0.0); } - public void periodic() { + public void periodic() { // simple get of most recent value; if no value has been published, // returns the default value passed to the subscribe() function double val = dblSub.get(); - // get the most recent value; if no value has been published, returns + // get the most recent value; if no value has been published, returns // the passed-in default value double val = dblSub.get(-1.0); - // subscribers also implement the appropriate Supplier interface, e.g. DoubleSupplier + // subscribers also implement the appropriate Supplier interface, e.g. DoubleSupplier double val = dblSub.getAsDouble(); - // get the most recent value, along with its timestamp + // get the most recent value, along with its timestamp TimestampedDouble tsVal = dblSub.getAtomic(); - // read all value changes since the last call to readQueue/readQueueValues + // read all value changes since the last call to readQueue/readQueueValues // readQueue() returns timestamps; readQueueValues() does not. TimestampedDouble[] tsUpdates = dblSub.readQueue(); double[] valUpdates = dblSub.readQueueValues(); } - // often not required in robot code, unless this class doesn't exist for + // 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() { @@ -255,29 +255,29 @@ Subscribers have a range of different ways to read received values. It's possibl // the subscriber is an instance variable so its lifetime matches that of the class // subscribing is automatically stopped when dblSub is destroyed by the class destructor nt::DoubleSubscriber dblSub; - public: + public: explicit Example(nt::DoubleTopic dblTopic) { // start subscribing; the return value must be retained. // the parameter is the default value if no value is available when get() is called dblSub = dblTopic.Subscribe(0.0); - // subscribe options may be specified using PubSubOptions + // subscribe options may be specified using PubSubOptions dblSub = dblTopic.subscribe(0.0, {.pollStorage = 10, .keepDuplicates = true}); - // SubscribeEx provides the options of using a custom type string. + // SubscribeEx provides the options of using a custom type string. // Using a custom type string for types other than raw and string is not recommended. dblSub = dblTopic.SubscribeEx("double", 0.0); } - void Periodic() { + void Periodic() { // simple get of most recent value; if no value has been published, // returns the default value passed to the Subscribe() function double val = dblSub.Get(); - // get the most recent value; if no value has been published, returns + // get the most recent value; if no value has been published, returns // the passed-in default value double val = dblSub.Get(-1.0); - // get the most recent value, along with its timestamp + // get the most recent value, along with its timestamp nt::TimestampedDouble tsVal = dblSub.GetAtomic(); - // read all value changes since the last call to ReadQueue/ReadQueueValues + // read all value changes since the last call to ReadQueue/ReadQueueValues // ReadQueue() returns timestamps; ReadQueueValues() does not. std::vector tsUpdates = dblSub.ReadQueue(); std::vector valUpdates = dblSub.ReadQueueValues(); @@ -293,28 +293,28 @@ Subscribers have a range of different ways to read received values. It's possibl // the subscriber is an instance variable, but since it's a handle, it's // not automatically released, so we need a destructor NT_Subscriber dblSub; - public: + public: explicit Example(NT_Topic dblTopic) { // start subscribing // Using a custom type string for types other than raw and string is not recommended. dblSub = nt::Subscribe(dblTopic, NT_DOUBLE, "double"); - // subscribe options may be specified using PubSubOptions + // subscribe options may be specified using PubSubOptions dblSub = nt::Subscribe(dblTopic, NT_DOUBLE, "double", {.pollStorage = 10, .keepDuplicates = true}); } - void Periodic() { + void Periodic() { // get the most recent value; if no value has been published, returns // the passed-in default value double val = nt::GetDouble(dblSub, 0.0); - // get the most recent value, along with its timestamp + // get the most recent value, along with its timestamp nt::TimestampedDouble tsVal = nt::GetAtomic(dblSub, 0.0); - // read all value changes since the last call to ReadQueue/ReadQueueValues + // read all value changes since the last call to ReadQueue/ReadQueueValues // ReadQueue() returns timestamps; ReadQueueValues() does not. std::vector tsUpdates = nt::ReadQueueDouble(dblSub); std::vector valUpdates = nt::ReadQueueValuesDouble(dblSub); } - ~Example() { + ~Example() { // stop subscribing nt::Unsubscribe(dblSub); } @@ -325,65 +325,64 @@ Subscribers have a range of different ways to read received values. It's possibl ```c // This code assumes that a NT_Topic dblTopic variable already exists - // start subscribing + // start subscribing // Using a custom type string for types other than raw and string is not recommended. NT_Subscriber dblSub = NT_Subscribe(dblTopic, NT_DOUBLE, "double", NULL, 0); - // subscribe options may be specified using NT_PubSubOptions + // subscribe options may be specified using NT_PubSubOptions struct NT_PubSubOptions options; memset(&options, 0, sizeof(options)); options.structSize = sizeof(options); options.keepDuplicates = 1; // true options.pollStorage = 10; NT_Subscriber dblSub = NT_Subscribe(dblTopic, NT_DOUBLE, "double", &options); - // get the most recent value; if no value has been published, returns + // get the most recent value; if no value has been published, returns // the passed-in default value double val = NT_GetDouble(dblSub, 0.0); - // get the most recent value, along with its timestamp + // get the most recent value, along with its timestamp struct NT_TimestampedDouble tsVal; NT_GetAtomic(dblSub, 0.0, &tsVal); NT_DisposeTimestamped(&tsVal); - // read all value changes since the last call to ReadQueue/ReadQueueValues + // read all value changes since the last call to ReadQueue/ReadQueueValues // ReadQueue() returns timestamps; ReadQueueValues() does not. size_t tsUpdatesLen; struct NT_TimestampedDouble* tsUpdates = NT_ReadQueueDouble(dblSub, &tsUpdatesLen); NT_FreeQueueDouble(tsUpdates, tsUpdatesLen); - size_t valUpdatesLen; + size_t valUpdatesLen; double* valUpdates = NT_ReadQueueValuesDouble(dblSub, &valUpdatesLen); NT_FreeDoubleArray(valUpdates, valUpdatesLen); - // stop subscribing + // stop subscribing NT_Unsubscribe(dblSub); ``` .. tab-item:: Python :sync: Python - ```python class Example: def __init__(self, dblTopic: ntcore.DoubleTopic): - # start subscribing; the return value must be retained. + # start subscribing; the return value must be retained. # the parameter is the default value if no value is available when get() is called self.dblSub = dblTopic.subscribe(0.0) - # subscribe options may be specified using PubSubOption + # subscribe options may be specified using PubSubOption self.dblSub = dblTopic.subscribe( 0.0, ntcore.PubSubOptions(keepDuplicates=True, pollStorage=10) ) - # subscribeEx provides the options of using a custom type string. + # subscribeEx provides the options of using a custom type string. # Using a custom type string for types other than raw and string is not recommended. dblSub = dblTopic.subscribeEx("double", 0.0) - def periodic(self): + def periodic(self): # simple get of most recent value; if no value has been published, # returns the default value passed to the subscribe() function val = self.dblSub.get() - # get the most recent value; if no value has been published, returns + # get the most recent value; if no value has been published, returns # the passed-in default value val = self.dblSub.get(-1.0) - # get the most recent value, along with its timestamp + # get the most recent value, along with its timestamp tsVal = self.dblSub.getAtomic() - # read all value changes since the last call to readQueue + # read all value changes since the last call to readQueue # readQueue() returns timestamps tsUpdates = self.dblSub.readQueue() - # often not required in robot code, unless this class doesn't exist for + # 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): @@ -404,18 +403,18 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway public class Example { // the entry is an instance variable so its lifetime matches that of the class final DoubleEntry dblEntry; - public Example(DoubleTopic dblTopic) { + public Example(DoubleTopic dblTopic) { // start subscribing; the return value must be retained. // the parameter is the default value if no value is available when get() is called dblEntry = dblTopic.getEntry(0.0); - // publish and subscribe options may be specified using PubSubOption + // publish and subscribe options may be specified using PubSubOption dblEntry = dblTopic.getEntry(0.0, PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10)); - // getEntryEx provides the options of using a custom type string. + // getEntryEx provides the options of using a custom type string. // Using a custom type string for types other than raw and string is not recommended. dblEntry = dblTopic.getEntryEx("double", 0.0); } - public void periodic() { + public void periodic() { // entries support all the same methods as subscribers: double val = dblEntry.get(); double val = dblEntry.get(-1.0); @@ -423,7 +422,7 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway TimestampedDouble tsVal = dblEntry.getAtomic(); TimestampedDouble[] tsUpdates = dblEntry.readQueue(); double[] valUpdates = dblEntry.readQueueValues(); - // entries also support all the same methods as publishers; the first time + // entries also support all the same methods as publishers; the first time // one of these is called, an internal publisher is automatically created dblEntry.setDefault(0.0); dblEntry.set(1.0); @@ -432,11 +431,11 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway dblEntry.set(3.0, time); myFunc(dblEntry); } - public void unpublish() { + public void unpublish() { // you can stop publishing while keeping the subscriber alive dblEntry.unpublish(); } - // often not required in robot code, unless this class doesn't exist for + // 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() { @@ -455,27 +454,27 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway // subscribing/publishing is automatically stopped when dblEntry is destroyed by // the class destructor nt::DoubleEntry dblEntry; - public: + public: explicit Example(nt::DoubleTopic dblTopic) { // start subscribing; the return value must be retained. // the parameter is the default value if no value is available when get() is called dblEntry = dblTopic.GetEntry(0.0); - // publish and subscribe options may be specified using PubSubOptions + // publish and subscribe options may be specified using PubSubOptions dblEntry = dblTopic.GetEntry(0.0, {.pollStorage = 10, .keepDuplicates = true}); - // GetEntryEx provides the options of using a custom type string. + // GetEntryEx provides the options of using a custom type string. // Using a custom type string for types other than raw and string is not recommended. dblEntry = dblTopic.GetEntryEx("double", 0.0); } - void Periodic() { + void Periodic() { // entries support all the same methods as subscribers: double val = dblEntry.Get(); double val = dblEntry.Get(-1.0); nt::TimestampedDouble tsVal = dblEntry.GetAtomic(); std::vector tsUpdates = dblEntry.ReadQueue(); std::vector valUpdates = dblEntry.ReadQueueValues(); - // entries also support all the same methods as publishers; the first time + // entries also support all the same methods as publishers; the first time // one of these is called, an internal publisher is automatically created dblEntry.SetDefault(0.0); dblEntry.Set(1.0); @@ -483,7 +482,7 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway int64_t time = nt::Now(); dblEntry.Set(3.0, time); } - void Unpublish() { + void Unpublish() { // you can stop publishing while keeping the subscriber alive dblEntry.Unpublish(); } @@ -498,23 +497,23 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway // the entry is an instance variable, but since it's a handle, it's // not automatically released, so we need a destructor NT_Entry dblEntry; - public: + public: explicit Example(NT_Topic dblTopic) { // start subscribing // Using a custom type string for types other than raw and string is not recommended. dblEntry = nt::GetEntry(dblTopic, NT_DOUBLE, "double"); - // publish and subscribe options may be specified using PubSubOptions + // publish and subscribe options may be specified using PubSubOptions dblEntry = nt::GetEntry(dblTopic, NT_DOUBLE, "double", {.pollStorage = 10, .keepDuplicates = true}); } - void Periodic() { + void Periodic() { // entries support all the same methods as subscribers: double val = nt::GetDouble(dblEntry, 0.0); nt::TimestampedDouble tsVal = nt::GetAtomic(dblEntry, 0.0); std::vector tsUpdates = nt::ReadQueueDouble(dblEntry); std::vector valUpdates = nt::ReadQueueValuesDouble(dblEntry); - // entries also support all the same methods as publishers; the first time + // entries also support all the same methods as publishers; the first time // one of these is called, an internal publisher is automatically created nt::SetDefaultDouble(dblPub, 0.0); nt::SetDouble(dblPub, 1.0); @@ -522,11 +521,11 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway int64_t time = nt::Now(); nt::SetDouble(dblPub, 3.0, time); } - void Unpublish() { + void Unpublish() { // you can stop publishing while keeping the subscriber alive nt::Unpublish(dblEntry); } - ~Example() { + ~Example() { // stop publishing and subscribing nt::ReleaseEntry(dblEntry); } @@ -537,38 +536,38 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway ```c // This code assumes that a NT_Topic dblTopic variable already exists - // start subscribing + // start subscribing // Using a custom type string for types other than raw and string is not recommended. NT_Entry dblEntry = NT_GetEntryEx(dblTopic, NT_DOUBLE, "double", NULL, 0); - // publish and subscribe options may be specified using NT_PubSubOptions + // publish and subscribe options may be specified using NT_PubSubOptions struct NT_PubSubOptions options; memset(&options, 0, sizeof(options)); options.structSize = sizeof(options); options.keepDuplicates = 1; // true options.pollStorage = 10; NT_Entry dblEntry = NT_GetEntryEx(dblTopic, NT_DOUBLE, "double", &options); - // entries support all the same methods as subscribers: + // entries support all the same methods as subscribers: double val = NT_GetDouble(dblEntry, 0.0); - struct NT_TimestampedDouble tsVal; + struct NT_TimestampedDouble tsVal; NT_GetAtomic(dblEntry, 0.0, &tsVal); NT_DisposeTimestamped(&tsVal); - size_t tsUpdatesLen; + size_t tsUpdatesLen; struct NT_TimestampedDouble* tsUpdates = NT_ReadQueueDouble(dblEntry, &tsUpdatesLen); NT_FreeQueueDouble(tsUpdates, tsUpdatesLen); - size_t valUpdatesLen; + size_t valUpdatesLen; double* valUpdates = NT_ReadQueueValuesDouble(dblEntry, &valUpdatesLen); NT_FreeDoubleArray(valUpdates, valUpdatesLen); - // entries also support all the same methods as publishers; the first time + // entries also support all the same methods as publishers; the first time // one of these is called, an internal publisher is automatically created NT_SetDefaultDouble(dblPub, 0.0); NT_SetDouble(dblPub, 1.0); NT_SetDouble(dblPub, 2.0, 0); // 0 = use current time int64_t time = NT_Now(); NT_SetDouble(dblPub, 3.0, time); - // you can stop publishing while keeping the subscriber alive + // you can stop publishing while keeping the subscriber alive // it's not necessary to call this before NT_ReleaseEntry() NT_Unpublish(dblEntry); - // stop subscribing + // stop subscribing NT_ReleaseEntry(dblEntry); ``` @@ -579,40 +578,40 @@ An :term:`entry` is a combined publisher and subscriber. The subscriber is alway ```python class Example: def __init__(self, dblTopic: ntcore.DoubleTopic): - # start subscribing; the return value must be retained. + # start subscribing; the return value must be retained. # the parameter is the default value if no value is available when get() is called self.dblEntry = dblTopic.getEntry(0.0) - # publish and subscribe options may be specified using PubSubOption + # publish and subscribe options may be specified using PubSubOption self.dblEntry = dblTopic.getEntry( 0.0, ntcore.PubSubOptions(keepDuplicates=True, pollStorage=10) ) - # getEntryEx provides the options of using a custom type string. + # getEntryEx provides the options of using a custom type string. # Using a custom type string for types other than raw and string is not recommended. self.dblEntry = dblTopic.getEntryEx("double", 0.0) - def periodic(self): + def periodic(self): # entries support all the same methods as subscribers: val = self.dblEntry.get() val = self.dblEntry.get(-1.0) val = self.dblEntry.getAsDouble() tsVal = self.dblEntry.getAtomic() tsUpdates = self.dblEntry.readQueue() - # entries also support all the same methods as publishers; the first time + # entries also support all the same methods as publishers; the first time # one of these is called, an internal publisher is automatically created self.dblEntry.setDefault(0.0) self.dblEntry.set(1.0) self.dblEntry.set(2.0, 0) # 0 = use current time time = ntcore._now() self.dblEntry.set(3.0, time) - def unpublish(self): + def unpublish(self): # you can stop publishing while keeping the subscriber alive self.dblEntry.unpublish() - # often not required in robot code, unless this class doesn't exist for + # 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): # stop subscribing/publishing self.dblEntry.close() - ``` + ``` ## Using GenericEntry, GenericPublisher, and GenericSubscriber @@ -629,52 +628,52 @@ For the most robust code, using the type-specific Publisher, Subscriber, and Ent final GenericPublisher pub; final GenericSubscriber sub; final GenericEntry entry; - public Example(Topic topic) { + public Example(Topic topic) { // start subscribing; the return value must be retained. // when publishing, a type string must be provided pub = topic.genericPublish("double"); - // subscribing can optionally include a type string + // subscribing can optionally include a type string // unlike type-specific subscribers, no default value is provided sub = topic.genericSubscribe(); sub = topic.genericSubscribe("double"); - // when getting an entry, the type string is also optional; if not provided + // when getting an entry, the type string is also optional; if not provided // the publisher data type will be determined by the first publisher-creating call entry = topic.getGenericEntry(); entry = topic.getGenericEntry("double"); - // publish and subscribe options may be specified using PubSubOption + // publish and subscribe options may be specified using PubSubOption pub = topic.genericPublish("double", PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10)); sub = topic.genericSubscribe(PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10)); entry = topic.getGenericEntry(PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10)); - // genericPublishEx provides the option of setting initial properties. + // genericPublishEx provides the option of setting initial properties. pub = topic.genericPublishEx("double", "{\"retained\": true}", PubSubOption.keepDuplicates(true), PubSubOption.pollStorage(10)); } - public void periodic() { + public void periodic() { // generic subscribers and entries have typed get operations; a default must be provided double val = sub.getDouble(-1.0); double val = entry.getDouble(-1.0); - // they also support an untyped get (also meets Supplier interface) + // they also support an untyped get (also meets Supplier interface) NetworkTableValue val = sub.get(); NetworkTableValue val = entry.get(); - // they also support readQueue + // they also support readQueue NetworkTableValue[] updates = sub.readQueue(); NetworkTableValue[] updates = entry.readQueue(); - // publishers and entries have typed set operations; these return false if the + // publishers and entries have typed set operations; these return false if the // topic already exists with a mismatched type boolean success = pub.setDefaultDouble(1.0); boolean success = pub.setBoolean(true); - // they also implement a generic set and Consumer interface + // they also implement a generic set and Consumer interface boolean success = entry.set(NetworkTableValue.makeDouble(...)); boolean success = entry.accept(NetworkTableValue.makeDouble(...)); } - public void unpublish() { + public void unpublish() { // you can stop publishing an entry while keeping the subscriber alive entry.unpublish(); } - // often not required in robot code, unless this class doesn't exist for + // 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/publishing public void close() { @@ -696,48 +695,48 @@ For the most robust code, using the type-specific Publisher, Subscriber, and Ent nt::GenericPublisher pub; nt::GenericSubscriber sub; nt::GenericEntry entry; - public: + public: Example(nt::Topic topic) { // start subscribing; the return value must be retained. // when publishing, a type string must be provided pub = topic.GenericPublish("double"); - // subscribing can optionally include a type string + // subscribing can optionally include a type string // unlike type-specific subscribers, no default value is provided sub = topic.GenericSubscribe(); sub = topic.GenericSubscribe("double"); - // when getting an entry, the type string is also optional; if not provided + // when getting an entry, the type string is also optional; if not provided // the publisher data type will be determined by the first publisher-creating call entry = topic.GetEntry(); entry = topic.GetEntry("double"); - // publish and subscribe options may be specified using PubSubOptions + // publish and subscribe options may be specified using PubSubOptions pub = topic.GenericPublish("double", {.pollStorage = 10, .keepDuplicates = true}); sub = topic.GenericSubscribe( {.pollStorage = 10, .keepDuplicates = true}); entry = topic.GetGenericEntry( {.pollStorage = 10, .keepDuplicates = true}); - // genericPublishEx provides the option of setting initial properties. + // genericPublishEx provides the option of setting initial properties. pub = topic.genericPublishEx("double", {{"myprop", 5}}, {.pollStorage = 10, .keepDuplicates = true}); } - void Periodic() { + void Periodic() { // generic subscribers and entries have typed get operations; a default must be provided double val = sub.GetDouble(-1.0); double val = entry.GetDouble(-1.0); - // they also support an untyped get + // they also support an untyped get nt::NetworkTableValue val = sub.Get(); nt::NetworkTableValue val = entry.Get(); - // they also support readQueue + // they also support readQueue std::vector updates = sub.ReadQueue(); std::vector updates = entry.ReadQueue(); - // publishers and entries have typed set operations; these return false if the + // publishers and entries have typed set operations; these return false if the // topic already exists with a mismatched type bool success = pub.SetDefaultDouble(1.0); bool success = pub.SetBoolean(true); - // they also implement a generic set and Consumer interface + // they also implement a generic set and Consumer interface bool success = entry.Set(nt::NetworkTableValue::MakeDouble(...)); } - void Unpublish() { + void Unpublish() { // you can stop publishing an entry while keeping the subscriber alive entry.Unpublish(); } @@ -751,18 +750,18 @@ For the most robust code, using the type-specific Publisher, Subscriber, and Ent ```python class Example: def __init__(self, topic: ntcore.Topic): - # start subscribing; the return value must be retained. + # start subscribing; the return value must be retained. # when publishing, a type string must be provided self.pub = topic.genericPublish("double") - # subscribing can optionally include a type string + # subscribing can optionally include a type string # unlike type-specific subscribers, no default value is provided self.sub = topic.genericSubscribe() self.sub = topic.genericSubscribe("double") - # when getting an entry, the type string is also optional; if not provided + # when getting an entry, the type string is also optional; if not provided # the publisher data type will be determined by the first publisher-creating call self.entry = topic.getGenericEntry() self.entry = topic.getGenericEntry("double") - # publish and subscribe options may be specified using PubSubOption + # publish and subscribe options may be specified using PubSubOption self.pub = topic.genericPublish( "double", ntcore.PubSubOptions(keepDuplicates=True, pollStorage=10) ) @@ -772,32 +771,32 @@ For the most robust code, using the type-specific Publisher, Subscriber, and Ent self.entry = topic.getGenericEntry( ntcore.PubSubOptions(keepDuplicates=True, pollStorage=10) ) - # genericPublishEx provides the option of setting initial properties. + # genericPublishEx provides the option of setting initial properties. self.pub = topic.genericPublishEx( "double", '{"retained": true}', ntcore.PubSubOptions(keepDuplicates=True, pollStorage=10), ) - def periodic(self): + def periodic(self): # generic subscribers and entries have typed get operations; a default must be provided val = self.sub.getDouble(-1.0) val = self.entry.getDouble(-1.0) - # they also support an untyped get (also meets Supplier interface) + # they also support an untyped get (also meets Supplier interface) val = self.sub.get() val = self.entry.get() - # they also support readQueue + # they also support readQueue updates = self.sub.readQueue() updates = self.entry.readQueue() - # publishers and entries have typed set operations; these return false if the + # publishers and entries have typed set operations; these return false if the # topic already exists with a mismatched type success = self.pub.setDefaultDouble(1.0) success = self.pub.setBoolean(True) - # they also implement a generic set + # they also implement a generic set success = self.entry.set(ntcore.Value.makeDouble(...)) - def unpublish(self): + def unpublish(self): # you can stop publishing an entry while keeping the subscriber alive self.entry.unpublish() - # often not required in robot code, unless this class doesn't exist for + # 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/publishing def close(self): @@ -820,26 +819,26 @@ While in most cases it's only necessary to subscribe to individual topics, it is // the subscriber is an instance variable so its lifetime matches that of the class final MultiSubscriber multiSub; final NetworkTableListenerPoller poller; - public Example(NetworkTableInstance inst) { + public Example(NetworkTableInstance inst) { // start subscribing; the return value must be retained. // provide an array of topic name prefixes multiSub = new MultiSubscriber(inst, new String[] {"/table1/", "/table2/"}); - // subscribe options may be specified using PubSubOption + // subscribe options may be specified using PubSubOption multiSub = new MultiSubscriber(inst, new String[] {"/table1/", "/table2/"}, PubSubOption.keepDuplicates(true)); - // to get value updates from a MultiSubscriber, it's necessary to create a listener + // to get value updates from a MultiSubscriber, it's necessary to create a listener // (see the listener documentation for more details) poller = new NetworkTableListenerPoller(inst); poller.addListener(multiSub, EnumSet.of(NetworkTableEvent.Kind.kValueAll)); } - public void periodic() { + public void periodic() { // read value events NetworkTableEvent[] events = poller.readQueue(); - for (NetworkTableEvent event : events) { + for (NetworkTableEvent event : events) { NetworkTableValue value = event.valueData.value; } } - // often not required in robot code, unless this class doesn't exist for + // 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() { @@ -860,23 +859,23 @@ While in most cases it's only necessary to subscribe to individual topics, it is // subscribing is automatically stopped when multiSub is destroyed by the class destructor nt::MultiSubscriber multiSub; nt::NetworkTableListenerPoller poller; - public: + public: explicit Example(nt::NetworkTableInstance inst) { // start subscribing; the return value must be retained. // provide an array of topic name prefixes multiSub = nt::MultiSubscriber{inst, {{"/table1/", "/table2/"}}}; - // subscribe options may be specified using PubSubOption + // subscribe options may be specified using PubSubOption multiSub = nt::MultiSubscriber{inst, {{"/table1/", "/table2/"}}, {.keepDuplicates = true}}; - // to get value updates from a MultiSubscriber, it's necessary to create a listener + // to get value updates from a MultiSubscriber, it's necessary to create a listener // (see the listener documentation for more details) poller = nt::NetworkTableListenerPoller{inst}; poller.AddListener(multiSub, nt::EventFlags::kValueAll); } - void Periodic() { + void Periodic() { // read value events std::vector events = poller.ReadQueue(); - for (auto&& event : events) { + for (auto&& event : events) { nt::NetworkTableValue value = event.GetValueEventData()->value; } } @@ -892,27 +891,27 @@ While in most cases it's only necessary to subscribe to individual topics, it is // not automatically released, so we need a destructor NT_MultiSubscriber multiSub; NT_ListenerPoller poller; - public: + public: explicit Example(NT_Inst inst) { // start subscribing; the return value must be retained. // provide an array of topic name prefixes multiSub = nt::SubscribeMultiple(inst, {{"/table1/", "/table2/"}}); - // subscribe options may be specified using PubSubOption + // subscribe options may be specified using PubSubOption multiSub = nt::SubscribeMultiple(inst, {{"/table1/", "/table2/"}}, {.keepDuplicates = true}); - // to get value updates from a MultiSubscriber, it's necessary to create a listener + // to get value updates from a MultiSubscriber, it's necessary to create a listener // (see the listener documentation for more details) poller = nt::CreateListenerPoller(inst); nt::AddPolledListener(poller, multiSub, nt::EventFlags::kValueAll); } - void Periodic() { + void Periodic() { // read value events std::vector events = nt::ReadListenerQueue(poller); - for (auto&& event : events) { + for (auto&& event : events) { nt::NetworkTableValue value = event.GetValueEventData()->value; } } - ~Example() { + ~Example() { // close listener nt::DestroyListenerPoller(poller); // stop subscribing @@ -925,7 +924,7 @@ While in most cases it's only necessary to subscribe to individual topics, it is ```c // This code assumes that a NT_Inst inst variable already exists - // start subscribing + // start subscribing // provide an array of topic name prefixes struct NT_String prefixes[2]; prefixes[0].str = "/table1/"; @@ -933,24 +932,24 @@ While in most cases it's only necessary to subscribe to individual topics, it is prefixes[1].str = "/table2/"; prefixes[1].len = 8; NT_MultiSubscriber multiSub = NT_SubscribeMultiple(inst, prefixes, 2, NULL, 0); - // subscribe options may be specified using NT_PubSubOptions + // subscribe options may be specified using NT_PubSubOptions struct NT_PubSubOptions options; memset(&options, 0, sizeof(options)); options.structSize = sizeof(options); options.keepDuplicates = 1; // true NT_MultiSubscriber multiSub = NT_SubscribeMultiple(inst, prefixes, 2, &options); - // to get value updates from a MultiSubscriber, it's necessary to create a listener + // to get value updates from a MultiSubscriber, it's necessary to create a listener // (see the listener documentation for more details) NT_ListenerPoller poller = NT_CreateListenerPoller(inst); NT_AddPolledListener(poller, multiSub, NT_EVENT_VALUE_ALL); - // read value events + // read value events size_t eventsLen; struct NT_Event* events = NT_ReadListenerQueue(poller, &eventsLen); - for (size_t i = 0; i < eventsLen; i++) { + for (size_t i = 0; i < eventsLen; i++) { NT_Value* value = &events[i].data.valueData.value; } - NT_DisposeEventArray(events, eventsLen); - // close listener + NT_DisposeEventArray(events, eventsLen); + // close listener NT_DestroyListenerPoller(poller); // stop subscribing NT_UnsubscribeMultiple(multiSub); @@ -963,23 +962,23 @@ While in most cases it's only necessary to subscribe to individual topics, it is ```python class Example: def __init__(self, inst: ntcore.NetworkTableInstance): - # start subscribing; the return value must be retained. + # start subscribing; the return value must be retained. # provide an array of topic name prefixes self.multiSub = ntcore.MultiSubscriber(inst, ["/table1/", "/table2/"]) - # subscribe options may be specified using PubSubOption + # subscribe options may be specified using PubSubOption self.multiSub = ntcore.MultiSubscriber( inst, ["/table1/", "/table2/"], ntcore.PubSubOptions(keepDuplicates=True) ) - # to get value updates from a MultiSubscriber, it's necessary to create a listener + # to get value updates from a MultiSubscriber, it's necessary to create a listener # (see the listener documentation for more details) self.poller = ntcore.NetworkTableListenerPoller(inst) self.poller.addListener(self.multiSub, ntcore.EventFlags.kValueAlls) - def periodic(self): + def periodic(self): # read value events events = self.poller.readQueue() - for event in events: + for event in events: value: ntcore.Value = event.data.value - # often not required in robot code, unless this class doesn't exist for + # 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): 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 386abed992..6683323a8a 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,35 +20,35 @@ Both of the following examples are extremely simplified programs that just illus ```java DoubleArraySubscriber areasSub; - @Override + @Override public void robotInit() { NetworkTable table = NetworkTableInstance.getDefault().getTable("GRIP/mycontoursReport"); areasSub = table.getDoubleArrayTopic("area").subscribe(new double[] {}); } - @Override + @Override public void teleopPeriodic() { - double[] areas = areasSub.get(); - System.out.print("areas: " ); - for (double area : areas) { - System.out.print(area + " "); - } - System.out.println(); + double[] areas = areasSub.get(); + System.out.print("areas: " ); + for (double area : areas) { + System.out.print(area + " "); + } + System.out.println(); } ``` ```c++ nt::DoubleArraySubscriber areasSub; - void Robot::RobotInit() override { + void Robot::RobotInit() override { auto table = nt::NetworkTableInstance::GetDefault().GetTable("GRIP/myContoursReport"); areasSub = table->GetDoubleArrayTopic("area").Subscribe({}); } - void Robot::TeleopPeriodic() override { + void Robot::TeleopPeriodic() override { std::cout << "Areas: "; - std::vector arr = areasSub.Get(); - for (double val : arr) { + std::vector arr = areasSub.Get(); + for (double val : arr) { std::cout << val << " "; } - std::cout << std::endl; + std::cout << std::endl; } ``` @@ -56,7 +56,7 @@ Both of the following examples are extremely simplified programs that just illus def robotInit(self): table = ntcore.NetworkTableInstance.getDefault().getTable("GRIP/mycontoursReport") self.areasSub = table.getDoubleArrayTopic("area").subscribe([]) - def teleopPeriodic(self): + def teleopPeriodic(self): areas = self.areasSub.get() print("Areas:", areas) ``` diff --git a/source/docs/software/networktables/robot-program.rst b/source/docs/software/networktables/robot-program.rst index 6a0b5b0617..b8d52203db 100644 --- a/source/docs/software/networktables/robot-program.rst +++ b/source/docs/software/networktables/robot-program.rst @@ -8,30 +8,30 @@ The example robot program below publishes incrementing X and Y values to a table ```java package edu.wpi.first.wpilibj.templates; - import edu.wpi.first.wpilibj.TimedRobot; + import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.networktables.DoublePublisher; import edu.wpi.first.networktables.NetworkTable; import edu.wpi.first.networktables.NetworkTableInstance; - public class EasyNetworkTableExample extends TimedRobot { + public class EasyNetworkTableExample extends TimedRobot { DoublePublisher xPub; DoublePublisher yPub; - public void robotInit() { + public void robotInit() { // Get the default instance of NetworkTables that was created automatically // when the robot program starts NetworkTableInstance inst = NetworkTableInstance.getDefault(); - // Get the table within that instance that contains the data. There can + // Get the table within that instance that contains the data. There can // be as many tables as you like and exist to make it easier to organize // your data. In this case, it's a table called datatable. NetworkTable table = inst.getTable("datatable"); - // Start publishing topics within that table that correspond to the X and Y values + // Start publishing topics within that table that correspond to the X and Y values // for some operation in your program. // The topic names are actually "/datatable/x" and "/datatable/y". xPub = table.getDoubleTopic("x").publish(); yPub = table.getDoubleTopic("y").publish(); } - double x = 0; + double x = 0; double y = 0; - public void teleopPeriodic() { + public void teleopPeriodic() { // Publish values that are constantly increasing. xPub.set(x); yPub.set(y); @@ -46,27 +46,27 @@ The example robot program below publishes incrementing X and Y values to a table #include #include #include - class EasyNetworkExample : public frc::TimedRobot { + class EasyNetworkExample : public frc::TimedRobot { public: nt::DoublePublisher xPub; nt::DoublePublisher yPub; - void RobotInit() { + void RobotInit() { // Get the default instance of NetworkTables that was created automatically // when the robot program starts auto inst = nt::NetworkTableInstance::GetDefault(); - // Get the table within that instance that contains the data. There can + // Get the table within that instance that contains the data. There can // be as many tables as you like and exist to make it easier to organize // your data. In this case, it's a table called datatable. auto table = inst.GetTable("datatable"); - // Start publishing topics within that table that correspond to the X and Y values + // Start publishing topics within that table that correspond to the X and Y values // for some operation in your program. // The topic names are actually "/datatable/x" and "/datatable/y". xPub = table->GetDoubleTopic("x").Publish(); yPub = table->GetDoubleTopic("y").Publish(); } - double x = 0; + double x = 0; double y = 0; - void TeleopPeriodic() { + void TeleopPeriodic() { // Publish values that are constantly increasing. xPub.Set(x); yPub.Set(y); @@ -74,29 +74,29 @@ The example robot program below publishes incrementing X and Y values to a table y += 0.05; } } - START_ROBOT_CLASS(EasyNetworkExample) + START_ROBOT_CLASS(EasyNetworkExample) ``` ```python import ntcore import wpilib - class EasyNetworkTableExample(wpilib.TimedRobot): + class EasyNetworkTableExample(wpilib.TimedRobot): def robotInit(self) -> None: # Get the default instance of NetworkTables that was created automatically # when the robot program starts inst = ntcore.NetworkTableInstance.getDefault() - # Get the table within that instance that contains the data. There can + # Get the table within that instance that contains the data. There can # be as many tables as you like and exist to make it easier to organize # your data. In this case, it's a table called datatable. table = inst.getTable("datatable") - # Start publishing topics within that table that correspond to the X and Y values + # Start publishing topics within that table that correspond to the X and Y values # for some operation in your program. # The topic names are actually "/datatable/x" and "/datatable/y". self.xPub = table.getDoubleTopic("x").publish() self.yPub = table.getDoubleTopic("y").publish() - self.x = 0 + self.x = 0 self.y = 0 - def teleopPeriodic(self) -> None: + def teleopPeriodic(self) -> None: # Publish values that are constantly increasing. self.xPub.set(self.x) self.yPub.set(self.y) diff --git a/source/docs/software/networktables/tables-and-topics.rst b/source/docs/software/networktables/tables-and-topics.rst index db0f8e7c4a..a44c78a632 100644 --- a/source/docs/software/networktables/tables-and-topics.rst +++ b/source/docs/software/networktables/tables-and-topics.rst @@ -18,14 +18,14 @@ Having a Topic object or handle does not mean the topic exists or is of the corr ```java NetworkTableInstance inst = NetworkTableInstance.getDefault(); NetworkTable table = inst.getTable("datatable"); - // get a topic from a NetworkTableInstance + // get a topic from a NetworkTableInstance // the topic name in this case is the full name DoubleTopic dblTopic = inst.getDoubleTopic("/datatable/X"); - // get a topic from a NetworkTable + // get a topic from a NetworkTable // the topic name in this case is the name within the table; // this line and the one above reference the same topic DoubleTopic dblTopic = table.getDoubleTopic("X"); - // get a type-specific topic from a generic Topic + // get a type-specific topic from a generic Topic Topic genericTopic = inst.getTopic("/datatable/X"); DoubleTopic dblTopic = new DoubleTopic(genericTopic); ``` @@ -36,14 +36,14 @@ Having a Topic object or handle does not mean the topic exists or is of the corr ```c++ nt::NetworkTableInstance inst = nt::NetworkTableInstance::GetDefault(); std::shared_ptr table = inst.GetTable("datatable"); - // get a topic from a NetworkTableInstance + // get a topic from a NetworkTableInstance // the topic name in this case is the full name nt::DoubleTopic dblTopic = inst.GetDoubleTopic("/datatable/X"); - // get a topic from a NetworkTable + // get a topic from a NetworkTable // the topic name in this case is the name within the table; // this line and the one above reference the same topic nt::DoubleTopic dblTopic = table->GetDoubleTopic("X"); - // get a type-specific topic from a generic Topic + // get a type-specific topic from a generic Topic nt::Topic genericTopic = inst.GetTopic("/datatable/X"); nt::DoubleTopic dblTopic{genericTopic}; ``` @@ -53,7 +53,7 @@ Having a Topic object or handle does not mean the topic exists or is of the corr ```c++ NT_Instance inst = nt::GetDefaultInstance(); - // get a topic from a NetworkTableInstance + // get a topic from a NetworkTableInstance NT_Topic topic = nt::GetTopic(inst, "/datatable/X"); ``` @@ -62,7 +62,7 @@ Having a Topic object or handle does not mean the topic exists or is of the corr ```c NT_Instance inst = NT_GetDefaultInstance(); - // get a topic from a NetworkTableInstance + // get a topic from a NetworkTableInstance NT_Topic topic = NT_GetTopic(inst, "/datatable/X"); ``` @@ -72,16 +72,16 @@ Having a Topic object or handle does not mean the topic exists or is of the corr ```python import ntcore - inst = ntcore.NetworkTableInstance.getDefault() + inst = ntcore.NetworkTableInstance.getDefault() table = inst.getTable("datatable") - # get a topic from a NetworkTableInstance + # get a topic from a NetworkTableInstance # the topic name in this case is the full name dblTopic = inst.getDoubleTopic("/datatable/X") - # get a topic from a NetworkTable + # get a topic from a NetworkTable # the topic name in this case is the name within the table; # this line and the one above reference the same topic dblTopic = table.getDoubleTopic("X") - # get a type-specific topic from a generic Topic + # get a type-specific topic from a generic Topic genericTopic = inst.getTopic("/datatable/X") dblTopic = ntcore.DoubleTopic(genericTopic) ``` diff --git a/source/docs/software/pathplanning/pathweaver/integrating-robot-program.rst b/source/docs/software/pathplanning/pathweaver/integrating-robot-program.rst index 68f24217f3..e5d69bd3e0 100644 --- a/source/docs/software/pathplanning/pathweaver/integrating-robot-program.rst +++ b/source/docs/software/pathplanning/pathweaver/integrating-robot-program.rst @@ -13,7 +13,7 @@ The ``fromPathweaverJson`` (Java) / ``FromPathweaverJson`` (C++) static methods ```java String trajectoryJSON = "paths/YourPath.wpilib.json"; Trajectory trajectory = new Trajectory(); - @Override + @Override public void robotInit() { try { Path trajectoryPath = Filesystem.getDeployDirectory().toPath().resolve(trajectoryJSON); @@ -28,8 +28,8 @@ The ``fromPathweaverJson`` (Java) / ``FromPathweaverJson`` (C++) static methods #include #include #include - frc::Trajectory trajectory; - void Robot::RobotInit() { + frc::Trajectory trajectory; + void Robot::RobotInit() { fs::path deployDirectory = frc::filesystem::GetDeployDirectory(); deployDirectory = deployDirectory / "paths" / "YourPath.wpilib.json"; trajectory = frc::TrajectoryUtil::FromPathweaverJson(deployDirectory.string()); diff --git a/source/docs/software/telemetry/datalog.rst b/source/docs/software/telemetry/datalog.rst index e3987a404f..91dec02f42 100644 --- a/source/docs/software/telemetry/datalog.rst +++ b/source/docs/software/telemetry/datalog.rst @@ -26,19 +26,19 @@ The most basic usage of DataLogManager only requires a single line of code (typi ```java import edu.wpi.first.wpilibj.DataLogManager; - // Starts recording to data log + // Starts recording to data log DataLogManager.start(); ``` ```c++ #include "frc/DataLogManager.h" - // Starts recording to data log + // Starts recording to data log frc::DataLogManager::Start(); ``` ```python from wpilib import DataLogManager - DataLogManager.start() + DataLogManager.start() ``` DataLogManager provides a convenience function (``DataLogManager.log()``) for logging of text messages to the ``messages`` entry in the data log. The message is also printed to standard output, so this can be a replacement for ``System.out.println()``. @@ -56,32 +56,32 @@ DataLogManager by default does not record joystick data. The ``DriverStation`` ```java import edu.wpi.first.wpilibj.DataLogManager; import edu.wpi.first.wpilibj.DriverStation; - // Starts recording to data log + // Starts recording to data log DataLogManager.start(); - // Record both DS control and joystick data + // Record both DS control and joystick data DriverStation.startDataLog(DataLogManager.getLog()); - // (alternatively) Record only DS control data + // (alternatively) Record only DS control data DriverStation.startDataLog(DataLogManager.getLog(), false); ``` ```c++ #include "frc/DataLogManager.h" #include "frc/DriverStation.h" - // Starts recording to data log + // Starts recording to data log frc::DataLogManager::Start(); - // Record both DS control and joystick data + // Record both DS control and joystick data DriverStation::StartDataLog(DataLogManager::GetLog()); - // (alternatively) Record only DS control data + // (alternatively) Record only DS control data DriverStation::StartDataLog(DataLogManager::GetLog(), false); ``` ```python from wpilib import DataLogManager, DriverStation - # Starts recording to data log + # Starts recording to data log DataLogManager.start() - # Record both DS control and joystick data + # Record both DS control and joystick data DriverStation.startDataLog(DataLogManager.getLog()) - # (alternatively) Record only DS control data + # (alternatively) Record only DS control data DriverStation.startDataLog(DataLogManager.getLog(), False) ``` @@ -101,19 +101,19 @@ The LogEntry classes can be used in conjunction with DataLogManager to record va import edu.wpi.first.util.datalog.DoubleLogEntry; import edu.wpi.first.util.datalog.StringLogEntry; import edu.wpi.first.wpilibj.DataLogManager; - BooleanLogEntry myBooleanLog; + BooleanLogEntry myBooleanLog; DoubleLogEntry myDoubleLog; StringLogEntry myStringLog; - public void robotInit() { + public void robotInit() { // Starts recording to data log DataLogManager.start(); - // Set up custom log entries + // Set up custom log entries DataLog log = DataLogManager.getLog(); myBooleanLog = new BooleanLogEntry(log, "/my/boolean"); myDoubleLog = new DoubleLogEntry(log, "/my/double"); myStringLog = new StringLogEntry(log, "/my/string"); } - public void teleopPeriodic() { + public void teleopPeriodic() { if (...) { // Only log when necessary myBooleanLog.append(true); @@ -126,19 +126,19 @@ The LogEntry classes can be used in conjunction with DataLogManager to record va ```c++ #include "frc/DataLogManager.h" #include "wpi/DataLog.h" - wpi::log::BooleanLogEntry myBooleanLog; + wpi::log::BooleanLogEntry myBooleanLog; wpi::log::DoubleLogEntry myDoubleLog; wpi::log::StringLogEntry myStringLog; - void RobotInit() { + void RobotInit() { // Starts recording to data log frc::DataLogManager::Start(); - // Set up custom log entries + // Set up custom log entries wpi::log::DataLog& log = frc::DataLogManager::GetLog(); myBooleanLog = wpi::Log::BooleanLogEntry(log, "/my/boolean"); myDoubleLog = wpi::log::DoubleLogEntry(log, "/my/double"); myStringLog = wpi::log::StringLogEntry(log, "/my/string"); } - void TeleopPeriodic() { + void TeleopPeriodic() { if (...) { // Only log when necessary myBooleanLog.Append(true); @@ -156,16 +156,16 @@ The LogEntry classes can be used in conjunction with DataLogManager to record va DoubleLogEntry, StringLogEntry, ) - class MyRobot(TimedRobot): + class MyRobot(TimedRobot): def robotInit(self): # Starts recording to data log DataLogManager.start() - # Set up custom log entries + # Set up custom log entries log = DataLogManager.getLog() self.myBooleanLog = BooleanLogEntry(log, "/my/boolean") self.myDoubleLog = DoubleLogEntry(log, "/my/double") self.myStringLog = StringLogEntry(log, "/my/string") - def teleopPeriodic(self): + def teleopPeriodic(self): if ...: # Only log when necessary self.myBooleanLog.append(True) diff --git a/source/docs/software/telemetry/robot-telemetry-with-annotations.rst b/source/docs/software/telemetry/robot-telemetry-with-annotations.rst index 295c9804da..41d1e937f4 100644 --- a/source/docs/software/telemetry/robot-telemetry-with-annotations.rst +++ b/source/docs/software/telemetry/robot-telemetry-with-annotations.rst @@ -15,18 +15,18 @@ This is enough to start logging data to NetworkTables for display and capture on public class Robot extends TimedRobot { private final Arm arm; private final Drivetrain drivetrain; - public Robot() { + public Robot() { arm = new Arm(); drivetrain = new Drivetrain(); - DataLogManager.start(); // Optional to mirror the NetworkTables-logged data to a file on disk + DataLogManager.start(); // Optional to mirror the NetworkTables-logged data to a file on disk Epilogue.bind(this); } } - @Logged + @Logged public class Arm { // ... } - @Logged + @Logged public class Drivetrain { // ... } @@ -80,22 +80,22 @@ The names of log entries can be changed using the ``name`` configuration option ```java public class Robot extends RobotBase { private final Arm arm; - public Robot() { + public Robot() { arm = new Arm(); } } - class Arm { + class Arm { public final Trigger atLowStop = new Trigger(...); public final Trigger atHighStop = new Trigger(...); private Rotation2d lastPosition = getPosition(); - public Rotation2d getPosition() { + public Rotation2d getPosition() { // ... } - public Measure> getSpeed() { + public Measure> getSpeed() { // ... } } - ``` + ``` .. tab-item:: Code with logging (minimal) @@ -103,21 +103,21 @@ The names of log entries can be changed using the ``name`` configuration option @Logged public class Robot extends RobotBase { private final Arm arm; // Anything loggable within the arm object will be logged under an "arm" entry - public Robot() { + public Robot() { arm = new Arm(); - Epilogue.bind(this); + Epilogue.bind(this); } } - @Logged + @Logged class Arm { public final Trigger atLowStop = new Trigger(...); // Logged as a boolean in an "atLowStop" entry public final Trigger atHighStop = new Trigger(...); // Logged as a boolean in an "atHighStop" entry private Rotation2d lastPosition = getPosition(); // Logged as a Rotation2d struct in a "lastPosition" entry - // Logged as a Rotation2d struct object in a "getPosition" entry + // Logged as a Rotation2d struct object in a "getPosition" entry public Rotation2d getPosition() { // ... } - // Logged as a double in terms of radians per second in a "getSpeed" entry + // Logged as a double in terms of radians per second in a "getSpeed" entry public Measure> getSpeed() { // ... } @@ -141,25 +141,25 @@ The names of log entries can be changed using the ``name`` configuration option public class Robot extends RobotBase { @Logged(name = "Arm") private Arm arm; - public Robot() { + public Robot() { arm = new Arm(); - DataLogManager.start(); + DataLogManager.start(); Epilogue.bind(this); } } - @Logged(strategy = OPT_IN) + @Logged(strategy = OPT_IN) class Arm { @Logged(name = "At Low Stop", importance = DEBUG) public final Trigger atLowStop = new Trigger(...); - @Logged(name = "At High Stop", importance = DEBUG) + @Logged(name = "At High Stop", importance = DEBUG) public final Trigger atHighStop = new Trigger(...); - @NotLogged // Redundant because the class strategy is opt-in + @NotLogged // Redundant because the class strategy is opt-in private Rotation2d lastPosition = getPosition(); // No @Logged annotation, not logged - @Logged(name = "Position", importance = CRITICAL) + @Logged(name = "Position", importance = CRITICAL) public Rotation2d getPosition() { // ... } - @Logged(name = "Speed", importance = CRITICAL) + @Logged(name = "Speed", importance = CRITICAL) public Measure> getSpeed() { // ... } @@ -211,19 +211,19 @@ If your main robot class inherits from ``TimedRobot``, the generated ``Epilogue` // Log only to disk, instead of the default NetworkTables logging // Note that this means data cannot be analyzed in realtime by a dashboard config.dataLogger = new FileLogger(DataLogManager.getLog()); - if (isSimulation()) { + if (isSimulation()) { // If running in simulation, then we'd want to re-throw any errors that // occur so we can debug and fix them! config.errorHandler = ErrorHandler.crashOnError(); } // Change the root data path config.root = "Telemetry"; - // Only log critical information instead of the default DEBUG level. + // Only log critical information instead of the default DEBUG level. // This can be helpful in a pinch to reduce network bandwidth or log file size // while still logging important information. config.minimumImportance = Logged.Importance.CRITICAL; }); - Epilogue.bind(this); + Epilogue.bind(this); } } ``` @@ -246,22 +246,22 @@ Custom loggers can be declared in any package, and only need to have the ``@Cust public double getAppliedVoltage(); public double getInputCurrent(); } - @CustomLoggerFor(VendorMotor.class) + @CustomLoggerFor(VendorMotor.class) public class YourCustomVendorMotorLogger extends ClassSpecificLogger { public YourCustomVendorMotorLogger() { super(VendorMotor.class); } - @Override + @Override public void update(DataLogger dataLogger, VendorMotor motor) { if (Epilogue.shouldLog(Logged.Importance.DEBUG)) { dataLogger.log("Faults", motor.getFaults()); } - dataLogger.log("Requested Speed (Duty Cycle)", motor.get()); + dataLogger.log("Requested Speed (Duty Cycle)", motor.get()); dataLogger.log("Motor Voltage (V)", motor.getAppliedVoltage()); dataLogger.log("Input Current (A)", motor.getInputCurrent()); } } - ``` + ``` Caveats and Limitations ----------------------- diff --git a/source/docs/software/telemetry/robot-telemetry-with-sendable.rst b/source/docs/software/telemetry/robot-telemetry-with-sendable.rst index e7e476d219..bf25a6d560 100644 --- a/source/docs/software/telemetry/robot-telemetry-with-sendable.rst +++ b/source/docs/software/telemetry/robot-telemetry-with-sendable.rst @@ -32,7 +32,7 @@ To send a ``Sendable`` object to the dashboard, simply use the dashboard's ``put ```python from wpilib import SmartDashboard - SmartDashboard.putData("Arm PID", armPIDController) + SmartDashboard.putData("Arm PID", armPIDController) ``` Additionally, some ``Sendable`` classes bind setters to the data values sent *from the dashboard to the robot*, allowing remote tuning of robot parameters. diff --git a/source/docs/software/vision-processing/introduction/cameraserver-class.rst b/source/docs/software/vision-processing/introduction/cameraserver-class.rst index cae75d7b44..663db8e440 100644 --- a/source/docs/software/vision-processing/introduction/cameraserver-class.rst +++ b/source/docs/software/vision-processing/introduction/cameraserver-class.rst @@ -77,21 +77,21 @@ The above graph is what the following CameraServer snippet creates: import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.cscore.CvSink; import edu.wpi.cscore.CvSource; - // Creates UsbCamera and MjpegServer [1] and connects them + // Creates UsbCamera and MjpegServer [1] and connects them CameraServer.startAutomaticCapture(); - // Creates the CvSink and connects it to the UsbCamera + // Creates the CvSink and connects it to the UsbCamera CvSink cvSink = CameraServer.getVideo(); - // Creates the CvSource and MjpegServer [2] and connects them + // Creates the CvSource and MjpegServer [2] and connects them CvSource outputStream = CameraServer.putVideo("Blur", 640, 480); ``` ```c++ #include "cameraserver/CameraServer.h" - // Creates UsbCamera and MjpegServer [1] and connects them + // Creates UsbCamera and MjpegServer [1] and connects them frc::CameraServer::StartAutomaticCapture(); - // Creates the CvSink and connects it to the UsbCamera + // Creates the CvSink and connects it to the UsbCamera cs::CvSink cvSink = frc::CameraServer::GetVideo(); - // Creates the CvSource and MjpegServer [2] and connects them + // Creates the CvSource and MjpegServer [2] and connects them cs::CvSource outputStream = frc::CameraServer::PutVideo("Blur", 640, 480); ``` @@ -104,14 +104,14 @@ The CameraServer implementation effectively does the following at the cscore lev import edu.wpi.cscore.CvSource; import edu.wpi.cscore.MjpegServer; import edu.wpi.cscore.UsbCamera; - // Creates UsbCamera and MjpegServer [1] and connects them + // Creates UsbCamera and MjpegServer [1] and connects them UsbCamera usbCamera = new UsbCamera("USB Camera 0", 0); MjpegServer mjpegServer1 = new MjpegServer("serve_USB Camera 0", 1181); mjpegServer1.setSource(usbCamera); - // Creates the CvSink and connects it to the UsbCamera + // Creates the CvSink and connects it to the UsbCamera CvSink cvSink = new CvSink("opencv_USB Camera 0"); cvSink.setSource(usbCamera); - // Creates the CvSource and MjpegServer [2] and connects them + // Creates the CvSource and MjpegServer [2] and connects them CvSource outputStream = new CvSource("Blur", PixelFormat.kMJPEG, 640, 480, 30); MjpegServer mjpegServer2 = new MjpegServer("serve_Blur", 1182); mjpegServer2.setSource(outputStream); @@ -119,14 +119,14 @@ The CameraServer implementation effectively does the following at the cscore lev ```c++ #include "cscore_oo.h" - // Creates UsbCamera and MjpegServer [1] and connects them + // Creates UsbCamera and MjpegServer [1] and connects them cs::UsbCamera usbCamera("USB Camera 0", 0); cs::MjpegServer mjpegServer1("serve_USB Camera 0", 1181); mjpegServer1.SetSource(usbCamera); - // Creates the CvSink and connects it to the UsbCamera + // Creates the CvSink and connects it to the UsbCamera cs::CvSink cvSink("opencv_USB Camera 0"); cvSink.SetSource(usbCamera); - // Creates the CvSource and MjpegServer [2] and connects them + // Creates the CvSource and MjpegServer [2] and connects them cs::CvSource outputStream("Blur", cs::PixelFormat::kMJPEG, 640, 480, 30); cs::MjpegServer mjpegServer2("serve_Blur", 1182); mjpegServer2.SetSource(outputStream); 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 7f226e1678..1e3ee1e1f5 100644 --- a/source/docs/software/vision-processing/roborio/using-multiple-cameras.rst +++ b/source/docs/software/vision-processing/roborio/using-multiple-cameras.rst @@ -14,13 +14,13 @@ If you're interested in just switching what the driver sees, and are using Smart UsbCamera camera2; Joystick joy1 = new Joystick(0); NetworkTableEntry cameraSelection; - @Override + @Override public void robotInit() { camera1 = CameraServer.startAutomaticCapture(0); camera2 = CameraServer.startAutomaticCapture(1); - cameraSelection = NetworkTableInstance.getDefault().getTable("").getEntry("CameraSelection"); + cameraSelection = NetworkTableInstance.getDefault().getTable("").getEntry("CameraSelection"); } - @Override + @Override public void teleopPeriodic() { if (joy1.getTriggerPressed()) { System.out.println("Setting camera 2"); @@ -39,13 +39,13 @@ If you're interested in just switching what the driver sees, and are using Smart cs::UsbCamera camera1; cs::UsbCamera camera2; frc::Joystick joy1{0}; - nt::NetworkTableEntry cameraSelection; - void RobotInit() override { + nt::NetworkTableEntry cameraSelection; + void RobotInit() override { camera1 = frc::CameraServer::StartAutomaticCapture(0); camera2 = frc::CameraServer::StartAutomaticCapture(1); - cameraSelection = nt::NetworkTableInstance::GetDefault().GetTable("")->GetEntry("CameraSelection"); + cameraSelection = nt::NetworkTableInstance::GetDefault().GetTable("")->GetEntry("CameraSelection"); } - void TeleopPeriodic() override { + void TeleopPeriodic() override { if (joy1.GetTriggerPressed()) { std::cout << "Setting Camera 2" << std::endl; cameraSelection.SetString(camera2.GetName()); @@ -66,12 +66,12 @@ If you're interested in just switching what the driver sees, and are using Smart ```python import wpilib from ntcore import NetworkTableInstance - class MyRobot(wpilib.TimedRobot): + class MyRobot(wpilib.TimedRobot): def robotInit(self): self.joy1 = wpilib.Joystick(0) self.cameraSelection = NetworkTableInstance.getDefault().getTable("").getEntry("CameraSelection") wpilib.CameraServer.launch("vision.py:main") - def teleopPeriodic(self): + def teleopPeriodic(self): if self.joy1.getTriggerPressed(): print("Setting camera 2") self.cameraSelection.setString("USB Camera 1") @@ -84,19 +84,19 @@ If you're interested in just switching what the driver sees, and are using Smart ```python from cscore import CameraServer - def main(): + def main(): CameraServer.enableLogging() - camera1 = CameraServer.startAutomaticCapture(0) + camera1 = CameraServer.startAutomaticCapture(0) camera2 = CameraServer.startAutomaticCapture(1) - CameraServer.waitForever() + CameraServer.waitForever() ``` ``pyproject.toml`` contents (this only shows the portions you need to update): ```toml [tool.robotpy] - ... - # Add cscore to the robotpy-extras list + ... + # Add cscore to the robotpy-extras list robotpy_extras = ["cscore"] ``` @@ -109,13 +109,13 @@ If you're using some other dashboard, you can change the camera used by the came UsbCamera camera2; VideoSink server; Joystick joy1 = new Joystick(0); - @Override + @Override public void robotInit() { camera1 = CameraServer.startAutomaticCapture(0); camera2 = CameraServer.startAutomaticCapture(1); server = CameraServer.getServer(); } - @Override + @Override public void teleopPeriodic() { if (joy1.getTriggerPressed()) { System.out.println("Setting camera 2"); @@ -133,12 +133,12 @@ If you're using some other dashboard, you can change the camera used by the came cs::VideoSink server; frc::Joystick joy1{0}; bool prevTrigger = false; - void RobotInit() override { + void RobotInit() override { camera1 = frc::CameraServer::StartAutomaticCapture(0); camera2 = frc::CameraServer::StartAutomaticCapture(1); server = frc::CameraServer::GetServer(); } - void TeleopPeriodic() override { + void TeleopPeriodic() override { if (joy1.GetTrigger() && !prevTrigger) { std::cout << "Setting Camera 2" << std::endl; server.SetSource(camera2); @@ -169,15 +169,15 @@ By default, the cscore library is pretty aggressive in turning off cameras not i UsbCamera camera2; VideoSink server; Joystick joy1 = new Joystick(0); - @Override + @Override public void robotInit() { camera1 = CameraServer.startAutomaticCapture(0); camera2 = CameraServer.startAutomaticCapture(1); server = CameraServer.getServer(); - camera1.setConnectionStrategy(ConnectionStrategy.kKeepOpen); + camera1.setConnectionStrategy(ConnectionStrategy.kKeepOpen); camera2.setConnectionStrategy(ConnectionStrategy.kKeepOpen); } - @Override + @Override public void teleopPeriodic() { if (joy1.getTriggerPressed()) { System.out.println("Setting camera 2"); @@ -205,7 +205,7 @@ By default, the cscore library is pretty aggressive in turning off cameras not i camera1.SetConnectionStrategy(cs::VideoSource::ConnectionStrategy::kConnectionKeepOpen); camera2.SetConnectionStrategy(cs::VideoSource::ConnectionStrategy::kConnectionKeepOpen); } - void TeleopPeriodic() override { + void TeleopPeriodic() override { if (joy1.GetTrigger() && !prevTrigger) { std::cout << "Setting Camera 2" << std::endl; server.SetSource(camera2); @@ -227,12 +227,12 @@ By default, the cscore library is pretty aggressive in turning off cameras not i ```python import wpilib from ntcore import NetworkTableInstance - class MyRobot(wpilib.TimedRobot): + class MyRobot(wpilib.TimedRobot): def robotInit(self): self.joy1 = wpilib.Joystick(0) self.cameraSelection = NetworkTableInstance.getDefault().getTable("").getEntry("CameraSelection") wpilib.CameraServer.launch("vision.py:main") - def teleopPeriodic(self): + def teleopPeriodic(self): if self.joy1.getTriggerPressed(): print("Setting camera 2") self.cameraSelection.setString("USB Camera 1") @@ -247,9 +247,9 @@ By default, the cscore library is pretty aggressive in turning off cameras not i from cscore import CameraServer, VideoSource def main(): CameraServer.enableLogging() - camera1 = CameraServer.startAutomaticCapture(0) + camera1 = CameraServer.startAutomaticCapture(0) camera2 = CameraServer.startAutomaticCapture(1) - camera1.setConnectionStrategy(VideoSource.ConnectionStrategy.kConnectionKeepOpen) + camera1.setConnectionStrategy(VideoSource.ConnectionStrategy.kConnectionKeepOpen) camera2.setConnectionStrategy(VideoSource.ConnectionStrategy.kConnectionKeepOpen) CameraServer.waitForever() ``` @@ -258,8 +258,8 @@ By default, the cscore library is pretty aggressive in turning off cameras not i ```toml [tool.robotpy] - ... - # Add cscore to the robotpy-extras list + ... + # Add cscore to the robotpy-extras list robotpy_extras = ["cscore"] ``` 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 18fa4dd4d9..bc114a2e65 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 @@ -87,8 +87,8 @@ In the following example a thread created in robotInit() gets the Camera Server ```toml [tool.robotpy] - ... - # Add cscore to the robotpy-extras list + ... + # Add cscore to the robotpy-extras list robotpy_extras = ["cscore"] ``` 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 a984396891..ed38bbb957 100644 --- a/source/docs/software/vision-processing/wpilibpi/basic-vision-example.rst +++ b/source/docs/software/vision-processing/wpilibpi/basic-vision-example.rst @@ -7,59 +7,59 @@ This is an example of a basic vision setup that posts the target's location in t ```py from cscore import CameraServer import ntcore - import cv2 + import cv2 import json import numpy as np import time - def main(): + def main(): with open('/boot/frc.json') as f: config = json.load(f) camera = config['cameras'][0] width = camera['width'] height = camera['height'] - nt = ntcore.NetworkTableInstance.getDefault() - CameraServer.startAutomaticCapture() - input_stream = CameraServer.getVideo() + nt = ntcore.NetworkTableInstance.getDefault() + CameraServer.startAutomaticCapture() + input_stream = CameraServer.getVideo() output_stream = CameraServer.putVideo('Processed', width, height) - # Table for vision output information + # Table for vision output information vision_nt = nt.getTable('Vision') - # Allocating new images is very expensive, always try to preallocate + # Allocating new images is very expensive, always try to preallocate img = np.zeros(shape=(240, 320, 3), dtype=np.uint8) - # Wait for NetworkTables to start + # Wait for NetworkTables to start time.sleep(0.5) - while True: + while True: start_time = time.time() - frame_time, input_img = input_stream.grabFrame(img) + frame_time, input_img = input_stream.grabFrame(img) output_img = np.copy(input_img) - # Notify output of error and skip iteration + # Notify output of error and skip iteration if frame_time == 0: - output_stream.notifyError(input_stream.getError()) - continue - # Convert to HSV and threshold image + output_stream.notifyError(input_stream.getError()) + continue + # Convert to HSV and threshold image hsv_img = cv2.cvtColor(input_img, cv2.COLOR_BGR2HSV) binary_img = cv2.inRange(hsv_img, (0, 0, 100), (85, 255, 255)) - _, contour_list = cv2.findContours(binary_img, mode=cv2.RETR_EXTERNAL, method=cv2.CHAIN_APPROX_SIMPLE) - x_list = [] + _, contour_list = cv2.findContours(binary_img, mode=cv2.RETR_EXTERNAL, method=cv2.CHAIN_APPROX_SIMPLE) + x_list = [] y_list = [] for contour in contour_list: - # Ignore small contours that could be because of noise/bad thresholding + # Ignore small contours that could be because of noise/bad thresholding if cv2.contourArea(contour) < 15: continue - cv2.drawContours(output_img, contour, -1, color=(255, 255, 255), thickness=-1) - rect = cv2.minAreaRect(contour) + cv2.drawContours(output_img, contour, -1, color=(255, 255, 255), thickness=-1) + rect = cv2.minAreaRect(contour) center, size, angle = rect center = tuple([int(dim) for dim in center]) # Convert to int so we can draw - # Draw rectangle and circle + # Draw rectangle and circle cv2.drawContours(output_img, [cv2.boxPoints(rect).astype(int)], -1, color=(0, 0, 255), thickness=2) cv2.circle(output_img, center=center, radius=3, color=(0, 0, 255), thickness=-1) - x_list.append((center[0] - width / 2) / (width / 2)) + x_list.append((center[0] - width / 2) / (width / 2)) x_list.append((center[1] - width / 2) / (width / 2)) - vision_nt.putNumberArray('target_x', x_list) + vision_nt.putNumberArray('target_x', x_list) vision_nt.putNumberArray('target_y', y_list) - processing_time = time.time() - start_time + processing_time = time.time() - start_time fps = 1 / processing_time cv2.putText(output_img, str(round(fps, 1)), (0, 40), cv2.FONT_HERSHEY_SIMPLEX, 1, (255, 255, 255)) output_stream.putFrame(output_img) - main() + main() ``` diff --git a/source/docs/software/vision-processing/wpilibpi/using-cameraserver.rst b/source/docs/software/vision-processing/wpilibpi/using-cameraserver.rst index 674d9e0969..a63070fa3b 100644 --- a/source/docs/software/vision-processing/wpilibpi/using-cameraserver.rst +++ b/source/docs/software/vision-processing/wpilibpi/using-cameraserver.rst @@ -10,13 +10,13 @@ The WPILibPi image comes with all the necessary libraries to make your own visio from cscore import CameraServer import cv2 import numpy as np - CameraServer.enableLogging() - camera = CameraServer.startAutomaticCapture() + CameraServer.enableLogging() + camera = CameraServer.startAutomaticCapture() camera.setResolution(width, height) - sink = cs.getVideo() - while True: + sink = cs.getVideo() + while True: time, input_img = cvSink.grabFrame(input_img) - if time == 0: # There is an error + if time == 0: # There is an error continue ``` @@ -37,16 +37,16 @@ Sometimes, you may want to send processed video frames back to the CameraServer # # CameraServer initialization code here # - output = cs.putVideo("Name", width, height) - while True: + output = cs.putVideo("Name", width, height) + while True: time, input_img = cvSink.grabFrame(input_img) if time == 0: # There is an error - output.notifyError(sink.getError()) - continue - # + output.notifyError(sink.getError()) + continue + # # Insert processing code here # - output.putFrame(processed_img) + output.putFrame(processed_img) ``` As an example, the processing code could outline the target in red, and show the corners in yellow for debugging purposes. 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 01d7d47227..57fee6fc4d 100644 --- a/source/docs/software/vision-processing/wpilibpi/working-with-contours.rst +++ b/source/docs/software/vision-processing/wpilibpi/working-with-contours.rst @@ -20,7 +20,7 @@ In cases where there is only one vision target, you can just take the largest co for contour in contours: if cv2.contourArea(contour) > cv2.contourArea(largest): largest = contour - # + # # Contour processing code # ``` @@ -71,15 +71,15 @@ You can use NetworkTables to send these properties to the Driver Station and the ```py import ntcore - nt = ntcore.NetworkTableInstance.getDefault().getTable('vision') - # + nt = ntcore.NetworkTableInstance.getDefault().getTable('vision') + # # Initialization code here # - while True: - # + while True: + # # Image processing code here # - nt.putNumber('center_x', center_x) + nt.putNumber('center_x', center_x) nt.putNumber('center_y', center_y) ``` 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 d0d36b1008..300c609d61 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/device-sim.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/device-sim.rst @@ -65,7 +65,7 @@ In C++, save the ``CallbackStore`` object in the right scope - the callback will } } CallbackStore store = simEncoder.registerCountCallback(callback); - store.close(); // cancel the callback + store.close(); // cancel the callback ``` ```c++ 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 8c601fee9e..6e38199b5c 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 @@ -30,7 +30,7 @@ You can calculate the measurement noise of your sensors by taking multiple data 60.0, // The mass of the robot is 60 kg. Units.inchesToMeters(3), // The robot uses 3" radius wheels. 0.7112, // The track width is 0.7112 meters. - // The standard deviations for measurement noise: + // The standard deviations for measurement noise: // x and y: 0.001 m // heading: 0.001 rad // l and r velocity: 0.1 m/s @@ -40,8 +40,8 @@ You can calculate the measurement noise of your sensors by taking multiple data ```c++ #include - ... - // Create the simulation model of our drivetrain. + ... + // Create the simulation model of our drivetrain. frc::sim::DifferentialDrivetrainSim m_driveSim{ frc::DCMotor::GetNEO(2), // 2 NEO motors on each side of the drivetrain. 7.29, // 7.29:1 gearing reduction. @@ -49,7 +49,7 @@ You can calculate the measurement noise of your sensors by taking multiple data 60_kg, // The mass of the robot is 60 kg. 3_in, // The robot uses 3" radius wheels. 0.7112_m, // The track width is 0.7112 meters. - // The standard deviations for measurement noise: + // The standard deviations for measurement noise: // x and y: 0.001 m // heading: 0.001 rad // l and r velocity: 0.1 m/s @@ -86,15 +86,15 @@ You can calculate the measurement noise of your sensors by taking multiple data static final double KaLinear = 0.2; static final double KvAngular = 1.5; static final double KaAngular = 0.3; - // Create the simulation model of our drivetrain. + // Create the simulation model of our drivetrain. private DifferentialDrivetrainSim m_driveSim = new DifferentialDrivetrainSim( - // Create a linear system from our identification gains. + // Create a linear system from our identification gains. LinearSystemId.identifyDrivetrainSystem(KvLinear, KaLinear, KvAngular, KaAngular), DCMotor.getNEO(2), // 2 NEO motors on each side of the drivetrain. 7.29, // 7.29:1 gearing reduction. 0.7112, // The track width is 0.7112 meters. Units.inchesToMeters(3), // The robot uses 3" radius wheels. - // The standard deviations for measurement noise: + // The standard deviations for measurement noise: // x and y: 0.001 m // heading: 0.001 rad // l and r velocity: 0.1 m/s @@ -110,8 +110,8 @@ You can calculate the measurement noise of your sensors by taking multiple data #include #include #include - ... - // Create our feedforward gain constants (from the identification + ... + // Create our feedforward gain constants (from the identification // tool). Note that these need to have correct units. static constexpr auto KvLinear = 1.98_V / 1_mps; static constexpr auto KaLinear = 0.2_V / 1_mps_sq; @@ -119,7 +119,7 @@ You can calculate the measurement noise of your sensors by taking multiple data static constexpr auto KaAngular = 0.3_V / 1_rad_per_s_sq; // The track width is 0.7112 meters. static constexpr auto kTrackwidth = 0.7112_m; - // Create the simulation model of our drivetrain. + // Create the simulation model of our drivetrain. frc::sim::DifferentialDrivetrainSim m_driveSim{ // Create a linear system from our identification gains. frc::LinearSystemId::IdentifyDrivetrainSystem( @@ -128,7 +128,7 @@ You can calculate the measurement noise of your sensors by taking multiple data frc::DCMotor::GetNEO(2), // 2 NEO motors on each side of the drivetrain. 7.29, // 7.29:1 gearing reduction. 3_in, // The robot uses 3" radius wheels. - // The standard deviations for measurement noise: + // The standard deviations for measurement noise: // x and y: 0.001 m // heading: 0.001 rad // l and r velocity: 0.1 m/s @@ -164,8 +164,8 @@ You can calculate the measurement noise of your sensors by taking multiple data ```c++ #include - ... - frc::sim::DifferentialDrivetrainSim m_driveSim = + ... + frc::sim::DifferentialDrivetrainSim m_driveSim = frc::sim::DifferentialDrivetrainSim::CreateKitbotSim( frc::sim::DifferentialDrivetrainSim::KitbotMotor::DualCIMPerSide, // 2 CIMs per side. frc::sim::DifferentialDrivetrainSim::KitbotGearing::k10p71, // 10.71:1 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 ccb564d0f0..35fe5ad15a 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 @@ -13,8 +13,8 @@ The robot pose can be visualized on the Simulator GUI (during simulation) or on ```c++ #include - .. - frc::Field2d m_field; + ... + frc::Field2d m_field; ``` This ``Field2d`` instance must then be sent over NetworkTables. The best place to do this is in the constructor of your subsystem. @@ -29,7 +29,7 @@ This ``Field2d`` instance must then be sent over NetworkTables. The best place t ```c++ #include - Drivetrain() { + Drivetrain() { ... frc::SmartDashboard::PutData("Field", &m_field); } 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 3b571a92d7..d73f5e88b3 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 @@ -14,7 +14,7 @@ The ``EncoderSim`` class allows users to set encoder positions and velocities on // create to use on a real robot. private Encoder m_leftEncoder = new Encoder(0, 1); private Encoder m_rightEncoder = new Encoder(2, 3); - // These are our EncoderSim objects, which we will only use in + // These are our EncoderSim objects, which we will only use in // simulation. However, you do not need to comment out these // declarations when you are deploying code to the roboRIO. private EncoderSim m_leftEncoderSim = new EncoderSim(m_leftEncoder); @@ -24,12 +24,12 @@ The ``EncoderSim`` class allows users to set encoder positions and velocities on ```c++ #include #include - ... - // These represent our regular encoder objects, which we would + ... + // These represent our regular encoder objects, which we would // create to use on a real robot. frc::Encoder m_leftEncoder{0, 1}; frc::Encoder m_rightEncoder{2, 3}; - // These are our EncoderSim objects, which we will only use in + // These are our EncoderSim objects, which we will only use in // simulation. However, you do not need to comment out these // declarations when you are deploying code to the roboRIO. frc::sim::EncoderSim m_leftEncoderSim{m_leftEncoder}; @@ -45,7 +45,7 @@ Similar to the ``EncoderSim`` class, simulated gyroscope classes also exist for ```java // Create our gyro object like we would on a real robot. private AnalogGyro m_gyro = new AnalogGyro(1); - // Create the simulated gyro object, used for setting the gyro + // Create the simulated gyro object, used for setting the gyro // angle. Like EncoderSim, this does not need to be commented out // when deploying code to the roboRIO. private AnalogGyroSim m_gyroSim = new AnalogGyroSim(m_gyro); @@ -54,10 +54,10 @@ Similar to the ``EncoderSim`` class, simulated gyroscope classes also exist for ```c++ #include #include - ... - // Create our gyro objectl ike we would on a real robot. + ... + // Create our gyro objectl ike we would on a real robot. frc::AnalogGyro m_gyro{1}; - // Create the simulated gyro object, used for setting the gyro + // Create the simulated gyro object, used for setting the gyro // angle. Like EncoderSim, this does not need to be commented out // when deploying code to the roboRIO. frc::sim::AnalogGyroSim m_gyroSim{m_gyro}; 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 c1a72f9160..0a3cda94b2 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 @@ -13,22 +13,22 @@ There are three main steps to updating the model: ```java private PWMSparkMax m_leftMotor = new PWMSparkMax(0); private PWMSparkMax m_rightMotor = new PWMSparkMax(1); - public Drivetrain() { + public Drivetrain() { ... m_leftEncoder.setDistancePerPulse(2 * Math.PI * kWheelRadius / kEncoderResolution); m_rightEncoder.setDistancePerPulse(2 * Math.PI * kWheelRadius / kEncoderResolution); } - public void simulationPeriodic() { + public void simulationPeriodic() { // Set the inputs to the system. Note that we need to convert // the [-1, 1] PWM signal to voltage by multiplying it by the // robot controller voltage. m_driveSim.setInputs(m_leftMotor.get() * RobotController.getInputVoltage(), m_rightMotor.get() * RobotController.getInputVoltage()); - // Advance the model by 20 ms. Note that if you are running this + // Advance the model by 20 ms. Note that if you are running this // subsystem in a separate thread or have changed the nominal timestep // of TimedRobot, this value needs to match it. m_driveSim.update(0.02); - // Update all of our sensors. + // Update all of our sensors. m_leftEncoderSim.setDistance(m_driveSim.getLeftPositionMeters()); m_leftEncoderSim.setRate(m_driveSim.getLeftVelocityMetersPerSecond()); m_rightEncoderSim.setDistance(m_driveSim.getRightPositionMeters()); @@ -40,23 +40,23 @@ There are three main steps to updating the model: ```c++ frc::PWMSparkMax m_leftMotor{0}; frc::PWMSparkMax m_rightMotor{1}; - Drivetrain() { + Drivetrain() { ... m_leftEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); m_rightEncoder.SetDistancePerPulse(2 * std::numbers::pi * kWheelRadius / kEncoderResolution); } - void SimulationPeriodic() { + void SimulationPeriodic() { // Set the inputs to the system. Note that we need to convert // the [-1, 1] PWM signal to voltage by multiplying it by the // robot controller voltage. m_driveSim.SetInputs( m_leftMotor.get() * units::volt_t(frc::RobotController::GetInputVoltage()), m_rightMotor.get() * units::volt_t(frc::RobotController::GetInputVoltage())); - // Advance the model by 20 ms. Note that if you are running this + // Advance the model by 20 ms. Note that if you are running this // subsystem in a separate thread or have changed the nominal timestep // of TimedRobot, this value needs to match it. m_driveSim.Update(20_ms); - // Update all of our sensors. + // Update all of our sensors. m_leftEncoderSim.SetDistance(m_driveSim.GetLeftPosition().value()); m_leftEncoderSim.SetRate(m_driveSim.GetLeftVelocity().value()); m_rightEncoderSim.SetDistance(m_driveSim.GetRightPosition().value()); 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 66362574fc..f364fa26f1 100644 --- a/source/docs/software/wpilib-tools/robot-simulation/simulation-gui.rst +++ b/source/docs/software/wpilib-tools/robot-simulation/simulation-gui.rst @@ -80,7 +80,7 @@ In cases where vendor libraries do not compile when running the robot simulation ```java TalonSRX motorLeft; TalonSRX motorRight; - public Robot() { + public Robot() { if (RobotBase.isReal()) { motorLeft = new TalonSRX(0); motorRight = new TalonSRX(1); 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 3885b7874b..04a8cfa8a0 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 @@ -15,12 +15,14 @@ The height constants and PID constants are automatically generated. ```java public class Elevator extends PIDSubsystem { - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS public static final double Bottom = 4.6; public static final double Stow = 1.65; public static final double Table_Height = 1.58; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS private AnalogPotentiometer pot;private PWMVictorSPX motor; //P I D Variables private static final double kP = 6.0; @@ -31,15 +33,15 @@ The height constants and PID constants are automatically generated. ``` ```c++ - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS - static constexpr const double Bottom = 4.6; - static constexpr const double Stow = 1.65; - static constexpr const double Table_Height = 1.58; + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS + static constexpr const double Bottom = 4.6; + static constexpr const double Stow = 1.65; + static constexpr const double Table_Height = 1.58; static constexpr const double kP = 6.0; - static constexpr const double kI = 0.0; - static constexpr const double kD = 0.0; - static constexpr const double kF = 0.0; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS + static constexpr const double kI = 0.0; + static constexpr const double kD = 0.0; + static constexpr const double kF = 0.0; + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS ``` ## Get Potentiometer Measurement @@ -51,7 +53,8 @@ The height constants and PID constants are automatically generated. public double getMeasurement() { // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SOURCE return pot.get(); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SOURCE + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SOURCE } ``` @@ -59,7 +62,8 @@ The height constants and PID constants are automatically generated. double Elevator::GetMeasurement() { // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SOURCE return m_pot.Get(); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SOURCE + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SOURCE } ``` @@ -70,13 +74,14 @@ The ``getMeasurement()`` method is used to set the value of the sensor that is p .. tab-set-code:: ```java - @Override - public void useOutput(double output, double setpoint) { - output += setpoint*kF; - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=OUTPUT - motor.set(output); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=OUTPUT - } + @Override + public void useOutput(double output, double setpoint) { + output += setpoint*kF; + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=OUTPUT + motor.set(output); + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=OUTPUT + } ``` ```c++ @@ -84,7 +89,8 @@ The ``getMeasurement()`` method is used to set the value of the sensor that is p output += setpoint*kF; // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=OUTPUT m_motor.Set(output); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=OUTPUT + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=OUTPUT } ``` 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 036bbea653..faabc50272 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 @@ -19,14 +19,16 @@ For more information on the organization of a Command Based robot, see :doc:`/do // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS m_chooser.setDefaultOption("Autonomous", new Autonomous()); // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS - SmartDashboard.putData("Auto Mode", m_chooser); + + SmartDashboard.putData("Auto Mode", m_chooser); ``` ```c++ // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS m_chooser.SetDefaultOption("Autonomous", new Autonomous()); // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS - frc::SmartDashboard::PutData("Auto Mode", &m_chooser); + + frc::SmartDashboard::PutData("Auto Mode", &m_chooser); ``` When the robot description is modified and code is re-exported RobotBuilder is designed to not modify any changes you made to the file, thus preserving your code. This makes RobotBuilder a full-lifecycle tool. To know what code is OK to be modified by RobotBuilder, it generates sections that will potentially have to be rewritten delimited with some special comments. These comments are shown in the example above. Don't add any code within these comment blocks, it will be rewritten next time the project is exported from RobotBuilder. @@ -54,15 +56,19 @@ Additionally, each file has a comment defining the type of file. If this is modi :linenos: :lineno-start: 11 :emphasize-lines: 19,50,70-75 - // ROBOTBUILDER TYPE: Robot. - package frc.robot; - import edu.wpi.first.hal.FRCNetComm.tInstances; + + // ROBOTBUILDER TYPE: Robot. + + package frc.robot; + + import edu.wpi.first.hal.FRCNetComm.tInstances; import edu.wpi.first.hal.FRCNetComm.tResourceType; import edu.wpi.first.hal.HAL; import edu.wpi.first.wpilibj.TimedRobot; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; - /** + + /** * The VM is configured to automatically run this class, and to call the * functions corresponding to each mode, as described in the TimedRobot * documentation. If you change the name of this class or the package after @@ -70,9 +76,12 @@ Additionally, each file has a comment defining the type of file. If this is modi * the project. */ public class Robot extends TimedRobot { // (1) - private Command m_autonomousCommand; - private RobotContainer m_robotContainer; - /** + + private Command m_autonomousCommand; + + private RobotContainer m_robotContainer; + + /** * This function is run when the robot is first started up and should be * used for any initialization code. */ @@ -83,7 +92,8 @@ Additionally, each file has a comment defining the type of file. If this is modi m_robotContainer = RobotContainer.getInstance(); HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_RobotBuilder); } - /** + + /** * This function is called every robot packet, no matter the mode. Use this for items like * diagnostics that you want ran during disabled, autonomous, teleoperated and test. * @@ -98,33 +108,40 @@ Additionally, each file has a comment defining the type of file. If this is modi // block in order for anything in the Command-based framework to work. CommandScheduler.getInstance().run(); // (2) } - /** + + + /** * This function is called once each time the robot enters Disabled mode. */ @Override public void disabledInit() { } - @Override + + @Override public void disabledPeriodic() { } - /** + + /** * This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */ @Override public void autonomousInit() { m_autonomousCommand = m_robotContainer.getAutonomousCommand(); // (3) - // schedule the autonomous command (example) + + // schedule the autonomous command (example) if (m_autonomousCommand != null) { m_autonomousCommand.schedule(); } } - /** + + /** * This function is called periodically during autonomous. */ @Override public void autonomousPeriodic() { } - @Override + + @Override public void teleopInit() { // This makes sure that the autonomous stops running when // teleop starts running. If you want the autonomous to @@ -134,25 +151,29 @@ Additionally, each file has a comment defining the type of file. If this is modi m_autonomousCommand.cancel(); } } - /** + + /** * This function is called periodically during operator control. */ @Override public void teleopPeriodic() { } - @Override + + @Override public void testInit() { // Cancels all running commands at the start of test mode. CommandScheduler.getInstance().cancelAll(); } - /** + + /** * This function is called periodically during test mode. */ @Override public void testPeriodic() { } - } - ``` + + } + ``` .. tab-item:: C++ (Header) @@ -160,12 +181,16 @@ Additionally, each file has a comment defining the type of file. If this is modi :linenos: :lineno-start: 11 :emphasize-lines: 9 - // ROBOTBUILDER TYPE: Robot. + + // ROBOTBUILDER TYPE: Robot. #pragma once - #include + + #include #include - #include "RobotContainer.h" - class Robot : public frc::TimedRobot { // {1} + + #include "RobotContainer.h" + + class Robot : public frc::TimedRobot { // {1} public: void RobotInit() override; void RobotPeriodic() override; @@ -176,13 +201,15 @@ Additionally, each file has a comment defining the type of file. If this is modi void TeleopInit() override; void TeleopPeriodic() override; void TestPeriodic() override; - private: + + private: // Have it null by default so that if testing teleop it // doesn't have undefined behavior and potentially crash. frc2::Command* m_autonomousCommand = nullptr; - RobotContainer* m_container = RobotContainer::GetInstance(); + + RobotContainer* m_container = RobotContainer::GetInstance(); }; - ``` + ``` .. tab-item:: C++ (Source) @@ -190,12 +217,17 @@ Additionally, each file has a comment defining the type of file. If this is modi :linenos: :lineno-start: 11 :emphasize-lines: 18,34-38 - // ROBOTBUILDER TYPE: Robot. - #include "Robot.h" - #include + + // ROBOTBUILDER TYPE: Robot. + + #include "Robot.h" + + #include #include - void Robot::RobotInit() {} - /** + + void Robot::RobotInit() {} + + /** * This function is called every robot packet, no matter the mode. Use * this for items like diagnostics that you want to run during disabled, * autonomous, teleoperated and test. @@ -204,25 +236,31 @@ Additionally, each file has a comment defining the type of file. If this is modi * LiveWindow and SmartDashboard integrated updating. */ void Robot::RobotPeriodic() { frc2::CommandScheduler::GetInstance().Run(); } // (2) - /** + + /** * This function is called once each time the robot enters Disabled mode. You * can use it to reset any subsystem information you want to clear when the * robot is disabled. */ void Robot::DisabledInit() {} - void Robot::DisabledPeriodic() {} - /** + + void Robot::DisabledPeriodic() {} + + /** * This autonomous runs the autonomous command selected by your {@link * RobotContainer} class. */ void Robot::AutonomousInit() { m_autonomousCommand = m_container->GetAutonomousCommand(); // {3} - if (m_autonomousCommand != nullptr) { + + if (m_autonomousCommand != nullptr) { m_autonomousCommand->Schedule(); } } - void Robot::AutonomousPeriodic() {} - void Robot::TeleopInit() { + + void Robot::AutonomousPeriodic() {} + + void Robot::TeleopInit() { // This makes sure that the autonomous stops running when // teleop starts running. If you want the autonomous to // continue until interrupted by another command, remove @@ -232,18 +270,21 @@ Additionally, each file has a comment defining the type of file. If this is modi m_autonomousCommand = nullptr; } } - /** + + /** * This function is called periodically during operator control. */ void Robot::TeleopPeriodic() {} - /** + + /** * This function is called periodically during test mode. */ void Robot::TestPeriodic() {} - #ifndef RUNNING_FRC_TESTS + + #ifndef RUNNING_FRC_TESTS int main() { return frc::StartRobot(); } #endif - ``` + ``` This is the main program generated by RobotBuilder. There are a number of parts to this program (highlighted sections): @@ -261,42 +302,56 @@ This is the main program generated by RobotBuilder. There are a number of parts :linenos: :lineno-start: 11 :emphasize-lines: 33-36, 39, 62, 81, 92, 112 - // ROBOTBUILDER TYPE: RobotContainer. - package frc.robot; - import frc.robot.commands.*; + + // ROBOTBUILDER TYPE: RobotContainer. + + package frc.robot; + + import frc.robot.commands.*; import frc.robot.subsystems.*; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior; - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.InstantCommand; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj2.command.button.JoystickButton; import frc.robot.subsystems.*; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS - /** + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + + + /** * This class is where the bulk of the robot should be declared. Since Command-based is a * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot} * periodic methods (other than the scheduler calls). Instead, the structure of the robot * (including subsystems, commands, and button mappings) should be declared here. */ public class RobotContainer { - private static RobotContainer m_robotContainer = new RobotContainer(); - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + private static RobotContainer m_robotContainer = new RobotContainer(); + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS // The robot's subsystems public final Wrist m_wrist = new Wrist(); // (1) public final Elevator m_elevator = new Elevator(); public final Claw m_claw = new Claw(); public final Drivetrain m_drivetrain = new Drivetrain(); - // Joysticks + + // Joysticks private final Joystick joystick2 = new Joystick(2); // (3) private final Joystick joystick1 = new Joystick(1); private final Joystick logitechController = new Joystick(0); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS - // A chooser for autonomous commands + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + + // A chooser for autonomous commands SendableChooser m_chooser = new SendableChooser<>(); - /** + + /** * The container for the robot. Contains subsystems, OI devices, and commands. */ private RobotContainer() { @@ -306,7 +361,9 @@ This is the main program generated by RobotBuilder. There are a number of parts SmartDashboard.putData(m_elevator); SmartDashboard.putData(m_claw); SmartDashboard.putData(m_drivetrain); - // SmartDashboard Buttons + + + // SmartDashboard Buttons SmartDashboard.putData("Close Claw", new CloseClaw( m_claw )); // (6) SmartDashboard.putData("Open Claw: OpenTime", new OpenClaw(1.0, m_claw)); SmartDashboard.putData("Pickup", new Pickup()); @@ -319,26 +376,36 @@ This is the main program generated by RobotBuilder. There are a number of parts SmartDashboard.putData("Set Wrist Setpoint: Raise Wrist", new SetWristSetpoint(-45, m_wrist)); SmartDashboard.putData("Drive: Straight3Meters", new Drive(3, 0, m_drivetrain)); SmartDashboard.putData("Drive: Place", new Drive(Drivetrain.PlaceDistance, Drivetrain.BackAwayDistance, m_drivetrain)); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SMARTDASHBOARD + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SMARTDASHBOARD // Configure the button bindings configureButtonBindings(); - // Configure default commands + + // Configure default commands // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SUBSYSTEM_DEFAULT_COMMAND m_drivetrain.setDefaultCommand(new TankDrive(() -> getJoystick1().getY(), () -> getJoystick2().getY(), m_drivetrain)); // (5) - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SUBSYSTEM_DEFAULT_COMMAND - // Configure autonomous sendable chooser + + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SUBSYSTEM_DEFAULT_COMMAND + + // Configure autonomous sendable chooser // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS - m_chooser.addOption("Set Elevator Setpoint: Bottom", new SetElevatorSetpoint(0, m_elevator)); + + m_chooser.addOption("Set Elevator Setpoint: Bottom", new SetElevatorSetpoint(0, m_elevator)); m_chooser.addOption("Set Elevator Setpoint: Platform", new SetElevatorSetpoint(0.2, m_elevator)); m_chooser.addOption("Set Elevator Setpoint: Top", new SetElevatorSetpoint(0.3, m_elevator)); m_chooser.setDefaultOption("Autonomous", new Autonomous()); // (2) - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS - SmartDashboard.putData("Auto Mode", m_chooser); + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS + + SmartDashboard.putData("Auto Mode", m_chooser); } - public static RobotContainer getInstance() { + + public static RobotContainer getInstance() { return m_robotContainer; } - /** + + /** * Use this method to define your button->command mappings. Buttons can be created by * instantiating a {@link GenericHID} or one of its subclasses ({@link * edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a @@ -349,34 +416,50 @@ This is the main program generated by RobotBuilder. There are a number of parts // Create some buttons final JoystickButton r1 = new JoystickButton(logitechController, 12); // (4) r1.onTrue(new Autonomous().withInterruptBehavior(InterruptionBehavior.kCancelSelf)); - final JoystickButton l1 = new JoystickButton(logitechController, 11); + + final JoystickButton l1 = new JoystickButton(logitechController, 11); l1.onTrue(new Place().withInterruptBehavior(InterruptionBehavior.kCancelSelf)); - final JoystickButton r2 = new JoystickButton(logitechController, 10); + + final JoystickButton r2 = new JoystickButton(logitechController, 10); r2.onTrue(new Pickup().withInterruptBehavior(InterruptionBehavior.kCancelSelf)); - final JoystickButton l2 = new JoystickButton(logitechController, 9); + + final JoystickButton l2 = new JoystickButton(logitechController, 9); l2.onTrue(new PrepareToPickup().withInterruptBehavior(InterruptionBehavior.kCancelSelf)); - final JoystickButton dpadLeft = new JoystickButton(logitechController, 8); + + final JoystickButton dpadLeft = new JoystickButton(logitechController, 8); dpadLeft.onTrue(new OpenClaw(1.0, m_claw).withInterruptBehavior(InterruptionBehavior.kCancelSelf)); - final JoystickButton dpadRight = new JoystickButton(logitechController, 6); + + final JoystickButton dpadRight = new JoystickButton(logitechController, 6); dpadRight.onTrue(new CloseClaw( m_claw ).withInterruptBehavior(InterruptionBehavior.kCancelSelf)); - final JoystickButton dpadDown = new JoystickButton(logitechController, 7); + + final JoystickButton dpadDown = new JoystickButton(logitechController, 7); dpadDown.onTrue(new SetElevatorSetpoint(0, m_elevator).withInterruptBehavior(InterruptionBehavior.kCancelSelf)); - final JoystickButton dpadUp = new JoystickButton(logitechController, 5); + + final JoystickButton dpadUp = new JoystickButton(logitechController, 5); dpadUp.onTrue(new SetElevatorSetpoint(0.3, m_elevator).withInterruptBehavior(InterruptionBehavior.kCancelSelf)); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=BUTTONS + + + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=BUTTONS } - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=FUNCTIONS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=FUNCTIONS public Joystick getLogitechController() { return logitechController; } - public Joystick getJoystick1() { + + public Joystick getJoystick1() { return joystick1; } - public Joystick getJoystick2() { + + public Joystick getJoystick2() { return joystick2; } - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=FUNCTIONS - /** + + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=FUNCTIONS + + /** * Use this to pass the autonomous command to the main {@link Robot} class. * * @return the command to run in autonomous @@ -385,8 +468,10 @@ This is the main program generated by RobotBuilder. There are a number of parts // The selected command will be run in autonomous return m_chooser.getSelected(); } - } - ``` + + + } + ``` .. tab-item:: C++ (Header) @@ -394,16 +479,21 @@ This is the main program generated by RobotBuilder. There are a number of parts :linenos: :lineno-start: 11 :emphasize-lines: 38, 56 - // ROBOTBUILDER TYPE: RobotContainer. - #pragma once - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + // ROBOTBUILDER TYPE: RobotContainer. + + #pragma once + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES #include #include - #include "subsystems/Claw.h" + + #include "subsystems/Claw.h" #include "subsystems/Drivetrain.h" #include "subsystems/Elevator.h" #include "subsystems/Wrist.h" - #include "commands/Autonomous.h" + + #include "commands/Autonomous.h" #include "commands/CloseClaw.h" #include "commands/Drive.h" #include "commands/OpenClaw.h" @@ -415,33 +505,48 @@ This is the main program generated by RobotBuilder. There are a number of parts #include "commands/TankDrive.h" #include #include - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES - class RobotContainer { - public: - frc2::Command* GetAutonomousCommand(); + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + class RobotContainer { + + public: + + frc2::Command* GetAutonomousCommand(); static RobotContainer* GetInstance(); - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=PROTOTYPES + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=PROTOTYPES // The robot's subsystems Drivetrain m_drivetrain; // (1) Claw m_claw; Elevator m_elevator; Wrist m_wrist; - frc::Joystick* getJoystick2(); + + + frc::Joystick* getJoystick2(); frc::Joystick* getJoystick1(); frc::Joystick* getLogitechController(); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=PROTOTYPES - private: - RobotContainer(); - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=PROTOTYPES + + private: + + RobotContainer(); + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS // Joysticks frc::Joystick m_logitechController{0}; // (3) frc::Joystick m_joystick1{1}; frc::Joystick m_joystick2{2}; - frc::SendableChooser m_chooser; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS - Autonomous m_autonomousCommand; + + frc::SendableChooser m_chooser; + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + Autonomous m_autonomousCommand; static RobotContainer* m_robotContainer; - void ConfigureButtonBindings(); + + void ConfigureButtonBindings(); }; ``` @@ -451,22 +556,34 @@ This is the main program generated by RobotBuilder. There are a number of parts :linenos: :lineno-start: 11 :emphasize-lines: 28, 46, 56, 74 - // ROBOTBUILDER TYPE: RobotContainer. - #include "RobotContainer.h" + + // ROBOTBUILDER TYPE: RobotContainer. + + #include "RobotContainer.h" #include #include - RobotContainer* RobotContainer::m_robotContainer = NULL; - RobotContainer::RobotContainer() : m_autonomousCommand( + + + + RobotContainer* RobotContainer::m_robotContainer = NULL; + + RobotContainer::RobotContainer() : m_autonomousCommand( // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR ){ - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SMARTDASHBOARD + + + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SMARTDASHBOARD // Smartdashboard Subsystems frc::SmartDashboard::PutData(&m_drivetrain); frc::SmartDashboard::PutData(&m_claw); frc::SmartDashboard::PutData(&m_elevator); frc::SmartDashboard::PutData(&m_wrist); - // SmartDashboard Buttons + + + // SmartDashboard Buttons frc::SmartDashboard::PutData("Drive: Straight3Meters", new Drive(3, 0, &m_drivetrain)); // (6) frc::SmartDashboard::PutData("Drive: Place", new Drive(Drivetrain::PlaceDistance, Drivetrain::BackAwayDistance, &m_drivetrain)); frc::SmartDashboard::PutData("Set Wrist Setpoint: Horizontal", new SetWristSetpoint(0, &m_wrist)); @@ -479,28 +596,41 @@ This is the main program generated by RobotBuilder. There are a number of parts frc::SmartDashboard::PutData("Pickup", new Pickup()); frc::SmartDashboard::PutData("Open Claw: OpenTime", new OpenClaw(1.0_s, &m_claw)); frc::SmartDashboard::PutData("Close Claw", new CloseClaw( &m_claw )); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SMARTDASHBOARD - ConfigureButtonBindings(); - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DEFAULT-COMMANDS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=SMARTDASHBOARD + + ConfigureButtonBindings(); + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DEFAULT-COMMANDS m_drivetrain.SetDefaultCommand(TankDrive([this] {return getJoystick1()->GetY();}, [this] {return getJoystick2()->GetY();}, &m_drivetrain)); // (5) - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DEFAULT-COMMANDS - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS - m_chooser.AddOption("Set Elevator Setpoint: Bottom", new SetElevatorSetpoint(0, &m_elevator)); + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DEFAULT-COMMANDS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS + + m_chooser.AddOption("Set Elevator Setpoint: Bottom", new SetElevatorSetpoint(0, &m_elevator)); m_chooser.AddOption("Set Elevator Setpoint: Platform", new SetElevatorSetpoint(0.2, &m_elevator)); m_chooser.AddOption("Set Elevator Setpoint: Top", new SetElevatorSetpoint(0.3, &m_elevator)); - m_chooser.SetDefaultOption("Autonomous", new Autonomous()); // (2) - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS - frc::SmartDashboard::PutData("Auto Mode", &m_chooser); - } - RobotContainer* RobotContainer::GetInstance() { + + m_chooser.SetDefaultOption("Autonomous", new Autonomous()); // (2) + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=AUTONOMOUS + + frc::SmartDashboard::PutData("Auto Mode", &m_chooser); + + } + + RobotContainer* RobotContainer::GetInstance() { if (m_robotContainer == NULL) { m_robotContainer = new RobotContainer(); } return(m_robotContainer); } - void RobotContainer::ConfigureButtonBindings() { + + void RobotContainer::ConfigureButtonBindings() { // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=BUTTONS - frc2::JoystickButton m_dpadUp{&m_logitechController, 5}; // (4) + + frc2::JoystickButton m_dpadUp{&m_logitechController, 5}; // (4) frc2::JoystickButton m_dpadDown{&m_logitechController, 7}; frc2::JoystickButton m_dpadRight{&m_logitechController, 6}; frc2::JoystickButton m_dpadLeft{&m_logitechController, 8}; @@ -508,18 +638,30 @@ This is the main program generated by RobotBuilder. There are a number of parts frc2::JoystickButton m_r2{&m_logitechController, 10}; frc2::JoystickButton m_l1{&m_logitechController, 11}; frc2::JoystickButton m_r1{&m_logitechController, 12}; - m_dpadUp.OnTrue(SetElevatorSetpoint(0.3, &m_elevator).WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); - m_dpadDown.OnTrue(SetElevatorSetpoint(0, &m_elevator).WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); - m_dpadRight.OnTrue(CloseClaw( &m_claw ).WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); - m_dpadLeft.OnTrue(OpenClaw(1.0_s, &m_claw).WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); - m_l2.OnTrue(PrepareToPickup().WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); - m_r2.OnTrue(Pickup().WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); - m_l1.OnTrue(Place().WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); - m_r1.OnTrue(Autonomous().WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=BUTTONS + + m_dpadUp.OnTrue(SetElevatorSetpoint(0.3, &m_elevator).WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); + + m_dpadDown.OnTrue(SetElevatorSetpoint(0, &m_elevator).WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); + + m_dpadRight.OnTrue(CloseClaw( &m_claw ).WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); + + m_dpadLeft.OnTrue(OpenClaw(1.0_s, &m_claw).WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); + + m_l2.OnTrue(PrepareToPickup().WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); + + m_r2.OnTrue(Pickup().WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); + + m_l1.OnTrue(Place().WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); + + m_r1.OnTrue(Autonomous().WithInterruptBehavior(frc2::Command::InterruptionBehavior::kCancelSelf)); + + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=BUTTONS } - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=FUNCTIONS - frc::Joystick* RobotContainer::getLogitechController() { + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=FUNCTIONS + + frc::Joystick* RobotContainer::getLogitechController() { return &m_logitechController; } frc::Joystick* RobotContainer::getJoystick1() { @@ -528,12 +670,15 @@ This is the main program generated by RobotBuilder. There are a number of parts frc::Joystick* RobotContainer::getJoystick2() { return &m_joystick2; } - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=FUNCTIONS - frc2::Command* RobotContainer::GetAutonomousCommand() { + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=FUNCTIONS + + + frc2::Command* RobotContainer::GetAutonomousCommand() { // The selected command will be run in autonomous return m_chooser.GetSelected(); } - ``` + ``` This is the RobotContainer generated by RobotBuilder which is where the subsystems and operator interface are defined. There are a number of parts to this program (highlighted sections): 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 92d13110d4..1e79012e00 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 @@ -46,12 +46,17 @@ Add two joysticks to the Operator Interface, one is the left stick and the other :linenos: :lineno-start: 11 :emphasize-lines: 119-121 - // ROBOTBUILDER TYPE: Subsystem. - package frc.robot.subsystems; - import frc.robot.commands.*; + + // ROBOTBUILDER TYPE: Subsystem. + + package frc.robot.subsystems; + + + import frc.robot.commands.*; import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj2.command.SubsystemBase; - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS import edu.wpi.first.wpilibj.AnalogGyro; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.CounterBase.EncodingType; @@ -60,16 +65,21 @@ Add two joysticks to the Operator Interface, one is the left stick and the other import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup; import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS - /** + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + + + /** * */ public class Drivetrain extends SubsystemBase { // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS public static final double PlaceDistance = 0.1; public static final double BackAwayDistance = 0.6; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS private PWMVictorSPX left1; private PWMVictorSPX left2; private MotorControllerGroup leftMotor; @@ -81,8 +91,10 @@ Add two joysticks to the Operator Interface, one is the left stick and the other private Encoder rightencoder; private AnalogGyro gyro; private AnalogInput rangefinder; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS - /** + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + /** * */ public Drivetrain() { @@ -90,48 +102,70 @@ Add two joysticks to the Operator Interface, one is the left stick and the other left1 = new PWMVictorSPX(0); addChild("left1",left1); left1.setInverted(false); - left2 = new PWMVictorSPX(1); + + left2 = new PWMVictorSPX(1); addChild("left2",left2); left2.setInverted(false); - leftMotor = new MotorControllerGroup(left1, left2 ); + + leftMotor = new MotorControllerGroup(left1, left2 ); addChild("Left Motor",leftMotor); - right1 = new PWMVictorSPX(5); + + + right1 = new PWMVictorSPX(5); addChild("right1",right1); right1.setInverted(false); - right2 = new PWMVictorSPX(6); + + right2 = new PWMVictorSPX(6); addChild("right2",right2); right2.setInverted(false); - rightMotor = new MotorControllerGroup(right1, right2 ); + + rightMotor = new MotorControllerGroup(right1, right2 ); addChild("Right Motor",rightMotor); - drive = new DifferentialDrive(leftMotor, rightMotor); + + + drive = new DifferentialDrive(leftMotor, rightMotor); addChild("Drive",drive); drive.setSafetyEnabled(true); drive.setExpiration(0.1); drive.setMaxOutput(1.0); - leftencoder = new Encoder(0, 1, false, EncodingType.k4X); + + + leftencoder = new Encoder(0, 1, false, EncodingType.k4X); addChild("left encoder",leftencoder); leftencoder.setDistancePerPulse(1.0); - rightencoder = new Encoder(2, 3, false, EncodingType.k4X); + + rightencoder = new Encoder(2, 3, false, EncodingType.k4X); addChild("right encoder",rightencoder); rightencoder.setDistancePerPulse(1.0); - gyro = new AnalogGyro(0); + + gyro = new AnalogGyro(0); addChild("gyro",gyro); gyro.setSensitivity(0.007); - rangefinder = new AnalogInput(1); + + rangefinder = new AnalogInput(1); addChild("range finder", rangefinder); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS + + + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS } - @Override + + @Override public void periodic() { // This method will be called once per scheduler run - } - @Override + + } + + @Override public void simulationPeriodic() { // This method will be called once per scheduler run when in simulation - } - // Put methods for controlling this subsystem + + } + + // Put methods for controlling this subsystem // here. Call these from Commands. - public void drive(double left, double right) { + + public void drive(double left, double right) { drive.tankDrive(left, right); } } @@ -144,9 +178,11 @@ Add two joysticks to the Operator Interface, one is the left stick and the other :linenos: :lineno-start: 11 :emphasize-lines: 43 - // ROBOTBUILDER TYPE: Subsystem. + + // ROBOTBUILDER TYPE: Subsystem. #pragma once - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES #include #include #include @@ -154,8 +190,10 @@ Add two joysticks to the Operator Interface, one is the left stick and the other #include #include #include - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES - /** + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + /** * * * @author ExampleAuthor @@ -176,19 +214,25 @@ Add two joysticks to the Operator Interface, one is the left stick and the other frc::MotorControllerGroup m_leftMotor{m_left1, m_left2 }; frc::PWMVictorSPX m_left2{1}; frc::PWMVictorSPX m_left1{0}; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS public: Drivetrain(); - void Periodic() override; + + void Periodic() override; void SimulationPeriodic() override; void Drive(double left, double right); // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS static constexpr const double PlaceDistance = 0.1; static constexpr const double BackAwayDistance = 0.6; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS - }; + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS + + + }; ``` .. tab-item:: C++ (Source) @@ -199,49 +243,78 @@ Add two joysticks to the Operator Interface, one is the left stick and the other :linenos: :lineno-start: 11 :emphasize-lines: 71-73 - // ROBOTBUILDER TYPE: Subsystem. - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + // ROBOTBUILDER TYPE: Subsystem. + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES #include "subsystems/Drivetrain.h" #include - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES - Drivetrain::Drivetrain(){ + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + Drivetrain::Drivetrain(){ SetName("Drivetrain"); // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS SetSubsystem("Drivetrain"); - AddChild("range finder", &m_rangefinder); - AddChild("gyro", &m_gyro); + + AddChild("range finder", &m_rangefinder); + + + AddChild("gyro", &m_gyro); m_gyro.SetSensitivity(0.007); - AddChild("right encoder", &m_rightencoder); + + AddChild("right encoder", &m_rightencoder); m_rightencoder.SetDistancePerPulse(1.0); - AddChild("left encoder", &m_leftencoder); + + AddChild("left encoder", &m_leftencoder); m_leftencoder.SetDistancePerPulse(1.0); - AddChild("Drive", &m_drive); + + AddChild("Drive", &m_drive); m_drive.SetSafetyEnabled(true); m_drive.SetExpiration(0.1_s); m_drive.SetMaxOutput(1.0); - AddChild("Right Motor", &m_rightMotor); - AddChild("right2", &m_right2); + + + AddChild("Right Motor", &m_rightMotor); + + + AddChild("right2", &m_right2); m_right2.SetInverted(false); - AddChild("right1", &m_right1); + + AddChild("right1", &m_right1); m_right1.SetInverted(false); - AddChild("Left Motor", &m_leftMotor); - AddChild("left2", &m_left2); + + AddChild("Left Motor", &m_leftMotor); + + + AddChild("left2", &m_left2); m_left2.SetInverted(false); - AddChild("left1", &m_left1); + + AddChild("left1", &m_left1); m_left1.SetInverted(false); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS } - void Drivetrain::Periodic() { + + void Drivetrain::Periodic() { // Put code here to be run every loop - } - void Drivetrain::SimulationPeriodic() { + + } + + void Drivetrain::SimulationPeriodic() { // This method will be called once per scheduler run when in simulation - } - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS - // Put methods for controlling this subsystem + + } + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS + + + // Put methods for controlling this subsystem // here. Call these from Commands. - void Drivetrain::Drive(double left, double right) { + + void Drivetrain::Drive(double left, double right) { m_drive.TankDrive(left, right); } ``` @@ -280,55 +353,75 @@ Create a parameter preset to retrieve joystick values. Java: For the left parame :linenos: :lineno-start: 11 :emphasize-lines: 48, 54 - // ROBOTBUILDER TYPE: Command. - package frc.robot.commands; + + // ROBOTBUILDER TYPE: Command. + + package frc.robot.commands; import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj2.command.CommandBase; import frc.robot.RobotContainer; // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS import frc.robot.subsystems.Drivetrain; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS - /** + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + + /** * */ public class TankDrive extends CommandBase { - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS private final Drivetrain m_drivetrain; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS - public TankDrive(Drivetrain subsystem) { - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS + + + public TankDrive(Drivetrain subsystem) { + + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_SETTING - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_SETTING + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_SETTING // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES - m_drivetrain = subsystem; + + m_drivetrain = subsystem; addRequirements(m_drivetrain); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES } - // Called when the command is initially scheduled. + + // Called when the command is initially scheduled. @Override public void initialize() { } - // Called every time the scheduler runs while the command is scheduled. + + // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { m_drivetrain.drive(m_left.getAsDouble(), m_right.getAsDouble()); } - // Called once the command ends or is interrupted. + + // Called once the command ends or is interrupted. @Override public void end(boolean interrupted) { m_drivetrain.drive(0.0, 0.0); } - // Returns true when the command should end. + + // Returns true when the command should end. @Override public boolean isFinished() { return false; } - @Override + + @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 } } ``` @@ -340,16 +433,23 @@ Create a parameter preset to retrieve joystick values. Java: For the left parame :linenos: :lineno-start: 11 :emphasize-lines: 40-41 - // ROBOTBUILDER TYPE: Command. - #pragma once - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES - #include + + // ROBOTBUILDER TYPE: Command. + + #pragma once + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + #include #include - #include "subsystems/Drivetrain.h" - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + #include "subsystems/Drivetrain.h" + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES #include "RobotContainer.h" #include - /** + + /** * * * @author ExampleAuthor @@ -358,18 +458,25 @@ Create a parameter preset to retrieve joystick values. Java: For the left parame public: // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR explicit TankDrive(Drivetrain* m_drivetrain); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR - void Initialize() override; + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR + + void Initialize() override; void Execute() override; bool IsFinished() override; void End(bool interrupted) override; bool RunsWhenDisabled() const override; - private: + + + private: // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLES - Drivetrain* m_drivetrain; + + + Drivetrain* m_drivetrain; frc::Joystick* m_leftJoystick; frc::Joystick* m_rightJoystick; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLES + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLES }; ``` @@ -380,38 +487,51 @@ Create a parameter preset to retrieve joystick values. Java: For the left parame :linenos: :lineno-start: 11 :emphasize-lines: 25, 35 - // ROBOTBUILDER TYPE: Command. - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR - #include "commands/TankDrive.h" - TankDrive::TankDrive(Drivetrain* m_drivetrain) + + // ROBOTBUILDER TYPE: Command. + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR + + #include "commands/TankDrive.h" + + TankDrive::TankDrive(Drivetrain* m_drivetrain) :m_drivetrain(m_drivetrain){ - // Use AddRequirements() here to declare subsystem dependencies + + // Use AddRequirements() here to declare subsystem dependencies // eg. AddRequirements(m_Subsystem); SetName("TankDrive"); AddRequirements({m_drivetrain}); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR } - // Called just before this Command runs the first time + + // Called just before this Command runs the first time void TankDrive::Initialize() { - } - // Called repeatedly when this Command is scheduled to run + + } + + // Called repeatedly when this Command is scheduled to run void TankDrive::Execute() { m_drivetrain->Drive(m_left(),m_right()); } - // Make this return true when this Command no longer needs to run execute() + + // Make this return true when this Command no longer needs to run execute() bool TankDrive::IsFinished() { return false; } - // Called once after isFinished returns true + + // Called once after isFinished returns true void TankDrive::End(bool interrupted) { m_drivetrain->Drive(0,0); } - bool TankDrive::RunsWhenDisabled() const { + + bool TankDrive::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 } - ``` + ``` Add code to the execute method to do the actual driving. All that is needed is pass the for the left and right parameters to the Drive Train subsystem. The subsystem just uses them for the tank steering method on its DifferentialDrive object. And we get tank steering. 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 bbee2b8951..ea050bcbc4 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,93 +17,128 @@ This is the definition of the `CloseClaw` command in RobotBuilder. Notice that i :linenos: :lineno-start: 11 :emphasize-lines: 42, 53, 59 - // ROBOTBUILDER TYPE: Command. - package frc.robot.commands; - import edu.wpi.first.wpilibj2.command.CommandBase; - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS - import frc.robot.subsystems.Claw; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS - /** - * - */ - public class CloseClaw extends CommandBase { - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS - private final Claw m_claw; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS - 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=VARIABLE_SETTING - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES - m_claw = subsystem; - addRequirements(m_claw); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES - } - // 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 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) - } - @Override - public boolean runsWhenDisabled() { - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED - return false; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED - } - } - ``` + + // ROBOTBUILDER TYPE: Command. + + package frc.robot.commands; + import edu.wpi.first.wpilibj2.command.CommandBase; + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + import frc.robot.subsystems.Claw; + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + + /** + * + */ + public class CloseClaw extends CommandBase { + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS + private final Claw m_claw; + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=VARIABLE_DECLARATIONS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS + + + 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=VARIABLE_SETTING + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES + + m_claw = subsystem; + addRequirements(m_claw); + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=REQUIRES + } + + // 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 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) + } + + @Override + public boolean runsWhenDisabled() { + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED + return false; + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DISABLED + } + } + ``` ```c++ :linenos: :lineno-start: 11 :emphasize-lines: 21, 31, 36 - // ROBOTBUILDER TYPE: Command. - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR - #include "commands/CloseClaw.h" - CloseClaw::CloseClaw(Claw* m_claw) + + // ROBOTBUILDER TYPE: Command. + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR + + #include "commands/CloseClaw.h" + + CloseClaw::CloseClaw(Claw* m_claw) :m_claw(m_claw){ - // Use AddRequirements() here to declare subsystem dependencies + + // Use AddRequirements() here to declare subsystem dependencies // eg. AddRequirements(m_Subsystem); SetName("CloseClaw"); AddRequirements({m_claw}); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR - } - // Called just before this Command runs the first time + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTOR + + } + + // 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 + + // 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() + + } + + // 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 + + // Called once after isFinished returns true void CloseClaw::End(bool interrupted) { m_claw->Stop(); // (3) } - bool CloseClaw::RunsWhenDisabled() const { + + 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/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 62e65a8077..75bb31e323 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 @@ -19,29 +19,41 @@ The claw at the end of a robot arm is a subsystem operated by a single VictorSPX :linenos: :lineno-start: 11 :emphasize-lines: 63-77 - // ROBOTBUILDER TYPE: Subsystem. - package frc.robot.subsystems; - import frc.robot.commands.*; + + // ROBOTBUILDER TYPE: Subsystem. + + package frc.robot.subsystems; + + + import frc.robot.commands.*; import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj2.command.SubsystemBase; - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.motorcontrol.MotorController; import edu.wpi.first.wpilibj.motorcontrol.PWMVictorSPX; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS - /** + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=IMPORTS + + + /** * */ public class Claw extends SubsystemBase { // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS public static final double PlaceDistance = 0.1; public static final double BackAwayDistance = 0.6; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS private PWMVictorSPX motor; private DigitalInput limitswitch; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS - /** + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + /** * */ public Claw() { @@ -49,31 +61,44 @@ The claw at the end of a robot arm is a subsystem operated by a single VictorSPX motor = new PWMVictorSPX(4); addChild("motor",motor); motor.setInverted(false); - limitswitch = new DigitalInput(4); + + limitswitch = new DigitalInput(4); addChild("limit switch", limitswitch); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS + + + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTRUCTORS } - @Override + + @Override public void periodic() { // This method will be called once per scheduler run - } - @Override + + } + + @Override public void simulationPeriodic() { // This method will be called once per scheduler run when in simulation - } - public void open() { + + } + + public void open() { motor.set(1.0); } - public void close() { + + public void close() { motor.set(-1.0); } - public void stop() { + + public void stop() { motor.set(0.0); } - public boolean isGripping() { + + public boolean isGripping() { return limitswitch.get(); } - } + + } ``` .. tab-item:: C++ @@ -83,38 +108,57 @@ The claw at the end of a robot arm is a subsystem operated by a single VictorSPX :linenos: :lineno-start: 11 :emphasize-lines: 38-52 - // ROBOTBUILDER TYPE: Subsystem. - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + // ROBOTBUILDER TYPE: Subsystem. + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES #include "subsystems/Claw.h" #include - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES - Claw::Claw(){ + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + Claw::Claw(){ SetName("Claw"); // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS SetSubsystem("Claw"); - AddChild("limit switch", &m_limitswitch); - AddChild("motor", &m_motor); + + AddChild("limit switch", &m_limitswitch); + + + AddChild("motor", &m_motor); m_motor.SetInverted(false); - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS } - void Claw::Periodic() { + + void Claw::Periodic() { // Put code here to be run every loop - } - void Claw::SimulationPeriodic() { + + } + + void Claw::SimulationPeriodic() { // This method will be called once per scheduler run when in simulation - } - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS - void Claw::Open() { + + } + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS + + + void Claw::Open() { m_motor.Set(1.0); } - void Claw::Close() { + + void Claw::Close() { m_motor.Set(-1.0); } - void Claw::Stop() { + + void Claw::Stop() { m_motor.Set(0.0); } - bool Claw::IsGripping() { + + bool Claw::IsGripping() { return m_limitswitch.Get(); } ``` @@ -136,14 +180,18 @@ Notice that member variable called ``motor`` and ``limitswitch`` are created by :linenos: :lineno-start: 11 :emphasize-lines: 30-33 - // ROBOTBUILDER TYPE: Subsystem. + + // ROBOTBUILDER TYPE: Subsystem. #pragma once - // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES #include #include #include - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES - /** + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=INCLUDES + + /** * * * @author ExampleAuthor @@ -155,22 +203,28 @@ Notice that member variable called ``motor`` and ``limitswitch`` are created by // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS frc::DigitalInput m_limitswitch{4}; frc::PWMVictorSPX m_motor{4}; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=DECLARATIONS public: Claw(); - void Periodic() override; + + void Periodic() override; void SimulationPeriodic() override; void Open(); void Close(); void Stop(); bool IsGripping(); // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CMDPIDGETTERS // BEGIN AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS static constexpr const double PlaceDistance = 0.1; static constexpr const double BackAwayDistance = 0.6; - // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS - }; + + // END AUTOGENERATED CODE, SOURCE=ROBOTBUILDER ID=CONSTANTS + + + }; ``` 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. diff --git a/source/docs/yearly-overview/2020-Game-Data.rst b/source/docs/yearly-overview/2020-Game-Data.rst index c1cf682a78..3154cbd2af 100644 --- a/source/docs/yearly-overview/2020-Game-Data.rst +++ b/source/docs/yearly-overview/2020-Game-Data.rst @@ -26,7 +26,7 @@ In C++ and Java the Game Data is accessed by using the GetGameSpecificMessage me ```java import edu.wpi.first.wpilibj.DriverStation; - String gameData; + String gameData; gameData = DriverStation.getInstance().getGameSpecificMessage(); if(gameData.length() > 0) { @@ -55,7 +55,7 @@ In C++ and Java the Game Data is accessed by using the GetGameSpecificMessage me ```c++ #include - std::string gameData; + std::string gameData; gameData = frc::DriverStation::GetInstance().GetGameSpecificMessage(); if(gameData.length() > 0) { diff --git a/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java-python.rst b/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java-python.rst index 5375254d36..1d1364c769 100644 --- a/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java-python.rst +++ b/source/docs/zero-to-robot/step-4/creating-test-drivetrain-program-cpp-java-python.rst @@ -168,7 +168,7 @@ Now let's look at various parts of the code. import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import com.ctre.phoenix6.hardware.TalonFX; - ``` + ``` ```c++ #include @@ -176,7 +176,7 @@ Now let's look at various parts of the code. #include #include #include - ``` + ``` ```python import wpilib # Used to get the joysticks @@ -191,11 +191,11 @@ Now let's look at various parts of the code. ```java import com.revrobotics.CANSparkMax; import com.revrobotics.CANSparkLowLevel.MotorType; - import edu.wpi.first.wpilibj.TimedRobot; + 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; - ``` + ``` ```c++ #include @@ -203,8 +203,8 @@ Now let's look at various parts of the code. #include #include #include - #include - ``` + #include + ``` ```python import wpilib # Used to get the joysticks @@ -225,7 +225,7 @@ Now let's look at various parts of the code. import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.drive.DifferentialDrive; import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX; - ``` + ``` ```c++ #include @@ -233,7 +233,7 @@ Now let's look at various parts of the code. #include #include #include - ``` + ``` ```python import wpilib # Used to get the joysticks @@ -332,7 +332,7 @@ Our code needs to reference the components of WPILib that are used. In C++ this frc::DifferentialDrive m_robotDrive{ [&](double output) { m_left.Set(output); }, [&](double output) { m_right.Set(output); }}; - frc::XboxController m_controller{0}; + frc::XboxController m_controller{0}; frc::Timer m_timer; ``` @@ -353,7 +353,7 @@ Our code needs to reference the components of WPILib that are used. In C++ this ) self.controller = wpilib.XboxController(0) self.timer = wpilib.Timer() - # We need to invert one side of the drivetrain so that positive voltages + # We need to invert one side of the drivetrain so that positive voltages # result in both sides moving forward. Depending on how your robot's # gearbox is constructed, you might have to invert the left side instead. self.rightDrive.setInverted(True) @@ -400,7 +400,7 @@ Our code needs to reference the components of WPILib that are used. In C++ this frc::DifferentialDrive m_robotDrive{ [&](double output) { m_left.Set(output); }, [&](double output) { m_right.Set(output); }}; - frc::XboxController m_controller{0}; + frc::XboxController m_controller{0}; frc::Timer m_timer; ``` @@ -453,7 +453,7 @@ Our code needs to reference the components of WPILib that are used. In C++ this frc::DifferentialDrive m_robotDrive{ [&](double output) { m_left.Set(output); }, [&](double output) { m_right.Set(output); }}; - frc::XboxController m_controller{0}; + frc::XboxController m_controller{0}; frc::Timer m_timer; ```