WPILib Örnek Projeler

Uyarı

WPILib örneklerini işlevsel tutmak için her girişimde bulunulsa da, “olduğu gibi” kullanılması amaçlanmamıştır. Kodun bir kullanıcı robotunda çalışması için en azından robota özgü sabitlerin değiştirilmesi gerekecektir. Birçok ampirik sabitin değerleri, gösterim amacıyla “sahte” hale getirilmiştir. Kullanıcıların, örnek kodu kopyalamak yerine kendi kodlarını (sıfırdan veya mevcut bir şablondan) yazmaları şiddetle tavsiye edilir.

WPILib örnek projeleri, çok sayıda kitaplık özelliği ve kullanım desenleri gösterir. Projeler, tek bir işlevin basit gösterimlerinden eksiksiz, rekabete uygun robot programlarına kadar çeşitlilik gösterir. Bu örneklerin tümü VS Code’da şu şekilde kullanılabilir Ctrl+Shift+P, ardından WPILib: Create a new project ve örnek seçilerek.

../../../_images/create-new-project.png

Temel Örnekler

Bu örnekler, temel / minimum robot işlevselliğini gösterir. Robot programlamaya ilk aşina olan, ancak işlevsellik açısından oldukça sınırlı olan yeni başlayan ekipler için kullanışlıdır.

  • Arcade Drive (Java, C++, Python): Demonstrates a simple differential drive implementation using “arcade”-style controls through the DifferentialDrive class.

  • Arcade Drive Xbox Controller (Java, C++, Python): Demonstrates the same functionality seen in the previous example, except using an XboxController instead of an ordinary joystick.

  • Getting Started (Java, C++, Python): Demonstrates a simple autonomous routine that drives forwards for two seconds at half speed.

  • Mecanum Drive (Java, C++, Python): Demonstrates a simple mecanum drive implementation using the MecanumDrive class.

  • Motor Controller (Java, C++, Python): Demonstrates how to control the output of a motor with a joystick with an encoder to read motor position.

  • Simple Vision (Java, C++, Python): Demonstrates how to stream video from a USB camera to the dashboard.

  • Relay (Java, C++, Python): Demonstrates the use of the Relay class to control a relay output with a set of joystick buttons.

  • Solenoids (Java, C++, Python): Demonstrates the use of the Solenoid and DoubleSolenoid classes to control solenoid outputs with a set of joystick buttons.

  • TankDrive (Java, C++, Python): Demonstrates a simple differential drive implementation using “tank”-style controls through the DifferentialDrive class.

  • Tank Drive Xbox Controller (Java, C++, Python): Demonstrates the same functionality seen in the previous example, except using an XboxController instead of an ordinary joystick.

Kontrol Örnekleri

Bu örnekler, yaygın robot kontrollerinin WPILib uygulamalarını gösterir. Sensörler mevcut olabilir, ancak bu örneklerin vurgulanan konsepti değildir.

  • DifferentialDriveBot (Java, C++, Python): Demonstrates an advanced differential drive implementation, including encoder-and-gyro odometry through the DifferentialDriveOdometry class, and composition with PID velocity control through the DifferentialDriveKinematics and PIDController classes.

  • Elevator with profiled PID controller (Java, C++, Python): Demonstrates the use of the ProfiledPIDController class to control the position of an elevator mechanism.

  • Elevator with trapezoid profiled PID (Java, C++, Python): Demonstrates the use of the TrapezoidProfile class in conjunction with a “smart motor controller” to control the position of an elevator mechanism.

  • Gyro Mecanum (Java, C++, Python): Demonstrates field-oriented control of a mecanum robot through the MecanumDrive class in conjunction with a gyro.

  • MecanumBot (Java, C++, Python): Demonstrates an advanced mecanum drive implementation, including encoder-and-gyro odometry through the MecanumDriveOdometry class, and composition with PID velocity control through the MecanumDriveKinematics and PIDController classes.

  • PotentiometerPID (Java, C++, Python): Demonstrates the use of the PIDController class and a potentiometer to control the position of an elevator mechanism.

  • RamseteController (Java, C++, Python): Demonstrates the use of the RamseteController class to follow a trajectory during the autonomous period.

  • SwerveBot (Java, C++, Python): Demonstrates an advanced swerve drive implementation, including encoder-and-gyro odometry through the SwerveDriveOdometry class, and composition with PID position and velocity control through the SwerveDriveKinematics and PIDController classes.

  • UltrasonicPID (Java, C++, Python): Demonstrates the use of the PIDController class in conjunction with an ultrasonic sensor to drive to a set distance from an object.

Sensör Örnekleri

Bu örnekler, WPILib kullanarak sensör okumayı ve veri işlemeyi gösterir. Mekanizma kontrolü mevcut olabilir, ancak bu örneklerin vurgulanan konsepti değildir.

  • Axis Camera Sample (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/axiscamera> __, C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/AxisCameraSample> __): Yakalanan bir video beslemesinde bir dikdörtgeni kaplamak ve bunu kontrol paneline aktarmak için OpenCV ve bir Axis Netcam kullanımını gösterir.

  • Power Distribution CAN Monitoring (Java, C++, Python): Demonstrates obtaining sensor information from a Power Distribution module over CAN using the PowerDistribution class.

  • Duty Cycle Encoder (Java, C++, Python): Demonstrates the use of the DutyCycleEncoder class to read values from a PWM-type absolute encoder.

  • DutyCycleInput (Java, C++, Python): Demonstrates the use of the DutyCycleInput class to read the frequency and fractional duty cycle of a PWM input.

  • Encoder (Java, C++, Python): Demonstrates the use of the Encoder class to read values from a quadrature encoder.

  • Gyro (Java, C++, Python): Demonstrates the use of the AnalogGyro class to measure robot heading and stabilize driving.

  • Intermediate Vision (Java, C++, Python): Demonstrates the use of OpenCV and a USB camera to overlay a rectangle on a captured video feed and stream it to the dashboard.

  • AprilTagsVision (Java, C++): Demonstrates on-roboRIO detection of AprilTags using an attached USB camera.

  • Ultrasonic (Java, C++, Python): Demonstrates the use of the Ultrasonic class to read data from an ultrasonic sensor in conjunction with the MedianFilter class to reduce signal noise.

  • SysIdRoutine (Java, C++): Demonstrates the use of the SysIdRoutine API to gather characterization data for a differential drivetrain.

Komut-Tabanlı Örnekler

Bu örnekler: Command-Based framework. ‘ın kullanımını gösterir.

  • ArmBot (Java, C++, Python): Demonstrates the use of a ProfiledPIDSubsystem to control a robot arm.

  • ArmBotOffboard (Java, C++, Python): Demonstrates the use of a TrapezoidProfileSubsystem in conjunction with a “smart motor controller” to control a robot arm.

  • DriveDistanceOffboard (Java, C++, Python): Demonstrates the use of a TrapezoidProfileCommand in conjunction with a “smart motor controller” to drive forward by a set distance with a trapezoidal motion profile.

  • FrisbeeBot (Java, C++, Python): A complete set of robot code for a simple frisbee-shooting robot typical of the 2013 FRC® game Ultimate Ascent. Demonstrates simple PID control through the PIDSubystem class.

  • Gears Bot (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot> __, C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/GearsBot> __): WPI gösteri robotu GearsBot için eksiksiz bir robot kodu seti.

  • Gyro Drive Commands (Java, C++, Python): Demonstrates the use of PIDCommand and ProfiledPIDCommand in conjunction with a gyro to turn a robot to face a specified heading and to stabilize heading while driving.

  • Inlined Hatchbot (Java, C++, Python): A complete set of robot code for a simple hatch-delivery bot typical of the 2019 FRC game Destination: Deep Space. Commands are written in an “inline” style, in which explicit subclassing of Command is avoided.

  • Traditional Hatchbot (Java, C++, Python): A complete set of robot code for a simple hatch-delivery bot typical of the 2019 FRC game Destination: Deep Space. Commands are written in a “traditional” style, in which subclasses of Command are written for each robot action.

  • MecanumControllerCommand (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand> __, C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand> __): TrajectoryGenerator ve MecanumControllerCommand sınıflarını kullanarak bir mecanum sürücü ile yörünge oluşturmayı ve takibi gösterir.

  • RamseteCommand (Java, C++, Python): Demonstrates trajectory generation and following with a differential drive using the TrajectoryGenerator and RamseteCommand classes. A matching step-by-step tutorial can be found here.

  • Select Command Example (Java, C++, Python): Demonstrates the use of the SelectCommand class to run one of a selection of commands depending on a runtime-evaluated condition.

  • SwerveControllerCommand (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand> __, C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand> __): TrajectoryGenerator ve SwerveControllerCommand sınıflarını kullanarak bir swerve sürücüsüyle yörünge oluşturmayı ve takip etmeyi gösterir.

State-Space Durum Uzayı Örnekleri

Bu örnekler, State-Space Control. ‘ın kullanımını gösterir.

  • StateSpaceFlywheel (Java, C++, Python): Demonstrates state-space control of a flywheel.

  • StateSpaceFlywheelSysId (Java, C++, Python): Demonstrates state-space control using SysId’s System Identification for controlling a flywheel.

  • ** StateSpaceElevator ** (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespaceelevator> __, C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator> __): Bir asansörün durum alanı kontrolünü gösterir.

  • ** StateSpaceArm ** (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacearm> __, C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/StateSpaceArm> __): Bir Kolun durum-uzay kontrolünü gösterir.

  • ** StateSpaceDriveSimulation ** (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation> __, C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation> __): Controller ve Field2d sınıfını takip eden bir RAMSETE yolu ile birlikte bir diferansiyel aktarma organının durum alanı kontrolünü gösterir.

Simülasyon Fiziği Örnekleri

Bu örnekler, fizik simülasyonunun kullanımını göstermektedir.

  • ElevatorSimulation (Java, C++, Python): Demonstrates the use of physics simulation with a simple elevator.

  • ArmSimulation (Java, C++, Python): Demonstrates the use of physics simulation with a simple single-jointed arm.

  • ** StateSpaceDriveSimulation ** (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation> __, C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation> __): Controller ve Field2d sınıfını takip eden bir RAMSETE yolu ile birlikte bir diferansiyel aktarma organının durum alanı kontrolünü gösterir.

  • ** SimpleDifferentialDriveSimulation ** (Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/simpledifferentialdrivesimulation> __, `` C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation> `__): Simülasyonda kullanılabilecek temel bir aktarma organının barebone örneği.

Çeşitli Örnekler

Bu örnekler, yukarıdaki kategorilerin hiçbirine uymayan çeşitli WPILib işlevselliğini gösterir.

  • Addressable LED (Java, C++, Python): Demonstrates the use of the AddressableLED class to control RGB LEDs for robot decoration and/or driver feedback.

  • DMA (Java, C++): Demonstrates the use of DMA (Direct Memory Access) to read from sensors without using the RoboRIO’s CPU.

  • ** HAL ** (C ++ <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibcExamples/src/main/cpp/examples/HAL> __): WPILib’in geri kalanını kullanmadan HAL (Donanım Soyutlama Katmanı) kullanımını gösterir. Bu örnek ileri düzey kullanıcılar içindir (yalnızca C ++).

  • HID Rumble (Java, C++, Python): Demonstrates the use of the “rumble” functionality for tactile feedback on supported HIDs (such as XboxControllers).

  • Shuffleboard (Java, C++, Python): Demonstrates configuring tab/widget layouts on the “Shuffleboard” dashboard from robot code through the Shuffleboard class’s fluent builder API.

  • RomiReference (Java, C++, Python): A command based example of how to run the Romi robot.

  • Mechanism2d (Java, C++, Python): A simple example of using Mechanism2d.