├── .github └── workflows │ ├── cleanup-cache.yml │ └── dist.yml ├── .gitignore ├── .readthedocs.yml ├── LICENSE.md ├── README.md ├── devtools ├── __init__.py ├── __main__.py ├── ci.py ├── config.py ├── ctx.py ├── subproject.py ├── update_pyproject.py └── util.py ├── docs ├── .gitignore ├── Makefile ├── api.rst ├── conf.py ├── cscore.imagewriter.rst ├── index.rst ├── make.bat ├── ntcore.util.rst ├── requirements.txt ├── wpilib.cameraserver.rst ├── wpilib.deployinfo.rst └── wpimath.units.rst ├── examples ├── cscore │ ├── CameraServer.java │ ├── cvstream.py │ ├── dual_cameraserver.py │ ├── enum_usb.py │ ├── httpcvstream.py │ ├── intermediate_cameraserver.py │ ├── quick_cameraserver.py │ ├── settings.py │ ├── switched_cameraserver.py │ ├── usbcvstream.py │ └── usbstream.py └── ntcore │ ├── pubsub_client.py │ ├── pubsub_server.py │ ├── simple_client.py │ ├── simple_poller.py │ └── simple_robot.py ├── rdev.sh ├── rdev.toml ├── rdev_requirements.txt └── subprojects ├── pyntcore ├── .gitignore ├── README.md ├── devtools │ └── gen-pubsub.py ├── meson.build ├── ntcore │ ├── __init__.py │ ├── _logutil.py │ ├── meta │ │ └── __init__.py │ ├── py.typed │ ├── src │ │ ├── NetworkTable.cpp.inl │ │ ├── NetworkTableEntry.cpp.inl │ │ ├── nt_instance.cpp │ │ ├── nt_instance.h │ │ ├── nt_type_caster.h │ │ ├── ntcore.cpp │ │ ├── py2value.cpp │ │ ├── py2value.h │ │ ├── pyentry.cpp │ │ └── pyentry.h │ ├── types.py │ └── util.py ├── pyproject.toml ├── semiwrap │ ├── .gitignore │ ├── BooleanArrayTopic.yml │ ├── BooleanTopic.yml │ ├── ConnectionListener.yml │ ├── DoubleArrayTopic.yml │ ├── DoubleTopic.yml │ ├── FloatArrayTopic.yml │ ├── FloatTopic.yml │ ├── GenericEntry.yml │ ├── IntegerArrayTopic.yml │ ├── IntegerTopic.yml │ ├── MultiSubscriber.yml │ ├── NTSendable.yml │ ├── NTSendableBuilder.yml │ ├── NetworkTable.yml │ ├── NetworkTableEntry.yml │ ├── NetworkTableInstance.yml │ ├── NetworkTableListener.yml │ ├── NetworkTableType.yml │ ├── NetworkTableValue.yml │ ├── RawTopic.yml │ ├── StringArrayTopic.yml │ ├── StringTopic.yml │ ├── StructArrayTopic.yml │ ├── StructTopic.yml │ ├── Topic.yml │ ├── TopicListener.yml │ ├── ValueListener.yml │ ├── ntcore_cpp.yml │ └── ntcore_cpp_types.yml └── tests │ ├── conftest.py │ ├── requirements.txt │ ├── run_tests.py │ ├── test_api.py │ ├── test_entry.py │ ├── test_network_table.py │ ├── test_struct_topic.py │ ├── test_util.py │ └── test_value.py ├── robotpy-apriltag ├── .gitignore ├── README.md ├── meson.build ├── pyproject.toml ├── robotpy_apriltag │ ├── __init__.py │ ├── py.typed │ └── src │ │ └── main.cpp ├── semiwrap │ ├── .gitignore │ ├── AprilTag.yml │ ├── AprilTagDetection.yml │ ├── AprilTagDetector.yml │ ├── AprilTagFieldLayout.yml │ ├── AprilTagFields.yml │ ├── AprilTagPoseEstimate.yml │ └── AprilTagPoseEstimator.yml └── tests │ ├── requirements.txt │ ├── run_tests.py │ ├── tag1_640_480.jpg │ ├── tag2_16h5_straight.png │ ├── tag2_45deg_X.png │ ├── tag2_45deg_y.png │ └── test_detection.py ├── robotpy-cscore ├── .gitignore ├── .gittrack ├── .gittrackexclude ├── LICENSE ├── README.rst ├── cscore │ ├── __init__.py │ ├── __main__.py │ ├── _logging.py │ ├── cvnp │ │ ├── README.md │ │ ├── cvnp.cpp │ │ ├── cvnp.h │ │ ├── cvnp_synonyms.cpp │ │ └── cvnp_synonyms.h │ ├── grip.py │ ├── imagewriter.py │ └── src │ │ └── main.cpp ├── meson.build ├── pyproject.toml ├── semiwrap │ ├── .gitignore │ ├── CameraServer.yml │ ├── cscore_cpp.yml │ ├── cscore_cv.yml │ ├── cscore_oo.yml │ └── cscore_runloop.yml └── tests │ ├── requirements.txt │ ├── run_tests.py │ ├── test_cv.py │ └── test_import.py ├── robotpy-hal ├── .gitignore ├── README.md ├── hal │ ├── __init__.py │ ├── _initialize.py │ ├── exceptions.py │ ├── py.typed │ ├── simulation │ │ ├── __init__.py │ │ ├── main.cpp │ │ ├── resethandles.cpp │ │ ├── sim_cb.h │ │ └── sim_value_cb.h │ └── src │ │ └── hal.cpp ├── meson.build ├── pyproject.toml ├── semiwrap │ ├── .gitignore │ ├── Accelerometer.yml │ ├── AddressableLED.yml │ ├── AddressableLEDTypes.yml │ ├── AnalogAccumulator.yml │ ├── AnalogGyro.yml │ ├── AnalogInput.yml │ ├── AnalogOutput.yml │ ├── AnalogTrigger.yml │ ├── CAN.yml │ ├── CANAPI.yml │ ├── CANAPITypes.yml │ ├── CTREPCM.yml │ ├── Constants.yml │ ├── Counter.yml │ ├── DIO.yml │ ├── DriverStation.yml │ ├── DriverStationTypes.yml │ ├── DutyCycle.yml │ ├── Encoder.yml │ ├── Extensions.yml │ ├── FRCUsageReporting.yml │ ├── HALBase.yml │ ├── HandlesInternal.yml │ ├── I2C.yml │ ├── I2CTypes.yml │ ├── Interrupts.yml │ ├── LEDs.yml │ ├── Main.yml │ ├── Notifier.yml │ ├── PWM.yml │ ├── Ports.yml │ ├── Power.yml │ ├── PowerDistribution.yml │ ├── REVPH.yml │ ├── Relay.yml │ ├── SPI.yml │ ├── SPITypes.yml │ ├── SerialHelper.yml │ ├── SerialPort.yml │ ├── SimDevice.yml │ ├── Threads.yml │ └── simulation │ │ ├── AccelerometerData.yml │ │ ├── AddressableLEDData.yml │ │ ├── AnalogGyroData.yml │ │ ├── AnalogInData.yml │ │ ├── AnalogOutData.yml │ │ ├── AnalogTriggerData.yml │ │ ├── CTREPCMData.yml │ │ ├── CanData.yml │ │ ├── DIOData.yml │ │ ├── DigitalPWMData.yml │ │ ├── DriverStationData.yml │ │ ├── DutyCycleData.yml │ │ ├── EncoderData.yml │ │ ├── I2CData.yml │ │ ├── MockHooks.yml │ │ ├── NotifierData.yml │ │ ├── NotifyListener.yml │ │ ├── PWMData.yml │ │ ├── PowerDistributionData.yml │ │ ├── REVPHData.yml │ │ ├── RelayData.yml │ │ ├── Reset.yml │ │ ├── RoboRioData.yml │ │ ├── SPIAccelerometerData.yml │ │ ├── SPIData.yml │ │ ├── SimCallbackRegistry.yml │ │ ├── SimDataValue.yml │ │ └── SimDeviceData.yml └── tests │ ├── requirements.txt │ ├── run_tests.py │ ├── test_hal.py │ └── test_hal_simulation.py ├── robotpy-halsim-ds-socket ├── .gitignore ├── README.md ├── halsim_ds_socket │ ├── __init__.py │ ├── main.py │ └── py.typed ├── pyproject.toml └── tests │ ├── requirements.txt │ ├── run_tests.py │ └── test_halsim_ds_socket.py ├── robotpy-halsim-gui ├── .gitignore ├── README.md ├── halsim_gui │ ├── __init__.py │ ├── _ext │ │ ├── __init__.py │ │ └── main.cpp │ ├── main.py │ └── py.typed ├── meson.build ├── pyproject.toml ├── semiwrap │ └── .gitignore └── tests │ ├── requirements.txt │ ├── run_tests.py │ └── test_halsim_gui.py ├── robotpy-halsim-ws ├── .gitignore ├── README.md ├── halsim_ws │ ├── __init__.py │ ├── client │ │ ├── __init__.py │ │ └── main.py │ ├── py.typed │ └── server │ │ ├── __init__.py │ │ └── main.py ├── pyproject.toml └── tests │ ├── requirements.txt │ ├── run_tests.py │ ├── test_halsim_ws_client.py │ └── test_halsim_ws_server.py ├── robotpy-native-apriltag ├── .gitignore └── pyproject.toml ├── robotpy-native-ntcore ├── .gitignore └── pyproject.toml ├── robotpy-native-romi ├── .gitignore └── pyproject.toml ├── robotpy-native-wpihal ├── .gitignore └── pyproject.toml ├── robotpy-native-wpilib ├── .gitignore └── pyproject.toml ├── robotpy-native-wpimath ├── .gitignore └── pyproject.toml ├── robotpy-native-wpinet ├── .gitignore └── pyproject.toml ├── robotpy-native-wpiutil ├── .gitignore └── pyproject.toml ├── robotpy-native-xrp ├── .gitignore └── pyproject.toml ├── robotpy-romi ├── .gitignore ├── README.md ├── meson.build ├── pyproject.toml ├── romi │ ├── __init__.py │ ├── py.typed │ └── src │ │ └── main.cpp ├── semiwrap │ ├── .gitignore │ ├── OnBoardIO.yml │ ├── RomiGyro.yml │ └── RomiMotor.yml └── tests │ ├── requirements.txt │ ├── run_tests.py │ └── test_romi.py ├── robotpy-wpilib ├── .gitignore ├── LICENSE.txt ├── README.md ├── README.rst ├── meson.build ├── pyproject.toml ├── semiwrap │ ├── .gitignore │ ├── ADIS16448_IMU.yml │ ├── ADIS16470_IMU.yml │ ├── ADXL345_I2C.yml │ ├── ADXL345_SPI.yml │ ├── ADXL362.yml │ ├── ADXRS450_Gyro.yml │ ├── AddressableLED.yml │ ├── Alert.yml │ ├── AnalogAccelerometer.yml │ ├── AnalogEncoder.yml │ ├── AnalogGyro.yml │ ├── AnalogInput.yml │ ├── AnalogOutput.yml │ ├── AnalogPotentiometer.yml │ ├── AnalogTrigger.yml │ ├── AnalogTriggerOutput.yml │ ├── AnalogTriggerType.yml │ ├── BuiltInAccelerometer.yml │ ├── CAN.yml │ ├── Color.yml │ ├── Color8Bit.yml │ ├── Compressor.yml │ ├── CompressorConfigType.yml │ ├── Controller.yml │ ├── Counter.yml │ ├── DMA.yml │ ├── DMASample.yml │ ├── DMC60.yml │ ├── DSControlWord.yml │ ├── DataLogManager.yml │ ├── DifferentialDriveVoltageConstraint.yml │ ├── DigitalGlitchFilter.yml │ ├── DigitalInput.yml │ ├── DigitalOutput.yml │ ├── DigitalSource.yml │ ├── DoubleSolenoid.yml │ ├── DriverStation.yml │ ├── DriverStationModeThread.yml │ ├── DutyCycle.yml │ ├── DutyCycleEncoder.yml │ ├── Encoder.yml │ ├── Errors.yml │ ├── Field2d.yml │ ├── FieldObject2d.yml │ ├── Filesystem.yml │ ├── Filter.yml │ ├── I2C.yml │ ├── InterruptableSensorBase.yml │ ├── IterativeRobot.yml │ ├── IterativeRobotBase.yml │ ├── Jaguar.yml │ ├── Joystick.yml │ ├── LEDPattern.yml │ ├── ListenerExecutor.yml │ ├── LiveWindow.yml │ ├── Mechanism2d.yml │ ├── MechanismLigament2d.yml │ ├── MechanismObject2d.yml │ ├── MechanismRoot2d.yml │ ├── MotorControllerGroup.yml │ ├── MotorSafety.yml │ ├── NidecBrushless.yml │ ├── Notifier.yml │ ├── PS4Controller.yml │ ├── PS5Controller.yml │ ├── PWM.yml │ ├── PWMMotorController.yml │ ├── PWMSparkFlex.yml │ ├── PWMSparkMax.yml │ ├── PWMSpeedController.yml │ ├── PWMTalonFX.yml │ ├── PWMTalonSRX.yml │ ├── PWMVenom.yml │ ├── PWMVictorSPX.yml │ ├── PneumaticHub.yml │ ├── PneumaticsBase.yml │ ├── PneumaticsControlModule.yml │ ├── PneumaticsModuleType.yml │ ├── Potentiometer.yml │ ├── PowerDistribution.yml │ ├── Preferences.yml │ ├── Relay.yml │ ├── Resource.yml │ ├── RobotBase.yml │ ├── RobotController.yml │ ├── RobotState.yml │ ├── RuntimeType.yml │ ├── SD540.yml │ ├── SPI.yml │ ├── SendableBuilderImpl.yml │ ├── SendableCameraWrapper.yml │ ├── SendableChooser.yml │ ├── SendableChooserBase.yml │ ├── SensorUtil.yml │ ├── SerialPort.yml │ ├── Servo.yml │ ├── SharpIR.yml │ ├── SimpleWidget.yml │ ├── SlewRateLimiter.yml │ ├── SmartDashboard.yml │ ├── Solenoid.yml │ ├── SolenoidBase.yml │ ├── Spark.yml │ ├── StadiaController.yml │ ├── SynchronousInterrupt.yml │ ├── SysIdRoutineLog.yml │ ├── Talon.yml │ ├── Threads.yml │ ├── TimedRobot.yml │ ├── Timer.yml │ ├── TimesliceRobot.yml │ ├── Tracer.yml │ ├── Ultrasonic.yml │ ├── Utility.yml │ ├── Victor.yml │ ├── VictorSP.yml │ ├── WPIErrors.yml │ ├── WPILibVersion.yml │ ├── Watchdog.yml │ ├── XboxController.yml │ ├── counter │ │ ├── EdgeConfiguration.yml │ │ ├── ExternalDirectionCounter.yml │ │ ├── Tachometer.yml │ │ └── UpDownCounter.yml │ ├── drive │ │ ├── DifferentialDrive.yml │ │ ├── MecanumDrive.yml │ │ └── RobotDriveBase.yml │ ├── event │ │ ├── BooleanEvent.yml │ │ ├── EventLoop.yml │ │ └── NetworkBooleanEvent.yml │ ├── interfaces │ │ ├── CounterBase.yml │ │ ├── GenericHID.yml │ │ └── MotorController.yml │ ├── shuffleboard │ │ ├── BuiltInLayouts.yml │ │ ├── BuiltInWidgets.yml │ │ ├── ComplexWidget.yml │ │ ├── LayoutType.yml │ │ ├── RecordingController.yml │ │ ├── Shuffleboard.yml │ │ ├── ShuffleboardComponent.yml │ │ ├── ShuffleboardComponentBase.yml │ │ ├── ShuffleboardContainer.yml │ │ ├── ShuffleboardEventImportance.yml │ │ ├── ShuffleboardInstance.yml │ │ ├── ShuffleboardLayout.yml │ │ ├── ShuffleboardRoot.yml │ │ ├── ShuffleboardTab.yml │ │ ├── ShuffleboardValue.yml │ │ ├── ShuffleboardWidget.yml │ │ ├── SimpleWidget.yml │ │ ├── SuppliedValueWidget.yml │ │ └── WidgetType.yml │ └── simulation │ │ ├── ADIS16448_IMUSim.yml │ │ ├── ADIS16470_IMUSim.yml │ │ ├── ADXL345Sim.yml │ │ ├── ADXL362Sim.yml │ │ ├── ADXRS450_GyroSim.yml │ │ ├── AddressableLEDSim.yml │ │ ├── AnalogEncoderSim.yml │ │ ├── AnalogGyroSim.yml │ │ ├── AnalogInputSim.yml │ │ ├── AnalogOutputSim.yml │ │ ├── AnalogTriggerSim.yml │ │ ├── BatterySim.yml │ │ ├── BuiltInAccelerometerSim.yml │ │ ├── CTREPCMSim.yml │ │ ├── CallbackStore.yml │ │ ├── DCMotorSim.yml │ │ ├── DIOSim.yml │ │ ├── DifferentialDrivetrainSim.yml │ │ ├── DigitalPWMSim.yml │ │ ├── DoubleSolenoidSim.yml │ │ ├── DriverStationSim.yml │ │ ├── DutyCycleEncoderSim.yml │ │ ├── DutyCycleSim.yml │ │ ├── ElevatorSim.yml │ │ ├── EncoderSim.yml │ │ ├── FlywheelSim.yml │ │ ├── GenericHIDSim.yml │ │ ├── JoystickSim.yml │ │ ├── LinearSystemSim.yml │ │ ├── Mechanism2D.yml │ │ ├── PCMSim.yml │ │ ├── PDPSim.yml │ │ ├── PS4ControllerSim.yml │ │ ├── PS5ControllerSim.yml │ │ ├── PWMSim.yml │ │ ├── PneumaticsBaseSim.yml │ │ ├── PowerDistributionSim.yml │ │ ├── REVPHSim.yml │ │ ├── RelaySim.yml │ │ ├── RoboRioSim.yml │ │ ├── SPIAccelerometerSim.yml │ │ ├── SendableChooserSim.yml │ │ ├── SharpIRSim.yml │ │ ├── SimDeviceSim.yml │ │ ├── SimHooks.yml │ │ ├── SingleJointedArmSim.yml │ │ ├── SolenoidSim.yml │ │ ├── StadiaControllerSim.yml │ │ ├── UltrasonicSim.yml │ │ └── XboxControllerSim.yml ├── tests │ ├── conftest.py │ ├── requirements.txt │ ├── run_tests.py │ ├── test_alert.py │ ├── test_datalogmanager.py │ ├── test_joystick.py │ ├── test_mechanism2d.py │ ├── test_notifier.py │ ├── test_sendable_chooser.py │ ├── test_wpilib.py │ ├── test_wpilib_drive.py │ ├── test_wpilib_interfaces.py │ └── test_wpilib_simulation.py └── wpilib │ ├── __init__.py │ ├── _impl │ ├── __init__.py │ ├── main.py │ ├── report_error.py │ ├── start.py │ └── utils.py │ ├── cameraserver.py │ ├── counter │ ├── __init__.py │ └── counter.cpp │ ├── deployinfo.py │ ├── drive │ ├── __init__.py │ └── drive.cpp │ ├── event │ ├── __init__.py │ └── event.cpp │ ├── interfaces │ ├── __init__.py │ └── interfaces.cpp │ ├── py.typed │ ├── shuffleboard │ ├── ShuffleboardData.cpp │ ├── ShuffleboardData.h │ ├── __init__.py │ └── shuffleboard.cpp │ ├── simulation │ ├── __init__.py │ └── simulation.cpp │ ├── src │ ├── main.cpp │ └── rpy │ │ ├── ControlWord.cpp │ │ ├── ControlWord.h │ │ ├── Filesystem.h │ │ ├── Filesystem.inc │ │ ├── MotorControllerGroup.cpp │ │ ├── MotorControllerGroup.h │ │ ├── Notifier.cpp │ │ ├── Notifier.h │ │ ├── SmartDashboardData.cpp │ │ └── SmartDashboardData.h │ └── sysid │ └── __init__.py ├── robotpy-wpimath ├── .gitignore ├── README.md ├── meson.build ├── pyproject.toml ├── semiwrap │ ├── .gitignore │ ├── ComputerVisionUtil.yml │ ├── MathUtil.yml │ ├── controls │ │ ├── ArmFeedforward.yml │ │ ├── BangBangController.yml │ │ ├── CentripetalAccelerationConstraint.yml │ │ ├── ControlAffinePlantInversionFeedforward.yml │ │ ├── DCMotor.yml │ │ ├── DifferentialDriveAccelerationLimiter.yml │ │ ├── DifferentialDriveFeedforward.yml │ │ ├── DifferentialDriveKinematicsConstraint.yml │ │ ├── DifferentialDrivePoseEstimator.yml │ │ ├── DifferentialDrivePoseEstimator3d.yml │ │ ├── DifferentialDriveVoltageConstraint.yml │ │ ├── DifferentialDriveWheelVoltages.yml │ │ ├── ElevatorFeedforward.yml │ │ ├── EllipticalRegionConstraint.yml │ │ ├── ExponentialProfile.yml │ │ ├── ExtendedKalmanFilter.yml │ │ ├── HolonomicDriveController.yml │ │ ├── ImplicitModelFollower.yml │ │ ├── KalmanFilter.yml │ │ ├── LTVDifferentialDriveController.yml │ │ ├── LTVUnicycleController.yml │ │ ├── LinearPlantInversionFeedforward.yml │ │ ├── LinearQuadraticRegulator.yml │ │ ├── LinearSystem.yml │ │ ├── LinearSystemId.yml │ │ ├── LinearSystemLoop.yml │ │ ├── LinearSystemLoopz.yml │ │ ├── MaxVelocityConstraint.yml │ │ ├── MecanumDriveKinematicsConstraint.yml │ │ ├── MecanumDrivePoseEstimator.yml │ │ ├── MecanumDrivePoseEstimator3d.yml │ │ ├── PIDController.yml │ │ ├── PoseEstimator.yml │ │ ├── PoseEstimator3d.yml │ │ ├── ProfiledPIDController.yml │ │ ├── RamseteController.yml │ │ ├── RectangularRegionConstraint.yml │ │ ├── SimpleMotorFeedforward.yml │ │ ├── SimulatedAnnealing.yml │ │ ├── SwerveDriveKinematicsConstraint.yml │ │ ├── SwerveDrivePoseEstimator.yml │ │ ├── SwerveDrivePoseEstimator3d.yml │ │ ├── Trajectory.yml │ │ ├── TrajectoryConfig.yml │ │ ├── TrajectoryConstraint.yml │ │ ├── TrajectoryGenerator.yml │ │ ├── TrajectoryParameterizer.yml │ │ ├── TrajectoryUtil.yml │ │ ├── TrapezoidProfile.yml │ │ └── TravelingSalesman.yml │ ├── filter │ │ ├── Debouncer.yml │ │ ├── LinearFilter.yml │ │ ├── MedianFilter.yml │ │ └── SlewRateLimiter.yml │ ├── geometry │ │ ├── CoordinateAxis.yml │ │ ├── CoordinateSystem.yml │ │ ├── Ellipse2d.yml │ │ ├── Pose2d.yml │ │ ├── Pose3d.yml │ │ ├── Quaternion.yml │ │ ├── Rectangle2d.yml │ │ ├── Rotation2d.yml │ │ ├── Rotation3d.yml │ │ ├── Transform2d.yml │ │ ├── Transform3d.yml │ │ ├── Translation2d.yml │ │ ├── Translation3d.yml │ │ ├── Twist2d.yml │ │ └── Twist3d.yml │ ├── interpolation │ │ └── TimeInterpolatableBuffer.yml │ ├── kinematics │ │ ├── ChassisSpeeds.yml │ │ ├── DifferentialDriveKinematics.yml │ │ ├── DifferentialDriveOdometry.yml │ │ ├── DifferentialDriveOdometry3d.yml │ │ ├── DifferentialDriveWheelPositions.yml │ │ ├── DifferentialDriveWheelSpeeds.yml │ │ ├── Kinematics.yml │ │ ├── MecanumDriveKinematics.yml │ │ ├── MecanumDriveOdometry.yml │ │ ├── MecanumDriveOdometry3d.yml │ │ ├── MecanumDriveWheelPositions.yml │ │ ├── MecanumDriveWheelSpeeds.yml │ │ ├── Odometry.yml │ │ ├── Odometry3d.yml │ │ ├── SwerveDriveKinematics.yml │ │ ├── SwerveDriveOdometry.yml │ │ ├── SwerveDriveOdometry3d.yml │ │ ├── SwerveModulePosition.yml │ │ └── SwerveModuleState.yml │ └── spline │ │ ├── CubicHermiteSpline.yml │ │ ├── QuinticHermiteSpline.yml │ │ ├── Spline.yml │ │ ├── SplineHelper.yml │ │ └── SplineParameterizer.yml ├── tests │ ├── conftest.py │ ├── cpp │ │ ├── .gitignore │ │ ├── meson.build │ │ ├── pyproject.toml │ │ ├── semiwrap │ │ │ ├── .gitignore │ │ │ └── module.yml │ │ └── wpimath_test │ │ │ ├── __init__.py │ │ │ ├── include │ │ │ └── module.h │ │ │ └── src │ │ │ └── module.cpp │ ├── geometry │ │ └── test_rotation2d.py │ ├── kinematics │ │ ├── test_chassis_speeds.py │ │ └── test_swerve.py │ ├── requirements.txt │ ├── run_tests.py │ ├── test_controller.py │ ├── test_estimator.py │ ├── test_interpolation.py │ ├── test_optimization_simulated_annealing.py │ ├── test_spline.py │ ├── test_system.py │ ├── test_trajectory.py │ ├── test_trajectory_exponential_profile.py │ └── test_units.py ├── tools │ └── create_units.py └── wpimath │ ├── __init__.py │ ├── _controls │ ├── __init__.py │ └── controls.cpp │ ├── _impl │ ├── __init__.py │ └── src │ │ ├── PyTrajectoryConstraint.h │ │ └── type_casters │ │ ├── _units_base_type_caster.h │ │ ├── frc_eigen.h │ │ ├── units_acceleration_type_caster.h │ │ ├── units_angle_type_caster.h │ │ ├── units_angular_acceleration_type_caster.h │ │ ├── units_angular_velocity_type_caster.h │ │ ├── units_area_type_caster.h │ │ ├── units_capacitance_type_caster.h │ │ ├── units_charge_type_caster.h │ │ ├── units_compound_type_caster.h │ │ ├── units_concentration_type_caster.h │ │ ├── units_conductance_type_caster.h │ │ ├── units_current_type_caster.h │ │ ├── units_data_transfer_rate_type_caster.h │ │ ├── units_data_type_caster.h │ │ ├── units_density_type_caster.h │ │ ├── units_energy_type_caster.h │ │ ├── units_force_type_caster.h │ │ ├── units_frequency_type_caster.h │ │ ├── units_illuminance_type_caster.h │ │ ├── units_impedance_type_caster.h │ │ ├── units_inductance_type_caster.h │ │ ├── units_length_type_caster.h │ │ ├── units_luminous_flux_type_caster.h │ │ ├── units_luminous_intensity_type_caster.h │ │ ├── units_magnetic_field_strength_type_caster.h │ │ ├── units_magnetic_flux_type_caster.h │ │ ├── units_mass_type_caster.h │ │ ├── units_misc_type_caster.h │ │ ├── units_moment_of_inertia_type_caster.h │ │ ├── units_power_type_caster.h │ │ ├── units_pressure_type_caster.h │ │ ├── units_radiation_type_caster.h │ │ ├── units_solid_angle_type_caster.h │ │ ├── units_substance_type_caster.h │ │ ├── units_temperature_type_caster.h │ │ ├── units_time_type_caster.h │ │ ├── units_torque_type_caster.h │ │ ├── units_velocity_type_caster.h │ │ ├── units_voltage_type_caster.h │ │ └── units_volume_type_caster.h │ ├── controller │ └── __init__.py │ ├── estimator │ └── __init__.py │ ├── filter │ ├── __init__.py │ └── filter.cpp │ ├── geometry │ ├── __init__.py │ ├── geometry.cpp │ └── include │ │ └── rpy │ │ └── geometryToString.h │ ├── interpolation │ ├── __init__.py │ └── interpolation.cpp │ ├── kinematics │ ├── __init__.py │ └── kinematics.cpp │ ├── optimization │ └── __init__.py │ ├── path │ └── __init__.py │ ├── py.typed │ ├── spline │ ├── __init__.py │ └── spline.cpp │ ├── src │ └── wpimath.cpp │ ├── system │ ├── __init__.py │ └── plant │ │ └── __init__.py │ ├── trajectory │ ├── __init__.py │ └── constraint │ │ └── __init__.py │ └── units.py ├── robotpy-wpinet ├── .gitignore ├── README.md ├── examples │ └── portfwd.py ├── meson.build ├── pyproject.toml ├── semiwrap │ ├── .gitignore │ ├── PortForwarder.yml │ └── WebServer.yml ├── tests │ ├── requirements.txt │ ├── run_tests.py │ └── test_wpinet.py └── wpinet │ ├── __init__.py │ ├── py.typed │ └── src │ └── main.cpp ├── robotpy-wpiutil ├── .gitignore ├── examples │ ├── printlog.py │ └── writelog.py ├── meson.build ├── pyproject.toml ├── semiwrap │ ├── .gitignore │ ├── DataLog.yml │ ├── DataLogBackgroundWriter.yml │ ├── DataLogReader.yml │ ├── DataLogWriter.yml │ ├── RawFrame.yml │ ├── Sendable.yml │ ├── SendableBuilder.yml │ ├── SendableHelper.yml │ ├── SendableRegistry.yml │ ├── StackTrace.yml │ ├── Synchronization.yml │ ├── WPyStruct.yml │ ├── modules │ │ └── .gitignore │ └── trampolines │ │ └── .gitignore ├── tests │ ├── conftest.py │ ├── cpp │ │ ├── meson.build │ │ ├── pyproject.toml │ │ └── wpiutil_test │ │ │ ├── __init__.py │ │ │ ├── module.cpp │ │ │ ├── sendable_test.cpp │ │ │ └── struct_test.cpp │ ├── requirements.txt │ ├── run_tests.py │ ├── test_array.py │ ├── test_ct_string.py │ ├── test_json.py │ ├── test_sendable.py │ ├── test_smallset.py │ ├── test_smallvector.py │ ├── test_span.py │ ├── test_stacktrace.py │ ├── test_stringmap.py │ └── test_struct.py └── wpiutil │ ├── __init__.py │ ├── _stacktrace.py │ ├── log │ └── __init__.py │ ├── py.typed │ ├── src │ ├── main.cpp │ ├── safethread_gil.cpp │ ├── stacktracehook.cpp │ ├── type_casters │ │ ├── wpi_array_type_caster.h │ │ ├── wpi_ct_string_type_caster.h │ │ ├── wpi_json_type_caster.h │ │ ├── wpi_smallset_type_caster.h │ │ ├── wpi_smallvector_type_caster.h │ │ ├── wpi_smallvectorimpl_type_caster.h │ │ ├── wpi_span_type_caster.h │ │ └── wpi_string_map_caster.h │ └── wpistruct │ │ ├── wpystruct.h │ │ ├── wpystruct_fns.cpp │ │ └── wpystruct_fns.h │ ├── sync │ └── __init__.py │ └── wpistruct │ ├── __init__.py │ ├── dataclass.py │ ├── desc.py │ └── typing.py └── robotpy-xrp ├── .gitignore ├── README.md ├── meson.build ├── pyproject.toml ├── semiwrap ├── .gitignore ├── XRPGyro.yml ├── XRPMotor.yml ├── XRPOnBoardIO.yml ├── XRPRangefinder.yml ├── XRPReflectanceSensor.yml └── XRPServo.yml ├── tests ├── requirements.txt ├── run_tests.py └── test_xrp.py └── xrp ├── __init__.py ├── extension ├── __init__.py └── main.py ├── py.typed ├── src └── main.cpp └── xrp.pc /.gitignore: -------------------------------------------------------------------------------- 1 | 2 | *.py[ciod] 3 | /dist 4 | /dist-other 5 | /cache 6 | 7 | rpy-include 8 | .venv/ 9 | -------------------------------------------------------------------------------- /.readthedocs.yml: -------------------------------------------------------------------------------- 1 | version: 2 2 | 3 | sphinx: 4 | configuration: docs/conf.py 5 | 6 | build: 7 | os: ubuntu-22.04 8 | tools: 9 | python: "3.11" 10 | jobs: 11 | post_install: 12 | - python -m robotpy_sphinx.download_and_install robotpy mostrobotpy main dist pypi-other-X64-3.11 13 | - python -m robotpy_sphinx.download_and_install robotpy mostrobotpy main dist pypi-Linux-X64-3.11 14 | post_build: 15 | - mkdir --parents _readthedocs/htmlzip 16 | - cp --recursive _readthedocs/html _readthedocs/$READTHEDOCS_PROJECT 17 | - cd _readthedocs ; zip --recurse-path --symlinks htmlzip/$READTHEDOCS_PROJECT.zip $READTHEDOCS_PROJECT 18 | 19 | python: 20 | install: 21 | - requirements: docs/requirements.txt 22 | -------------------------------------------------------------------------------- /devtools/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/devtools/__init__.py -------------------------------------------------------------------------------- /docs/Makefile: -------------------------------------------------------------------------------- 1 | # Minimal makefile for Sphinx documentation 2 | # 3 | 4 | # You can set these variables from the command line, and also 5 | # from the environment for the first two. 6 | SPHINXOPTS ?= 7 | SPHINXBUILD ?= sphinx-build 8 | SOURCEDIR = . 9 | BUILDDIR = _build 10 | 11 | # Put it first so that "make" without argument is like "make help". 12 | help: 13 | @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 14 | 15 | .PHONY: help Makefile 16 | 17 | # Catch-all target: route all unknown targets to Sphinx using the new 18 | # "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). 19 | %: Makefile 20 | @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) 21 | -------------------------------------------------------------------------------- /docs/cscore.imagewriter.rst: -------------------------------------------------------------------------------- 1 | cscore.imagewriter Package 2 | =========================== 3 | 4 | .. automodule:: cscore.imagewriter 5 | :members: 6 | -------------------------------------------------------------------------------- /docs/index.rst: -------------------------------------------------------------------------------- 1 | 2 | RobotPy API Documentation 3 | ========================= 4 | 5 | .. include:: _sidebar.rst.inc 6 | 7 | Indices and tables 8 | ================== 9 | 10 | * :ref:`genindex` 11 | * :ref:`modindex` 12 | * :ref:`search` 13 | -------------------------------------------------------------------------------- /docs/ntcore.util.rst: -------------------------------------------------------------------------------- 1 | ntcore.util Package 2 | =========================== 3 | 4 | .. automodule:: ntcore.util 5 | :members: 6 | -------------------------------------------------------------------------------- /docs/requirements.txt: -------------------------------------------------------------------------------- 1 | sphinx 2 | sphinx-rtd-theme 3 | robotpy-sphinx-plugin~=0.2 4 | opencv-python 5 | -------------------------------------------------------------------------------- /docs/wpilib.cameraserver.rst: -------------------------------------------------------------------------------- 1 | wpilib.cameraserver Package 2 | =========================== 3 | 4 | .. automodule:: wpilib.cameraserver 5 | :members: 6 | -------------------------------------------------------------------------------- /docs/wpilib.deployinfo.rst: -------------------------------------------------------------------------------- 1 | wpilib.deployinfo Package 2 | =========================== 3 | 4 | .. automodule:: wpilib.deployinfo 5 | :members: 6 | -------------------------------------------------------------------------------- /docs/wpimath.units.rst: -------------------------------------------------------------------------------- 1 | wpimath.units Package 2 | ===================== 3 | 4 | .. automodule:: wpimath.units 5 | :members: 6 | -------------------------------------------------------------------------------- /examples/cscore/usbstream.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import cscore as cs 4 | 5 | camera = cs.UsbCamera("usbcam", 0) 6 | camera.setVideoMode(cs.VideoMode.PixelFormat.kMJPEG, 320, 240, 30) 7 | 8 | mjpegServer = cs.MjpegServer("httpserver", 8081) 9 | mjpegServer.setSource(camera) 10 | 11 | print("mjpg server listening at http://0.0.0.0:8081") 12 | input("Press enter to exit...") 13 | -------------------------------------------------------------------------------- /rdev.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | 3 | cd "$(dirname "$0")" 4 | python3 -m devtools "$@" 5 | -------------------------------------------------------------------------------- /rdev_requirements.txt: -------------------------------------------------------------------------------- 1 | black 2 | build 3 | click 4 | packaging 5 | pytest 6 | tomlkit 7 | tomli 8 | toposort 9 | validobj~=1.2 10 | 11 | ninja 12 | msvc-runtime>=14.42.34433; platform_system == 'Windows' 13 | -------------------------------------------------------------------------------- /subprojects/pyntcore/.gitignore: -------------------------------------------------------------------------------- 1 | *.py[ciod] 2 | *.egg-info 3 | __pycache__ 4 | .vscode 5 | 6 | *.so 7 | *.dylib 8 | *.dll 9 | 10 | /build 11 | /dist 12 | 13 | /ntcore/lib 14 | /ntcore/_init__ntcore.py 15 | /ntcore/ntcore.pc 16 | /ntcore/version.py 17 | /ntcore/trampolines -------------------------------------------------------------------------------- /subprojects/pyntcore/README.md: -------------------------------------------------------------------------------- 1 | pyntcore 2 | ======== 3 | 4 | Python pybind11 wrappers around the C++ ntcore library. -------------------------------------------------------------------------------- /subprojects/pyntcore/meson.build: -------------------------------------------------------------------------------- 1 | project('pyntcore', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | ntcore_sources += files( 8 | 'ntcore/src/ntcore.cpp', 9 | 'ntcore/src/nt_instance.cpp', 10 | 'ntcore/src/py2value.cpp', 11 | 'ntcore/src/pyentry.cpp', 12 | ) 13 | 14 | subdir('semiwrap/modules') 15 | -------------------------------------------------------------------------------- /subprojects/pyntcore/ntcore/meta/__init__.py: -------------------------------------------------------------------------------- 1 | # autogenerated by 'semiwrap create-imports ntcore.meta ntcore._ntcore.meta' 2 | from .._ntcore.meta import ( 3 | Client, 4 | ClientPublisher, 5 | ClientSubscriber, 6 | SubscriberOptions, 7 | TopicPublisher, 8 | TopicSubscriber, 9 | decodeClientPublishers, 10 | decodeClientSubscribers, 11 | decodeClients, 12 | decodeTopicPublishers, 13 | decodeTopicSubscribers, 14 | ) 15 | 16 | __all__ = [ 17 | "Client", 18 | "ClientPublisher", 19 | "ClientSubscriber", 20 | "SubscriberOptions", 21 | "TopicPublisher", 22 | "TopicSubscriber", 23 | "decodeClientPublishers", 24 | "decodeClientSubscribers", 25 | "decodeClients", 26 | "decodeTopicPublishers", 27 | "decodeTopicSubscribers", 28 | ] 29 | -------------------------------------------------------------------------------- /subprojects/pyntcore/ntcore/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/pyntcore/ntcore/py.typed -------------------------------------------------------------------------------- /subprojects/pyntcore/ntcore/src/nt_instance.h: -------------------------------------------------------------------------------- 1 | 2 | #pragma once 3 | 4 | #include 5 | #include 6 | 7 | namespace pyntcore { 8 | 9 | void onInstanceStart(nt::NetworkTableInstance *instance); 10 | void onInstancePreReset(nt::NetworkTableInstance *instance); 11 | void onInstancePostReset(nt::NetworkTableInstance *instance); 12 | void onInstanceDestroy(nt::NetworkTableInstance *instance); 13 | 14 | void resetAllInstances(); 15 | 16 | }; // namespace pyntcore 17 | -------------------------------------------------------------------------------- /subprojects/pyntcore/ntcore/src/ntcore.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include "nt_instance.h" 4 | 5 | SEMIWRAP_PYBIND11_MODULE(m) { 6 | initWrapper(m); 7 | 8 | static int unused; 9 | py::capsule cleanup(&unused, [](void *) { 10 | pyntcore::resetAllInstances(); 11 | }); 12 | 13 | m.add_object("_st_cleanup", cleanup); 14 | } -------------------------------------------------------------------------------- /subprojects/pyntcore/ntcore/src/py2value.h: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | namespace pyntcore { 8 | 9 | const char * nttype2str(NT_Type type); 10 | 11 | py::object ntvalue2py(const nt::Value &ntvalue); 12 | 13 | nt::Value py2ntvalue(py::handle h); 14 | 15 | py::function valueFactoryByType(nt::NetworkTableType type); 16 | 17 | inline void ensure_value_is(NT_Type expected, nt::Value *v) { 18 | if (v->type() != expected) { 19 | throw py::value_error(fmt::format( 20 | "Value type is {}, not {}", nttype2str(v->type()), nttype2str(expected) 21 | )); 22 | } 23 | } 24 | 25 | }; -------------------------------------------------------------------------------- /subprojects/pyntcore/ntcore/types.py: -------------------------------------------------------------------------------- 1 | from typing import Sequence, Union 2 | 3 | ValueT = Union[ 4 | bool, 5 | int, 6 | float, 7 | str, 8 | bytes, 9 | Sequence[bool], 10 | Sequence[int], 11 | Sequence[float], 12 | Sequence[str], 13 | ] 14 | -------------------------------------------------------------------------------- /subprojects/pyntcore/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/pyntcore/semiwrap/ConnectionListener.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | nt::ConnectionListener: 4 | methods: 5 | ConnectionListener: 6 | overloads: 7 | '': 8 | nt::NetworkTableInstance, bool, std::function: 9 | GetHandle: 10 | nt::ConnectionListenerPoller: 11 | methods: 12 | ConnectionListenerPoller: 13 | overloads: 14 | '': 15 | nt::NetworkTableInstance: 16 | GetHandle: 17 | Add: 18 | Remove: 19 | ReadQueue: 20 | -------------------------------------------------------------------------------- /subprojects/pyntcore/semiwrap/MultiSubscriber.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | nt::MultiSubscriber: 4 | methods: 5 | MultiSubscriber: 6 | overloads: 7 | '': 8 | ignore: true 9 | NetworkTableInstance, std::span, const PubSubOptions&: 10 | GetHandle: 11 | ignore: true 12 | inline_code: | 13 | .def("close", [](MultiSubscriber *self) { 14 | py::gil_scoped_release release; 15 | *self = MultiSubscriber(); 16 | }, py::doc("Destroys the subscriber")) 17 | .def("__enter__", [](MultiSubscriber *self) { 18 | return self; 19 | }) 20 | .def("__exit__", [](MultiSubscriber *self, py::args args) { 21 | py::gil_scoped_release release; 22 | *self = MultiSubscriber(); 23 | }) 24 | -------------------------------------------------------------------------------- /subprojects/pyntcore/semiwrap/NTSendable.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - networktables/NTSendableBuilder.h 3 | 4 | classes: 5 | nt::NTSendable: 6 | methods: 7 | InitSendable: 8 | overloads: 9 | NTSendableBuilder&: 10 | virtual_xform: | 11 | [&](py::function fn) { 12 | auto builderHandle = py::cast(builder, py::return_value_policy::reference); 13 | fn(builderHandle); 14 | } 15 | wpi::SendableBuilder&: 16 | virtual_xform: | 17 | [&](py::function fn) { 18 | auto builderHandle = py::cast(builder, py::return_value_policy::reference); 19 | fn(builderHandle); 20 | } 21 | -------------------------------------------------------------------------------- /subprojects/pyntcore/semiwrap/NTSendableBuilder.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | nt::NTSendableBuilder: 4 | force_type_casters: 5 | - std::function 6 | typealias: 7 | - BackendKind = wpi::SendableBuilder::BackendKind 8 | methods: 9 | SetUpdateTable: 10 | cpp_code: | 11 | [](NTSendableBuilder *self, std::function func) { 12 | self->SetUpdateTable(std::move(func)); 13 | } 14 | GetTopic: 15 | GetTable: 16 | GetBackendKind: 17 | -------------------------------------------------------------------------------- /subprojects/pyntcore/semiwrap/NetworkTableType.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | NetworkTableType: 4 | -------------------------------------------------------------------------------- /subprojects/pyntcore/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest -------------------------------------------------------------------------------- /subprojects/pyntcore/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/.gitignore: -------------------------------------------------------------------------------- 1 | *.py[ciod] 2 | *.egg-info 3 | __pycache__ 4 | .vscode 5 | 6 | *.so 7 | *.dylib 8 | *.dll 9 | 10 | /build 11 | /dist 12 | 13 | /robotpy_apriltag/include 14 | /robotpy_apriltag/lib 15 | /robotpy_apriltag/_init__apriltag.py 16 | /robotpy_apriltag/apriltag.pc 17 | /robotpy_apriltag/version.py 18 | /robotpy_apriltag/trampolines -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/README.md: -------------------------------------------------------------------------------- 1 | robotpy-apriltag 2 | ================ 3 | 4 | RobotPy wrappers around WPILib's version of the apriltag library. 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/meson.build: -------------------------------------------------------------------------------- 1 | project('robotpy-apriltag', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | apriltag_sources += files( 8 | 'robotpy_apriltag/src/main.cpp', 9 | ) 10 | 11 | subdir('semiwrap/modules') 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/robotpy_apriltag/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__apriltag 2 | 3 | # autogenerated by 'semiwrap create-imports robotpy_apriltag robotpy_apriltag._apriltag' 4 | from ._apriltag import ( 5 | AprilTag, 6 | AprilTagDetection, 7 | AprilTagDetector, 8 | AprilTagField, 9 | AprilTagFieldLayout, 10 | AprilTagPoseEstimate, 11 | AprilTagPoseEstimator, 12 | ) 13 | 14 | __all__ = [ 15 | "AprilTag", 16 | "AprilTagDetection", 17 | "AprilTagDetector", 18 | "AprilTagField", 19 | "AprilTagFieldLayout", 20 | "AprilTagPoseEstimate", 21 | "AprilTagPoseEstimator", 22 | ] 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/robotpy_apriltag/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-apriltag/robotpy_apriltag/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/robotpy_apriltag/src/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.robotpy_apriltag._apriltag.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) { initWrapper(m); } 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/semiwrap/AprilTag.yml: -------------------------------------------------------------------------------- 1 | 2 | functions: 3 | to_json: 4 | ignore: true 5 | from_json: 6 | ignore: true 7 | classes: 8 | frc::AprilTag: 9 | attributes: 10 | ID: 11 | pose: 12 | methods: 13 | Generate36h11AprilTagImage: 14 | ignore: true 15 | Generate16h5AprilTagImage: 16 | ignore: true 17 | operator==: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/semiwrap/AprilTagFieldLayout.yml: -------------------------------------------------------------------------------- 1 | 2 | functions: 3 | to_json: 4 | ignore: true 5 | from_json: 6 | ignore: true 7 | LoadAprilTagLayoutField: 8 | ignore: true 9 | classes: 10 | frc::AprilTagFieldLayout: 11 | enums: 12 | OriginPosition: 13 | methods: 14 | AprilTagFieldLayout: 15 | overloads: 16 | '': 17 | std::string_view: 18 | std::vector, units::meter_t, units::meter_t: 19 | LoadField: 20 | GetFieldLength: 21 | GetFieldWidth: 22 | GetTags: 23 | SetOrigin: 24 | overloads: 25 | OriginPosition: 26 | const Pose3d&: 27 | GetOrigin: 28 | GetTagPose: 29 | Serialize: 30 | operator==: 31 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/semiwrap/AprilTagFields.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | AprilTagField: 4 | functions: 5 | LoadAprilTagLayoutField: 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/semiwrap/AprilTagPoseEstimate.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::AprilTagPoseEstimate: 4 | attributes: 5 | pose1: 6 | pose2: 7 | error1: 8 | error2: 9 | methods: 10 | GetAmbiguity: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | opencv-python~=4.6 -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/tests/tag1_640_480.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-apriltag/tests/tag1_640_480.jpg -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/tests/tag2_16h5_straight.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-apriltag/tests/tag2_16h5_straight.png -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/tests/tag2_45deg_X.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-apriltag/tests/tag2_45deg_X.png -------------------------------------------------------------------------------- /subprojects/robotpy-apriltag/tests/tag2_45deg_y.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-apriltag/tests/tag2_45deg_y.png -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/.gitignore: -------------------------------------------------------------------------------- 1 | *.pyc 2 | *.egg-info 3 | __pycache__ 4 | *.so 5 | *.dll 6 | *.pybind11.json 7 | *.pc 8 | 9 | /cscore/_init__cscore.py 10 | /cscore/trampolines 11 | /cscore/version.py 12 | 13 | /lib 14 | /dist 15 | /build 16 | 17 | .project 18 | .pydevproject 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/.gittrack: -------------------------------------------------------------------------------- 1 | [git-source-track] 2 | validation_root = cscore 3 | exclude_commits_file = .gittrackexclude 4 | upstream_root = ../allwpilib/cameraserver/src/main/java 5 | upstream_commit = 60c2f5905191c25c3e4ff2fc735cec2ca5f012bf 6 | 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/README.rst: -------------------------------------------------------------------------------- 1 | robotpy-cscore 2 | ============== 3 | 4 | These are python bindings for the cscore library, which is a high performance 5 | library used in the FIRST Robotics competition to serve video to/from robots. 6 | However, the core library is suitable for use in other applications, and is 7 | comparable to something like mjpg-streamer. 8 | 9 | This library requires python 3.6+ 10 | 11 | Documentation 12 | ============= 13 | 14 | * `Installation `_ 15 | * `Usage `_ 16 | 17 | Author 18 | ====== 19 | 20 | Dustin Spicuzza (dustin@virtualroadside.com) 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/cscore/_logging.py: -------------------------------------------------------------------------------- 1 | import logging 2 | import typing 3 | 4 | from ._cscore import _setLogger 5 | 6 | 7 | def enableLogging(level: typing.Optional[int] = None): 8 | """Enable logging for cscore""" 9 | if level is None: 10 | level = logging.DEBUG 11 | logger = logging.getLogger("cscore") 12 | _setLogger(lambda lvl, file, line, msg: logger.log(lvl, msg), level) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/cscore/cvnp/cvnp_synonyms.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | #include 3 | #include 4 | #include 5 | #include 6 | 7 | 8 | namespace cvnp 9 | { 10 | struct TypeSynonyms 11 | { 12 | int cv_depth = -1; 13 | std::string cv_depth_name; 14 | std::string np_format; 15 | std::string np_format_long; 16 | 17 | pybind11::dtype dtype() { return pybind11::dtype(np_format); } 18 | std::string str() const; 19 | }; 20 | 21 | extern std::vector sTypeSynonyms; 22 | 23 | std::vector list_types_synonyms(); 24 | void print_types_synonyms(); 25 | } -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/meson.build: -------------------------------------------------------------------------------- 1 | project('robotpy-cscore', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | cscore_sources += files( 8 | 'cscore/src/main.cpp', 9 | 'cscore/cvnp/cvnp.cpp', 10 | 'cscore/cvnp/cvnp_synonyms.cpp', 11 | ) 12 | 13 | # 14 | # Statically link to cscore/opencv to avoid exporting opencv symbols 15 | # 16 | 17 | cpp = meson.get_compiler('cpp') 18 | libs_path = meson.current_source_dir() + '/lib/lib' 19 | 20 | cscore_deps += [ 21 | cpp.find_library('opencv480', dirs: libs_path), 22 | cpp.find_library('cscore', dirs: libs_path), 23 | cpp.find_library('cameraserver', dirs: libs_path), 24 | ] 25 | 26 | subdir('semiwrap/modules') 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/semiwrap/cscore_runloop.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | functions: 4 | RunMainRunLoop: 5 | RunMainRunLoopTimeout: 6 | StopMainRunLoop: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | numpy -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/tests/test_cv.py: -------------------------------------------------------------------------------- 1 | import cscore as cs 2 | import numpy as np 3 | 4 | 5 | def test_empty_img(): 6 | img = np.zeros(shape=(0, 0, 3)) 7 | sink = cs.CvSink("something") 8 | _, rimg = sink.grabFrame(img) 9 | assert (rimg == img).all() 10 | 11 | 12 | def test_nonempty_img(): 13 | img = np.zeros(shape=(480, 640, 3), dtype=np.uint8) 14 | img2 = np.zeros(shape=(480, 640, 3), dtype=np.uint8) 15 | sink = cs.CvSink("something") 16 | _, img = sink.grabFrame(img) 17 | _, img = sink.grabFrame(img) 18 | assert (img == img2).all() 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-cscore/tests/test_import.py: -------------------------------------------------------------------------------- 1 | import cscore 2 | 3 | 4 | def test_cscore_import(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/.gitignore: -------------------------------------------------------------------------------- 1 | *.py[ciod] 2 | *.egg-info 3 | 4 | *.so 5 | *.dll 6 | *.dylib 7 | 8 | .vscode 9 | 10 | __pycache__ 11 | /hal/trampolines 12 | /hal/_init__wpiHal.py 13 | /hal/version.py 14 | /hal/wpihal.pc 15 | /hal/simulation/_init__simulation.py 16 | /hal/simulation/hal_simulation.pc 17 | /hal/simulation/trampolines 18 | 19 | /dist 20 | /build -------------------------------------------------------------------------------- /subprojects/robotpy-hal/README.md: -------------------------------------------------------------------------------- 1 | robotpy-hal 2 | =========== 3 | 4 | Python wrappers around the WPILib HAL. 5 | 6 | API Documentation can be found at 7 | https://robotpy.readthedocs.io/projects/hal/en/latest -------------------------------------------------------------------------------- /subprojects/robotpy-hal/hal/__init__.py: -------------------------------------------------------------------------------- 1 | from .version import version as __version__ 2 | 3 | # Only needed for side effects 4 | from . import _initialize 5 | from .exceptions import HALError 6 | 7 | from . import _init__wpiHal 8 | from ._wpiHal import * 9 | 10 | from ._wpiHal import __hal_simulation__ 11 | 12 | del _init__wpiHal 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/hal/_initialize.py: -------------------------------------------------------------------------------- 1 | from . import exceptions, _init__wpiHal, _wpiHal 2 | 3 | # Always initialize HAL here, disable extension notice because we'll handle 4 | # that for users 5 | _sse = getattr(_wpiHal, "setShowExtensionsNotFoundMessages", None) 6 | if _sse: 7 | _wpiHal.setShowExtensionsNotFoundMessages(False) 8 | 9 | _wpiHal.initialize(500, 0) 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/hal/exceptions.py: -------------------------------------------------------------------------------- 1 | class HALError(RuntimeError): 2 | pass 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/hal/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-hal/hal/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-hal/hal/simulation/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__simulation 2 | from ._simulation import * 3 | 4 | del _init__simulation 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/hal/simulation/resethandles.cpp: -------------------------------------------------------------------------------- 1 | 2 | 3 | #ifndef __FRC_ROBORIO__ 4 | #include 5 | #include 6 | #include 7 | 8 | void HALSIM_ResetGlobalHandles() { 9 | 10 | // if we just reset the handles, notifiers might hang forever, 11 | // so we just enumerate and cancel them all 12 | auto sz = HALSIM_GetNotifierInfo(nullptr, 0); 13 | if (sz > 0) { 14 | struct HALSIM_NotifierInfo *info = new struct HALSIM_NotifierInfo[sz]; 15 | HALSIM_GetNotifierInfo(info, sz); 16 | 17 | for (int i = 0; i < sz; i++) { 18 | HAL_CleanNotifier(info->handle); 19 | } 20 | } 21 | 22 | hal::HandleBase::ResetGlobalHandles(); 23 | } 24 | 25 | #else 26 | 27 | void HALSIM_ResetGlobalHandles() {} 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/hal/simulation/sim_cb.h: -------------------------------------------------------------------------------- 1 | 2 | #pragma once 3 | 4 | class SimCB { 5 | public: 6 | 7 | SimCB(std::function fn, std::function cancel) : 8 | m_fn(fn), 9 | m_cancel(cancel) 10 | {} 11 | 12 | void SetUID(int32_t uid) { 13 | m_uid = uid; 14 | } 15 | 16 | ~SimCB() { 17 | Cancel(); 18 | } 19 | 20 | void Cancel() { 21 | if (m_valid) { 22 | m_cancel(m_uid); 23 | m_valid = false; 24 | } 25 | } 26 | 27 | std::function m_fn; 28 | 29 | private: 30 | bool m_valid = true; 31 | int32_t m_uid; 32 | std::function m_cancel; 33 | }; -------------------------------------------------------------------------------- /subprojects/robotpy-hal/meson.build: -------------------------------------------------------------------------------- 1 | project('robotpy-hal', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | wpihal_sources += files( 8 | 'hal/src/hal.cpp', 9 | ) 10 | 11 | hal_simulation_sources += files( 12 | 'hal/simulation/main.cpp', 13 | 'hal/simulation/resethandles.cpp', 14 | ) 15 | 16 | subdir('semiwrap/modules') 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Accelerometer.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | enums: 7 | HAL_AccelerometerRange: 8 | functions: 9 | HAL_SetAccelerometerActive: 10 | HAL_SetAccelerometerRange: 11 | HAL_GetAccelerometerX: 12 | HAL_GetAccelerometerY: 13 | HAL_GetAccelerometerZ: 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/AddressableLED.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeAddressableLED: 8 | HAL_FreeAddressableLED: 9 | HAL_SetAddressableLEDOutputPort: 10 | HAL_SetAddressableLEDLength: 11 | HAL_WriteAddressableLEDData: 12 | HAL_SetAddressableLEDBitTiming: 13 | HAL_SetAddressableLEDSyncTime: 14 | HAL_StartAddressableLEDOutput: 15 | HAL_StopAddressableLEDOutput: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/AddressableLEDTypes.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | classes: 7 | HAL_AddressableLEDData: 8 | attributes: 9 | b: 10 | g: 11 | r: 12 | padding: 13 | ignore: true 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/AnalogAccumulator.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_IsAccumulatorChannel: 8 | HAL_InitAccumulator: 9 | HAL_ResetAccumulator: 10 | HAL_SetAccumulatorCenter: 11 | HAL_SetAccumulatorDeadband: 12 | HAL_GetAccumulatorValue: 13 | HAL_GetAccumulatorCount: 14 | HAL_GetAccumulatorOutput: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/AnalogGyro.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeAnalogGyro: 8 | HAL_SetupAnalogGyro: 9 | HAL_FreeAnalogGyro: 10 | HAL_SetAnalogGyroParameters: 11 | HAL_SetAnalogGyroVoltsPerDegreePerSecond: 12 | HAL_ResetAnalogGyro: 13 | HAL_CalibrateAnalogGyro: 14 | HAL_SetAnalogGyroDeadband: 15 | HAL_GetAnalogGyroAngle: 16 | HAL_GetAnalogGyroRate: 17 | HAL_GetAnalogGyroOffset: 18 | HAL_GetAnalogGyroCenter: 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/AnalogInput.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeAnalogInputPort: 8 | HAL_FreeAnalogInputPort: 9 | HAL_CheckAnalogModule: 10 | HAL_CheckAnalogInputChannel: 11 | HAL_SetAnalogInputSimDevice: 12 | HAL_SetAnalogSampleRate: 13 | HAL_GetAnalogSampleRate: 14 | HAL_SetAnalogAverageBits: 15 | HAL_GetAnalogAverageBits: 16 | HAL_SetAnalogOversampleBits: 17 | HAL_GetAnalogOversampleBits: 18 | HAL_GetAnalogValue: 19 | HAL_GetAnalogAverageValue: 20 | HAL_GetAnalogVoltsToValue: 21 | HAL_GetAnalogVoltage: 22 | HAL_GetAnalogAverageVoltage: 23 | HAL_GetAnalogLSBWeight: 24 | HAL_GetAnalogOffset: 25 | HAL_GetAnalogValueToVolts: 26 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/AnalogOutput.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeAnalogOutputPort: 8 | HAL_FreeAnalogOutputPort: 9 | HAL_SetAnalogOutput: 10 | HAL_GetAnalogOutput: 11 | HAL_CheckAnalogOutputChannel: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/AnalogTrigger.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | enums: 7 | HAL_AnalogTriggerType: 8 | value_prefix: HAL_Trigger 9 | functions: 10 | HAL_InitializeAnalogTrigger: 11 | HAL_InitializeAnalogTriggerDutyCycle: 12 | HAL_CleanAnalogTrigger: 13 | HAL_SetAnalogTriggerLimitsRaw: 14 | HAL_SetAnalogTriggerLimitsVoltage: 15 | HAL_SetAnalogTriggerLimitsDutyCycle: 16 | HAL_SetAnalogTriggerAveraged: 17 | HAL_SetAnalogTriggerFiltered: 18 | HAL_GetAnalogTriggerInWindow: 19 | HAL_GetAnalogTriggerTriggerState: 20 | HAL_GetAnalogTriggerOutput: 21 | HAL_GetAnalogTriggerFPGAIndex: 22 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/CAN.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_CAN_SendMessage: 8 | buffers: 9 | - { type: IN, src: data, len: dataSize } 10 | HAL_CAN_ReceiveMessage: 11 | buffers: 12 | - { type: OUT, src: data, len: dataSize, minsz: 8 } 13 | HAL_CAN_OpenStreamSession: 14 | HAL_CAN_CloseStreamSession: 15 | HAL_CAN_ReadStreamSession: 16 | ignore: true # TODO: an array of messages 17 | HAL_CAN_GetCANStatus: 18 | classes: 19 | HAL_CANStreamMessage: 20 | attributes: 21 | messageID: 22 | timeStamp: 23 | data: 24 | dataSize: 25 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/CANAPI.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_GetCANPacketBaseTime: 8 | HAL_InitializeCAN: 9 | HAL_CleanCAN: 10 | HAL_WriteCANPacket: 11 | buffers: 12 | - { type: IN, src: data, len: length } 13 | HAL_WriteCANPacketRepeating: 14 | buffers: 15 | - { type: IN, src: data, len: length } 16 | HAL_WriteCANRTRFrame: 17 | HAL_StopCANPacketRepeating: 18 | HAL_ReadCANPacketNew: 19 | buffers: 20 | - { type: OUT, src: data, len: length, minsz: 8 } 21 | HAL_ReadCANPacketLatest: 22 | buffers: 23 | - { type: OUT, src: data, len: length, minsz: 8 } 24 | HAL_ReadCANPacketTimeout: 25 | buffers: 26 | - { type: OUT, src: data, len: length, minsz: 8 } 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/CANAPITypes.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | enums: 7 | HAL_CANDeviceType: 8 | value_prefix: HAL_CAN_Dev 9 | HAL_CANManufacturer: 10 | value_prefix: HAL_CAN_Man -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Constants.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_GetSystemClockTicksPerMicrosecond: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/DIO.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeDIOPort: 8 | HAL_CheckDIOChannel: 9 | HAL_FreeDIOPort: 10 | HAL_SetDIOSimDevice: 11 | HAL_AllocateDigitalPWM: 12 | HAL_FreeDigitalPWM: 13 | HAL_SetDigitalPWMRate: 14 | HAL_SetDigitalPWMDutyCycle: 15 | HAL_SetDigitalPWMPPS: 16 | HAL_SetDigitalPWMOutputChannel: 17 | HAL_SetDIO: 18 | HAL_SetDIODirection: 19 | HAL_GetDIO: 20 | HAL_GetDIODirection: 21 | HAL_Pulse: 22 | HAL_PulseMultiple: 23 | HAL_IsPulsing: 24 | HAL_IsAnyPulsing: 25 | HAL_SetFilterSelect: 26 | HAL_GetFilterSelect: 27 | HAL_SetFilterPeriod: 28 | HAL_GetFilterPeriod: 29 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/DutyCycle.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeDutyCycle: 8 | HAL_FreeDutyCycle: 9 | HAL_SetDutyCycleSimDevice: 10 | ifndef: __FRC_ROBORIO__ 11 | HAL_GetDutyCycleFrequency: 12 | HAL_GetDutyCycleOutput: 13 | HAL_GetDutyCycleHighTime: 14 | HAL_GetDutyCycleOutputScaleFactor: 15 | HAL_GetDutyCycleFPGAIndex: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Extensions.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_LoadOneExtension: 8 | ifndef: __FRC_ROBORIO__ 9 | HAL_LoadExtensions: 10 | ifndef: __FRC_ROBORIO__ 11 | HAL_RegisterExtension: 12 | ignore: true 13 | HAL_RegisterExtensionListener: 14 | ignore: true 15 | HAL_SetShowExtensionsNotFoundMessages: 16 | ifndef: __FRC_ROBORIO__ 17 | HAL_OnShutdown: 18 | ignore: true 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/FRCUsageReporting.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_Report: 8 | 9 | enums: 10 | tResourceType: 11 | tInstances: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/HandlesInternal.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | attributes: 7 | InvalidHandleIndex: 8 | enums: 9 | HAL_HandleEnum: 10 | functions: 11 | getHandleIndex: 12 | getHandleType: 13 | isHandleType: 14 | isHandleCorrectVersion: 15 | getHandleTypedIndex: 16 | getPortHandleChannel: 17 | getPortHandleModule: 18 | getPortHandleSPIEnable: 19 | createPortHandle: 20 | createPortHandleForSPI: 21 | createHandle: 22 | classes: 23 | hal::HandleBase: 24 | ignore: true 25 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/I2C.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeI2C: 8 | HAL_TransactionI2C: 9 | buffers: 10 | - { type: IN, src: dataToSend, len: sendSize } 11 | - { type: OUT, src: dataReceived, len: receiveSize } 12 | HAL_WriteI2C: 13 | buffers: 14 | - { type: IN, src: dataToSend, len: sendSize } 15 | HAL_ReadI2C: 16 | buffers: 17 | - { type: OUT, src: buffer, len: count } 18 | HAL_CloseI2C: 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/I2CTypes.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | enums: 7 | HAL_I2CPort: 8 | value_prefix: HAL_I2C 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Interrupts.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeInterrupts: 8 | HAL_CleanInterrupts: 9 | HAL_WaitForInterrupt: 10 | HAL_WaitForMultipleInterrupts: 11 | HAL_ReadInterruptRisingTimestamp: 12 | HAL_ReadInterruptFallingTimestamp: 13 | HAL_RequestInterrupts: 14 | HAL_SetInterruptUpSourceEdge: 15 | HAL_ReleaseWaitingInterrupt: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/LEDs.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | enums: 4 | HAL_RadioLEDState: 5 | functions: 6 | HAL_SetRadioLEDState: 7 | HAL_GetRadioLEDState: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Main.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_SetMain: 8 | ignore: true # TODO 9 | HAL_HasMain: 10 | HAL_RunMain: 11 | HAL_ExitMain: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Notifier.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeNotifier: 8 | HAL_SetNotifierName: 9 | HAL_StopNotifier: 10 | HAL_CleanNotifier: 11 | HAL_UpdateNotifierAlarm: 12 | HAL_CancelNotifierAlarm: 13 | HAL_WaitForNotifierAlarm: 14 | HAL_SetNotifierThreadPriority: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/PWM.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializePWMPort: 8 | HAL_FreePWMPort: 9 | HAL_CheckPWMChannel: 10 | HAL_SetPWMConfigMicroseconds: 11 | HAL_GetPWMConfigMicroseconds: 12 | HAL_SetPWMConfig: 13 | HAL_SetPWMConfigRaw: 14 | HAL_GetPWMConfigRaw: 15 | HAL_SetPWMEliminateDeadband: 16 | HAL_GetPWMEliminateDeadband: 17 | HAL_SetPWMPulseTimeMicroseconds: 18 | HAL_GetPWMPulseTimeMicroseconds: 19 | HAL_SetPWMRaw: 20 | HAL_SetPWMSpeed: 21 | HAL_SetPWMPosition: 22 | HAL_SetPWMDisabled: 23 | HAL_GetPWMRaw: 24 | HAL_GetPWMSpeed: 25 | HAL_GetPWMPosition: 26 | HAL_LatchPWMZero: 27 | HAL_SetPWMPeriodScale: 28 | HAL_SetPWMAlwaysHighMode: 29 | HAL_GetPWMLoopTiming: 30 | HAL_GetPWMCycleStartTime: 31 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Power.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_GetVinVoltage: 8 | HAL_GetVinCurrent: 9 | HAL_GetUserVoltage6V: 10 | HAL_GetUserCurrent6V: 11 | HAL_GetUserActive6V: 12 | HAL_GetUserCurrentFaults6V: 13 | HAL_SetUserRailEnabled6V: 14 | HAL_GetUserVoltage5V: 15 | HAL_GetUserCurrent5V: 16 | HAL_GetUserActive5V: 17 | HAL_GetUserCurrentFaults5V: 18 | HAL_SetUserRailEnabled5V: 19 | HAL_GetUserVoltage3V3: 20 | HAL_GetUserCurrent3V3: 21 | HAL_GetUserActive3V3: 22 | HAL_GetUserCurrentFaults3V3: 23 | HAL_SetUserRailEnabled3V3: 24 | HAL_GetBrownoutVoltage: 25 | HAL_SetBrownoutVoltage: 26 | HAL_GetCPUTemp: -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Relay.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_InitializeRelayPort: 8 | HAL_FreeRelayPort: 9 | HAL_CheckRelayChannel: 10 | HAL_SetRelay: 11 | HAL_GetRelay: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/SPITypes.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | enums: 7 | HAL_SPIPort: 8 | value_prefix: HAL_SPI 9 | HAL_SPIMode: 10 | value_prefix: HAL_SPI 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/SerialHelper.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | classes: 4 | hal::SerialHelper: 5 | methods: 6 | SerialHelper: 7 | GetVISASerialPortName: 8 | GetOSSerialPortName: 9 | GetVISASerialPortList: 10 | GetOSSerialPortList: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/Threads.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HAL_ 5 | 6 | functions: 7 | HAL_GetThreadPriority: 8 | # no way to get native handle 9 | ignore: true 10 | HAL_GetCurrentThreadPriority: 11 | HAL_SetThreadPriority: 12 | # no way to get native handle 13 | ignore: true 14 | HAL_SetCurrentThreadPriority: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/AnalogGyroData.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | functions: 7 | HALSIM_ResetAnalogGyroData: 8 | HALSIM_RegisterAnalogGyroAngleCallback: 9 | ignore: true 10 | HALSIM_CancelAnalogGyroAngleCallback: 11 | HALSIM_GetAnalogGyroAngle: 12 | HALSIM_SetAnalogGyroAngle: 13 | HALSIM_RegisterAnalogGyroRateCallback: 14 | ignore: true 15 | HALSIM_CancelAnalogGyroRateCallback: 16 | HALSIM_GetAnalogGyroRate: 17 | HALSIM_SetAnalogGyroRate: 18 | HALSIM_RegisterAnalogGyroInitializedCallback: 19 | ignore: true 20 | HALSIM_CancelAnalogGyroInitializedCallback: 21 | HALSIM_GetAnalogGyroInitialized: 22 | HALSIM_SetAnalogGyroInitialized: 23 | HALSIM_RegisterAnalogGyroAllCallbacks: 24 | ignore: true 25 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/AnalogOutData.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | functions: 7 | HALSIM_ResetAnalogOutData: 8 | HALSIM_RegisterAnalogOutVoltageCallback: 9 | ignore: true 10 | HALSIM_CancelAnalogOutVoltageCallback: 11 | HALSIM_GetAnalogOutVoltage: 12 | HALSIM_SetAnalogOutVoltage: 13 | HALSIM_RegisterAnalogOutInitializedCallback: 14 | ignore: true 15 | HALSIM_CancelAnalogOutInitializedCallback: 16 | HALSIM_GetAnalogOutInitialized: 17 | HALSIM_SetAnalogOutInitialized: 18 | HALSIM_RegisterAnalogOutAllCallbacks: 19 | ignore: true 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/CanData.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | functions: 7 | HALSIM_ResetCanData: 8 | HALSIM_RegisterCanSendMessageCallback: 9 | ignore: true 10 | HALSIM_CancelCanSendMessageCallback: 11 | HALSIM_RegisterCanReceiveMessageCallback: 12 | ignore: true 13 | HALSIM_CancelCanReceiveMessageCallback: 14 | HALSIM_RegisterCanOpenStreamCallback: 15 | ignore: true 16 | HALSIM_CancelCanOpenStreamCallback: 17 | HALSIM_RegisterCanCloseStreamCallback: 18 | ignore: true 19 | HALSIM_CancelCanCloseStreamCallback: 20 | HALSIM_RegisterCanReadStreamCallback: 21 | ignore: true 22 | HALSIM_CancelCanReadStreamCallback: 23 | HALSIM_RegisterCanGetCANStatusCallback: 24 | ignore: true 25 | HALSIM_CancelCanGetCANStatusCallback: 26 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/DigitalPWMData.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | functions: 7 | HALSIM_FindDigitalPWMForChannel: 8 | HALSIM_ResetDigitalPWMData: 9 | HALSIM_RegisterDigitalPWMInitializedCallback: 10 | ignore: true 11 | HALSIM_CancelDigitalPWMInitializedCallback: 12 | HALSIM_GetDigitalPWMInitialized: 13 | HALSIM_SetDigitalPWMInitialized: 14 | HALSIM_RegisterDigitalPWMDutyCycleCallback: 15 | ignore: true 16 | HALSIM_CancelDigitalPWMDutyCycleCallback: 17 | HALSIM_GetDigitalPWMDutyCycle: 18 | HALSIM_SetDigitalPWMDutyCycle: 19 | HALSIM_RegisterDigitalPWMPinCallback: 20 | ignore: true 21 | HALSIM_CancelDigitalPWMPinCallback: 22 | HALSIM_GetDigitalPWMPin: 23 | HALSIM_SetDigitalPWMPin: 24 | HALSIM_RegisterDigitalPWMAllCallbacks: 25 | ignore: true 26 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/I2CData.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | functions: 7 | HALSIM_ResetI2CData: 8 | HALSIM_RegisterI2CInitializedCallback: 9 | ignore: true 10 | HALSIM_CancelI2CInitializedCallback: 11 | HALSIM_GetI2CInitialized: 12 | HALSIM_SetI2CInitialized: 13 | HALSIM_RegisterI2CReadCallback: 14 | ignore: true 15 | HALSIM_CancelI2CReadCallback: 16 | HALSIM_RegisterI2CWriteCallback: 17 | ignore: true 18 | HALSIM_CancelI2CWriteCallback: 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/NotifierData.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | functions: 7 | HALSIM_GetNextNotifierTimeout: 8 | HALSIM_GetNumNotifiers: 9 | HALSIM_GetNotifierInfo: 10 | classes: 11 | HALSIM_NotifierInfo: 12 | attributes: 13 | handle: 14 | name: 15 | timeout: 16 | waitTimeValid: 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/NotifyListener.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | classes: 7 | HalCallbackListener: 8 | ignore: true # TODO 9 | attributes: 10 | callback: 11 | param: 12 | methods: 13 | HalCallbackListener: 14 | overloads: 15 | "": 16 | void*, CallbackFunction: 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/Reset.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | functions: 7 | HALSIM_ResetAllSimData: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/SPIData.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | strip_prefixes: 4 | - HALSIM_ 5 | 6 | functions: 7 | HALSIM_ResetSPIData: 8 | HALSIM_RegisterSPIInitializedCallback: 9 | ignore: true 10 | HALSIM_CancelSPIInitializedCallback: 11 | HALSIM_GetSPIInitialized: 12 | HALSIM_SetSPIInitialized: 13 | HALSIM_RegisterSPIReadCallback: 14 | ignore: true 15 | HALSIM_CancelSPIReadCallback: 16 | HALSIM_RegisterSPIWriteCallback: 17 | ignore: true 18 | HALSIM_CancelSPIWriteCallback: 19 | HALSIM_RegisterSPIReadAutoReceivedDataCallback: 20 | ignore: true 21 | HALSIM_CancelSPIReadAutoReceivedDataCallback: 22 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/SimCallbackRegistry.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | classes: 4 | SimCallbackRegistryBase: 5 | ignore: true # TODO 6 | methods: 7 | Cancel: 8 | Reset: 9 | GetMutex: 10 | DoRegister: 11 | DoReset: 12 | SimCallbackRegistry: 13 | ignore: true # TODO 14 | methods: 15 | Register: 16 | Invoke: 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/semiwrap/simulation/SimDataValue.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | classes: 4 | SimDataValueBase: 5 | ignore: true 6 | attributes: 7 | m_value: 8 | methods: 9 | SimDataValueBase: 10 | CancelCallback: 11 | Get: 12 | Reset: 13 | GetMutex: 14 | DoRegisterCallback: 15 | DoSet: 16 | SimDataValue: 17 | ignore: true 18 | methods: 19 | SimDataValue: 20 | overloads: 21 | "": 22 | T: 23 | RegisterCallback: 24 | Set: 25 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-hal/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ds-socket/.gitignore: -------------------------------------------------------------------------------- 1 | 2 | *.pyc 3 | *.egg-info 4 | 5 | *.dll 6 | *.so 7 | *.dylib 8 | 9 | .vscode 10 | 11 | /build 12 | /dist 13 | *.egg-info 14 | 15 | /halsim_ds_socket/version.py 16 | /halsim_ds_socket/lib 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ds-socket/README.md: -------------------------------------------------------------------------------- 1 | robotpy-halsim-ds-socket 2 | ================== 3 | 4 | Installing this package will allow you to utilize the 2020+ WPILib GUI 5 | DS Socket from a RobotPy program. 6 | 7 | Usage 8 | ----- 9 | 10 | First, install pyfrc. Then run your robot with the 'sim' argument and --ds-socket flag: 11 | 12 | # Windows 13 | py -3 -m robotpy sim --ds-socket 14 | 15 | # Linux/OSX 16 | python3 -m robotpy sim --ds-socket 17 | 18 | WPILib's documentation for using the simulator can be found at http://docs.wpilib.org/en/latest/docs/software/wpilib-tools/robot-simulation/ 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ds-socket/halsim_ds_socket/__init__.py: -------------------------------------------------------------------------------- 1 | from .main import loadExtension 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ds-socket/halsim_ds_socket/main.py: -------------------------------------------------------------------------------- 1 | import logging 2 | import os 3 | from os.path import abspath, dirname, join 4 | 5 | logger = logging.getLogger("halsim_ds_socket") 6 | 7 | 8 | def loadExtension(): 9 | try: 10 | import hal 11 | except ImportError as e: 12 | # really, should never happen... 13 | raise ImportError("you must install robotpy-hal!") from e 14 | 15 | from .version import version 16 | 17 | logger.info("WPILib HAL Simulation DS Socket Extension %s", version) 18 | 19 | root = join(abspath(dirname(__file__)), "lib") 20 | ext = join(root, os.listdir(root)[0]) 21 | retval = hal.loadOneExtension(ext) 22 | if retval != 0: 23 | logger.warn("loading extension may have failed (error=%d)", retval) 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ds-socket/halsim_ds_socket/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-halsim-ds-socket/halsim_ds_socket/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ds-socket/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ds-socket/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ds-socket/tests/test_halsim_ds_socket.py: -------------------------------------------------------------------------------- 1 | import ctypes 2 | import pathlib 3 | 4 | 5 | def test_halsim_ds_socket(): 6 | # dependencies 7 | import native.wpihal._init_robotpy_native_wpihal 8 | import native.wpinet._init_robotpy_native_wpinet 9 | 10 | import halsim_ds_socket as base 11 | 12 | loaded = 0 13 | for fname in (pathlib.Path(base.__file__).parent / "lib").iterdir(): 14 | if fname.is_file() and fname.suffix in (".dll", ".dylib", ".so"): 15 | ctypes.CDLL(str(fname)) 16 | loaded += 1 17 | 18 | assert loaded 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/.gitignore: -------------------------------------------------------------------------------- 1 | 2 | *.pyc 3 | *.egg-info 4 | 5 | *.dll 6 | *.so 7 | *.dylib 8 | 9 | .vscode 10 | 11 | /build 12 | /dist 13 | *.egg-info 14 | 15 | /halsim_gui/version.py 16 | /halsim_gui/lib 17 | /halsim_gui/include 18 | 19 | /halsim_gui/_ext/_init__halsim_gui_ext.py 20 | /halsim_gui/_ext/halsim_gui_ext.pc 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/README.md: -------------------------------------------------------------------------------- 1 | robotpy-halsim-gui 2 | ================== 3 | 4 | Installing this package will allow you to utilize the 2020+ WPILib GUI 5 | simulation from a RobotPy program. 6 | 7 | Usage 8 | ----- 9 | 10 | First, install pyfrc. Then run your robot with the 'sim' argument: 11 | 12 | # Windows 13 | py -3 -m robotpy sim 14 | 15 | # Linux/OSX 16 | python3 -m robotpy sim 17 | 18 | WPILib's documentation for using the simulator can be found at http://docs.wpilib.org/en/latest/docs/software/wpilib-tools/robot-simulation/simulation-gui.html 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/halsim_gui/__init__.py: -------------------------------------------------------------------------------- 1 | from .main import loadExtension 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/halsim_gui/_ext/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__halsim_gui_ext 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/halsim_gui/_ext/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | 4 | #include 5 | #include 6 | 7 | SEMIWRAP_PYBIND11_MODULE(m) { 8 | 9 | initWrapper(m); 10 | 11 | m.def("_kill_on_signal", []() { 12 | HAL_RegisterExtensionListener( 13 | nullptr, [](void *, const char *name, void *data) { 14 | if (std::string_view{name} == HALSIMGUI_EXT_ADDGUILATEEXECUTE) { 15 | auto AddGuiLateExecute = (halsimgui::AddGuiLateExecuteFn)data; 16 | AddGuiLateExecute([] { 17 | py::gil_scoped_acquire gil; 18 | if (PyErr_CheckSignals() == -1) { 19 | throw py::error_already_set(); 20 | } 21 | }); 22 | } 23 | }); 24 | }); 25 | } -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/halsim_gui/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-halsim-gui/halsim_gui/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/meson.build: -------------------------------------------------------------------------------- 1 | project('halsim-gui', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | halsim_gui_ext_sources += files( 8 | 'halsim_gui/_ext/main.cpp', 9 | ) 10 | halsim_gui_ext_deps += [ 11 | declare_dependency( 12 | include_directories: ['halsim_gui/include'] 13 | ) 14 | ] 15 | 16 | subdir('semiwrap/modules') 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-gui/tests/test_halsim_gui.py: -------------------------------------------------------------------------------- 1 | import ctypes 2 | import pathlib 3 | 4 | 5 | def test_halsim_gui(): 6 | # dependencies 7 | import wpinet 8 | import hal 9 | import wpimath 10 | import ntcore 11 | 12 | import halsim_gui as base 13 | 14 | loaded = 0 15 | for fname in (pathlib.Path(base.__file__).parent / "lib").iterdir(): 16 | if fname.is_file() and fname.suffix in (".dll", ".dylib", ".so"): 17 | ctypes.CDLL(str(fname)) 18 | loaded += 1 19 | 20 | assert loaded 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/.gitignore: -------------------------------------------------------------------------------- 1 | 2 | *.pyc 3 | *.egg-info 4 | 5 | *.dll 6 | *.so 7 | *.dylib 8 | 9 | .vscode 10 | 11 | /build 12 | /dist 13 | *.egg-info 14 | 15 | /halsim_ws/version.py 16 | /halsim_ws/server/lib 17 | /halsim_ws/client/lib 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/README.md: -------------------------------------------------------------------------------- 1 | robotpy-halsim-ws 2 | ================== 3 | 4 | Installing this package will allow you to utilize the 2020+ WPILib websim from a RobotPy program. 5 | 6 | Usage 7 | ----- 8 | 9 | First, install pyfrc. Then run your robot with the 'sim' argument and --ws-server or --ws-client flag: 10 | 11 | # Windows 12 | py -3 -m robotpy sim --ws-server 13 | py -3 -m robotpy sim --ws-client 14 | 15 | # Linux/OSX 16 | python3 -m robotpy sim --ws-server 17 | python3 -m robotpy sim --ws-client 18 | 19 | WPILib's documentation for using the simulator can be found at http://docs.wpilib.org/en/latest/docs/software/wpilib-tools/robot-simulation/ 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/halsim_ws/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-halsim-ws/halsim_ws/__init__.py -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/halsim_ws/client/__init__.py: -------------------------------------------------------------------------------- 1 | from .main import loadExtension 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/halsim_ws/client/main.py: -------------------------------------------------------------------------------- 1 | import logging 2 | import os 3 | from os.path import abspath, dirname, join 4 | 5 | logger = logging.getLogger("halsim_ws.client") 6 | 7 | 8 | def loadExtension(): 9 | try: 10 | import hal 11 | except ImportError as e: 12 | # really, should never happen... 13 | raise ImportError("you must install robotpy-hal!") from e 14 | 15 | from ..version import version 16 | 17 | logger.info("WPILib HAL Simulation websim client %s", version) 18 | 19 | root = join(abspath(dirname(__file__)), "lib") 20 | ext = join(root, os.listdir(root)[0]) 21 | retval = hal.loadOneExtension(ext) 22 | if retval != 0: 23 | logger.warn("loading extension may have failed (error=%d)", retval) 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/halsim_ws/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-halsim-ws/halsim_ws/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/halsim_ws/server/__init__.py: -------------------------------------------------------------------------------- 1 | from .main import loadExtension 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/halsim_ws/server/main.py: -------------------------------------------------------------------------------- 1 | import logging 2 | import os 3 | from os.path import abspath, dirname, join 4 | 5 | logger = logging.getLogger("halsim_ws.server") 6 | 7 | 8 | def loadExtension(): 9 | try: 10 | import hal 11 | except ImportError as e: 12 | # really, should never happen... 13 | raise ImportError("you must install robotpy-hal!") from e 14 | 15 | from ..version import version 16 | 17 | logger.info("WPILib HAL Simulation websim server %s", version) 18 | 19 | root = join(abspath(dirname(__file__)), "lib") 20 | ext = join(root, os.listdir(root)[0]) 21 | retval = hal.loadOneExtension(ext) 22 | if retval != 0: 23 | logger.warn("loading extension may have failed (error=%d)", retval) 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/tests/test_halsim_ws_client.py: -------------------------------------------------------------------------------- 1 | import ctypes 2 | import pathlib 3 | 4 | 5 | def test_halsim_ws_client(): 6 | # dependencies 7 | import native.wpihal._init_robotpy_native_wpihal 8 | import native.wpinet._init_robotpy_native_wpinet 9 | 10 | import halsim_ws.client as base 11 | 12 | loaded = 0 13 | for fname in (pathlib.Path(base.__file__).parent / "lib").iterdir(): 14 | if fname.is_file() and fname.suffix in (".dll", ".dylib", ".so"): 15 | ctypes.CDLL(str(fname)) 16 | loaded += 1 17 | 18 | assert loaded 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-halsim-ws/tests/test_halsim_ws_server.py: -------------------------------------------------------------------------------- 1 | import ctypes 2 | import pathlib 3 | 4 | 5 | def test_halsim_ws_server(): 6 | # dependencies 7 | import native.wpihal._init_robotpy_native_wpihal 8 | import native.wpinet._init_robotpy_native_wpinet 9 | 10 | import halsim_ws.server as base 11 | 12 | loaded = 0 13 | for fname in (pathlib.Path(base.__file__).parent / "lib").iterdir(): 14 | if fname.is_file() and fname.suffix in (".dll", ".dylib", ".so"): 15 | ctypes.CDLL(str(fname)) 16 | loaded += 1 17 | 18 | assert loaded 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-apriltag/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-ntcore/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-romi/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-wpihal/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-wpilib/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-wpimath/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-wpinet/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-wpiutil/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-native-xrp/.gitignore: -------------------------------------------------------------------------------- 1 | /dist 2 | /src 3 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/.gitignore: -------------------------------------------------------------------------------- 1 | *.py[cod] 2 | *.so 3 | *.dll 4 | *.egg-info 5 | 6 | /build 7 | 8 | /romi/trampolines 9 | /romi/_init__romi.py 10 | /romi/romi.pc 11 | /romi/version.py -------------------------------------------------------------------------------- /subprojects/robotpy-romi/README.md: -------------------------------------------------------------------------------- 1 | robotpy-romi 2 | ============ 3 | 4 | RobotPy support for the WPILib ROMI vendor library. 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/meson.build: -------------------------------------------------------------------------------- 1 | project('robotpy-romi', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | romi_sources += files( 8 | 'romi/src/main.cpp', 9 | ) 10 | 11 | subdir('semiwrap/modules') 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/romi/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__romi 2 | 3 | # autogenerated by 'semiwrap create-imports romi romi._romi' 4 | from ._romi import OnBoardIO, RomiGyro, RomiMotor 5 | 6 | __all__ = ["OnBoardIO", "RomiGyro", "RomiMotor"] 7 | 8 | del _init__romi 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/romi/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-romi/romi/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-romi/romi/src/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) { 5 | initWrapper(m); 6 | } -------------------------------------------------------------------------------- /subprojects/robotpy-romi/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/semiwrap/OnBoardIO.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::OnBoardIO: 4 | attributes: 5 | kMessageInterval: 6 | m_nextMessageTime: 7 | enums: 8 | ChannelMode: 9 | methods: 10 | OnBoardIO: 11 | GetButtonAPressed: 12 | GetButtonBPressed: 13 | GetButtonCPressed: 14 | SetGreenLed: 15 | SetRedLed: 16 | SetYellowLed: 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/semiwrap/RomiGyro.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::RomiGyro: 4 | methods: 5 | RomiGyro: 6 | GetAngle: 7 | GetRate: 8 | Calibrate: 9 | GetRateX: 10 | GetRateY: 11 | GetRateZ: 12 | GetAngleX: 13 | GetAngleY: 14 | GetAngleZ: 15 | Reset: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/semiwrap/RomiMotor.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::RomiMotor: 4 | methods: 5 | RomiMotor: 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-romi/tests/test_romi.py: -------------------------------------------------------------------------------- 1 | import romi 2 | 3 | 4 | def test_romi(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/README.rst: -------------------------------------------------------------------------------- 1 | RobotPy WPILib 2 | ============== 3 | 4 | Python version of WPILib - the standard library used for programming FRC 5 | robots. 6 | 7 | Installation 8 | ============ 9 | 10 | Typically, you don't install this directly, but use the RobotPy installer 11 | to install it on your roboRIO, or it is installed by pip as part of the 12 | pyfrc setup process. 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/ADXL345_I2C.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - networktables/NTSendableBuilder.h 3 | 4 | classes: 5 | frc::ADXL345_I2C: 6 | constants: 7 | - frc::ADXL345_I2C::Range::kRange_2G 8 | ignored_bases: 9 | - wpi::SendableHelper 10 | enums: 11 | Axes: 12 | Range: 13 | attributes: 14 | kAddress: 15 | methods: 16 | ADXL345_I2C: 17 | GetI2CPort: 18 | GetI2CDeviceAddress: 19 | SetRange: 20 | GetX: 21 | GetY: 22 | GetZ: 23 | GetAcceleration: 24 | GetAccelerations: 25 | InitSendable: 26 | frc::ADXL345_I2C::AllAxes: 27 | attributes: 28 | XAxis: 29 | YAxis: 30 | ZAxis: 31 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/ADXL362.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - networktables/NTSendableBuilder.h 3 | - frc/DigitalSource.h 4 | 5 | classes: 6 | frc::ADXL362: 7 | constants: 8 | - frc::ADXL362::Range::kRange_2G 9 | ignored_bases: 10 | - wpi::SendableHelper 11 | enums: 12 | Axes: 13 | Range: 14 | methods: 15 | ADXL362: 16 | overloads: 17 | Range: 18 | SPI::Port, Range: 19 | GetSpiPort: 20 | SetRange: 21 | GetX: 22 | GetY: 23 | GetZ: 24 | GetAcceleration: 25 | GetAccelerations: 26 | InitSendable: 27 | frc::ADXL362::AllAxes: 28 | attributes: 29 | XAxis: 30 | YAxis: 31 | ZAxis: 32 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/ADXRS450_Gyro.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | - frc/DigitalSource.h 4 | 5 | classes: 6 | frc::ADXRS450_Gyro: 7 | ignored_bases: 8 | - wpi::SendableHelper 9 | methods: 10 | ADXRS450_Gyro: 11 | overloads: 12 | '': 13 | SPI::Port: 14 | IsConnected: 15 | GetAngle: 16 | GetRate: 17 | Reset: 18 | Calibrate: 19 | GetRotation2d: 20 | GetPort: 21 | InitSendable: 22 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/AnalogAccelerometer.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::AnalogAccelerometer: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | methods: 9 | AnalogAccelerometer: 10 | overloads: 11 | int: 12 | AnalogInput*: 13 | ignore: true 14 | std::shared_ptr: 15 | GetAcceleration: 16 | SetSensitivity: 17 | SetZero: 18 | PIDGet: 19 | rename: pidGet 20 | InitSendable: 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/AnalogOutput.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::AnalogOutput: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | attributes: 9 | m_channel: 10 | m_port: 11 | ignore: true 12 | methods: 13 | AnalogOutput: 14 | SetVoltage: 15 | GetVoltage: 16 | GetChannel: 17 | InitSendable: 18 | 19 | inline_code: | 20 | cls_AnalogOutput 21 | .def("__repr__", [](const AnalogOutput &self) { 22 | return py::str("").format(self.GetChannel()); 23 | }); 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/AnalogPotentiometer.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::AnalogPotentiometer: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | methods: 9 | AnalogPotentiometer: 10 | overloads: 11 | int, double, double: 12 | AnalogInput*, double, double: 13 | ignore: true 14 | std::shared_ptr, double, double: 15 | Get: 16 | PIDGet: 17 | rename: pidGet 18 | InitSendable: 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/AnalogTriggerOutput.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | - frc/AnalogInput.h 4 | - frc/DutyCycle.h 5 | - frc/AnalogTrigger.h 6 | 7 | classes: 8 | frc::AnalogTriggerOutput: 9 | ignored_bases: 10 | - wpi::SendableHelper 11 | methods: 12 | Get: 13 | GetPortHandleForRouting: 14 | GetAnalogTriggerTypeForRouting: 15 | IsAnalogTrigger: 16 | GetChannel: 17 | InitSendable: 18 | AnalogTriggerOutput: 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/AnalogTriggerType.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | AnalogTriggerType: 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/BuiltInAccelerometer.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpi/sendable/SendableBuilder.h 4 | 5 | classes: 6 | frc::BuiltInAccelerometer: 7 | ignored_bases: 8 | - wpi::SendableHelper 9 | constants: 10 | - frc::BuiltInAccelerometer::Range::kRange_8G 11 | enums: 12 | Range: 13 | methods: 14 | BuiltInAccelerometer: 15 | SetRange: 16 | GetX: 17 | GetY: 18 | GetZ: 19 | InitSendable: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Compressor.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpi/sendable/SendableBuilder.h 4 | - frc/Compressor.h 5 | - frc/Solenoid.h 6 | - frc/DoubleSolenoid.h 7 | 8 | classes: 9 | frc::Compressor: 10 | ignored_bases: 11 | - wpi::SendableHelper 12 | methods: 13 | Compressor: 14 | overloads: 15 | int, PneumaticsModuleType: 16 | PneumaticsModuleType: 17 | Start: 18 | Stop: 19 | Enabled: 20 | IsEnabled: 21 | GetPressureSwitchValue: 22 | GetCurrent: 23 | GetAnalogVoltage: 24 | GetPressure: 25 | Disable: 26 | EnableDigital: 27 | EnableAnalog: 28 | EnableHybrid: 29 | GetConfigType: 30 | InitSendable: 31 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/CompressorConfigType.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | CompressorConfigType: 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Controller.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::Controller: 4 | methods: 5 | Controller: 6 | Enable: 7 | Disable: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DMA.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/AnalogInput.h 3 | - frc/Counter.h 4 | - frc/DigitalSource.h 5 | - frc/DMASample.h 6 | - frc/DutyCycle.h 7 | - frc/Encoder.h 8 | 9 | classes: 10 | frc::DMA: 11 | methods: 12 | DMA: 13 | SetPause: 14 | SetRate: 15 | AddEncoder: 16 | AddEncoderPeriod: 17 | AddCounter: 18 | AddCounterPeriod: 19 | AddDigitalSource: 20 | AddDutyCycle: 21 | AddAnalogInput: 22 | AddAveragedAnalogInput: 23 | AddAnalogAccumulator: 24 | SetExternalTrigger: 25 | StartDMA: 26 | StopDMA: 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DMASample.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::DMASample: 3 | methods: 4 | Update: 5 | GetTime: 6 | GetTimeStamp: 7 | GetEncoderRaw: 8 | GetEncoderDistance: 9 | GetEncoderPeriodRaw: 10 | GetCounter: 11 | GetCounterPeriod: 12 | GetDigitalSource: 13 | GetAnalogInputRaw: 14 | GetAnalogInputVoltage: 15 | GetAveragedAnalogInputRaw: 16 | GetAveragedAnalogInputVoltage: 17 | GetAnalogAccumulator: 18 | GetDutyCycleOutputRaw: 19 | GetDutyCycleOutput: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DMC60.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::DMC60: 6 | methods: 7 | DMC60: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DSControlWord.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::DSControlWord: 4 | methods: 5 | DSControlWord: 6 | IsEnabled: 7 | no_release_gil: true 8 | IsDisabled: 9 | no_release_gil: true 10 | IsEStopped: 11 | no_release_gil: true 12 | IsAutonomous: 13 | no_release_gil: true 14 | IsAutonomousEnabled: 15 | no_release_gil: true 16 | IsTeleop: 17 | no_release_gil: true 18 | IsTeleopEnabled: 19 | no_release_gil: true 20 | IsTest: 21 | no_release_gil: true 22 | IsDSAttached: 23 | no_release_gil: true 24 | IsFMSAttached: 25 | no_release_gil: true 26 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DataLogManager.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpi/DataLog.h 4 | 5 | classes: 6 | frc::DataLogManager: 7 | methods: 8 | Start: 9 | Stop: 10 | Log: 11 | GetLog: 12 | return_value_policy: reference 13 | GetLogDir: 14 | LogNetworkTables: 15 | LogConsoleOutput: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DifferentialDriveVoltageConstraint.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::DifferentialDriveVoltageConstraint: 3 | methods: 4 | DifferentialDriveVoltageConstraint: 5 | MaxVelocity: 6 | MinMaxAcceleration: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DigitalGlitchFilter.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | - frc/Counter.h 4 | - frc/Encoder.h 5 | 6 | classes: 7 | frc::DigitalGlitchFilter: 8 | ignored_bases: 9 | - wpi::SendableHelper 10 | methods: 11 | DigitalGlitchFilter: 12 | Add: 13 | overloads: 14 | DigitalSource*: 15 | Encoder*: 16 | Counter*: 17 | Remove: 18 | overloads: 19 | DigitalSource*: 20 | Encoder*: 21 | Counter*: 22 | SetPeriodCycles: 23 | SetPeriodNanoSeconds: 24 | GetPeriodCycles: 25 | GetPeriodNanoSeconds: 26 | InitSendable: 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DigitalInput.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | - frc/DigitalGlitchFilter.h 4 | 5 | classes: 6 | frc::DigitalInput: 7 | ignored_bases: 8 | - wpi::SendableHelper 9 | methods: 10 | DigitalInput: 11 | Get: 12 | GetPortHandleForRouting: 13 | GetAnalogTriggerTypeForRouting: 14 | IsAnalogTrigger: 15 | GetChannel: 16 | SetSimDevice: 17 | InitSendable: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DigitalOutput.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::DigitalOutput: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | methods: 9 | DigitalOutput: 10 | Set: 11 | Get: 12 | GetPortHandleForRouting: 13 | GetAnalogTriggerTypeForRouting: 14 | IsAnalogTrigger: 15 | GetChannel: 16 | Pulse: 17 | IsPulsing: 18 | SetPWMRate: 19 | EnablePPS: 20 | EnablePWM: 21 | DisablePWM: 22 | UpdateDutyCycle: 23 | SetSimDevice: 24 | InitSendable: 25 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DigitalSource.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::DigitalSource: 3 | methods: 4 | DigitalSource: 5 | GetPortHandleForRouting: 6 | GetAnalogTriggerTypeForRouting: 7 | IsAnalogTrigger: 8 | GetChannel: 9 | 10 | inline_code: | 11 | cls_DigitalSource 12 | .def("__repr__", [](py::handle self) { 13 | py::object type_name = self.get_type().attr("__qualname__"); 14 | int channel = self.cast().GetChannel(); 15 | return py::str("<{} {}>").format(type_name, channel); 16 | }); 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DoubleSolenoid.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::DoubleSolenoid: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | enums: 9 | Value: 10 | methods: 11 | DoubleSolenoid: 12 | overloads: 13 | int, PneumaticsModuleType, int, int: 14 | PneumaticsModuleType, int, int: 15 | Set: 16 | Get: 17 | Toggle: 18 | GetFwdChannel: 19 | GetRevChannel: 20 | IsFwdSolenoidDisabled: 21 | IsRevSolenoidDisabled: 22 | InitSendable: 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/DriverStationModeThread.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::internal::DriverStationModeThread: 4 | rename: _DriverStationModeThread 5 | methods: 6 | DriverStationModeThread: 7 | InAutonomous: 8 | InDisabled: 9 | InTeleop: 10 | InTest: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Errors.yml: -------------------------------------------------------------------------------- 1 | 2 | functions: 3 | GetErrorMessage: 4 | ReportErrorV: 5 | ignore: true 6 | ReportError: 7 | ignore: true 8 | MakeErrorV: 9 | ignore: true 10 | MakeError: 11 | ignore: true 12 | classes: 13 | frc::RuntimeError: 14 | ignore: true 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Field2d.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - networktables/NTSendableBuilder.h 3 | 4 | classes: 5 | frc::Field2d: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | methods: 9 | Field2d: 10 | SetRobotPose: 11 | overloads: 12 | const Pose2d&: 13 | units::meter_t, units::meter_t, Rotation2d: 14 | GetRobotPose: 15 | GetObject: 16 | return_value_policy: reference_internal 17 | GetRobotObject: 18 | return_value_policy: reference_internal 19 | InitSendable: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/FieldObject2d.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/trajectory/Trajectory.h 3 | 4 | classes: 5 | frc::FieldObject2d: 6 | nodelete: true 7 | methods: 8 | FieldObject2d: 9 | ignore: true 10 | SetPose: 11 | overloads: 12 | const Pose2d&: 13 | units::meter_t, units::meter_t, Rotation2d: 14 | GetPose: 15 | SetPoses: 16 | overloads: 17 | std::span: 18 | std::initializer_list: 19 | ignore: true 20 | SetTrajectory: 21 | GetPoses: 22 | overloads: 23 | '[const]': 24 | wpi::SmallVectorImpl& [const]: 25 | ignore: true 26 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Filesystem.yml: -------------------------------------------------------------------------------- 1 | 2 | functions: 3 | GetOperatingDirectory: 4 | GetDeployDirectory: 5 | GetOperatingDirectoryFs: 6 | ignore: true 7 | GetDeployDirectoryFs: 8 | ignore: true 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Filter.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::Filter: 3 | methods: 4 | Filter: 5 | overloads: 6 | PIDSource&: 7 | std::shared_ptr: 8 | SetPIDSourceType: 9 | GetPIDSourceType: 10 | PIDGet: 11 | rename: pidGet 12 | Get: 13 | Reset: 14 | PIDGetSource: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/I2C.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::I2C: 3 | enums: 4 | Port: 5 | methods: 6 | I2C: 7 | GetPort: 8 | GetDeviceAddress: 9 | Transaction: 10 | buffers: 11 | - {type: IN, src: dataToSend, len: sendSize} 12 | - {type: OUT, src: dataReceived, len: receiveSize} 13 | AddressOnly: 14 | Write: 15 | WriteBulk: 16 | buffers: 17 | - {type: IN, src: data, len: count} 18 | Read: 19 | buffers: 20 | - {type: OUT, src: data, len: count} 21 | ReadOnly: 22 | buffers: 23 | - {type: OUT, src: buffer, len: count} 24 | VerifySensor: 25 | buffers: 26 | - {type: IN, src: expected, len: count} 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/IterativeRobot.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::IterativeRobot: 3 | methods: 4 | IterativeRobot: 5 | StartCompetition: 6 | EndCompetition: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Jaguar.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::Jaguar: 6 | methods: 7 | Jaguar: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/ListenerExecutor.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::ListenerExecutor: 3 | methods: 4 | Execute: 5 | RunListenerTasks: 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/LiveWindow.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpi/sendable/Sendable.h 4 | - pybind11/functional.h 5 | 6 | classes: 7 | frc::LiveWindow: 8 | methods: 9 | GetInstance: 10 | ignore: true 11 | SetEnabledCallback: 12 | SetDisabledCallback: 13 | EnableTelemetry: 14 | keepalive: 15 | - [1, 2] 16 | DisableTelemetry: 17 | keepalive: 18 | - [1, 2] 19 | DisableAllTelemetry: 20 | EnableAllTelemetry: 21 | IsEnabled: 22 | SetEnabled: 23 | UpdateValues: 24 | 25 | inline_code: | 26 | static int unused; 27 | py::capsule cleanup(&unused, [](void *) { 28 | frc::LiveWindow::SetEnabledCallback(nullptr); 29 | frc::LiveWindow::SetDisabledCallback(nullptr); 30 | }); 31 | m.add_object("_lw_cleanup", cleanup); 32 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Mechanism2d.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpi/sendable/SendableBuilder.h 4 | 5 | classes: 6 | frc::Mechanism2d: 7 | ignored_bases: 8 | - wpi::SendableHelper 9 | methods: 10 | Mechanism2d: 11 | GetRoot: 12 | return_value_policy: reference_internal 13 | SetBackgroundColor: 14 | InitSendable: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/MechanismLigament2d.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::MechanismLigament2d: 4 | methods: 5 | MechanismLigament2d: 6 | ignore: true 7 | SetColor: 8 | GetColor: 9 | SetLength: 10 | GetLength: 11 | SetAngle: 12 | GetAngle: 13 | SetLineWeight: 14 | GetLineWeight: 15 | UpdateEntries: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/MotorSafety.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/SmallString.h 3 | 4 | classes: 5 | frc::MotorSafety: 6 | methods: 7 | MotorSafety: 8 | Feed: 9 | SetExpiration: 10 | GetExpiration: 11 | IsAlive: 12 | SetSafetyEnabled: 13 | IsSafetyEnabled: 14 | Check: 15 | CheckMotors: 16 | StopMotor: 17 | GetDescription: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/NidecBrushless.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | - wpi/SmallString.h 4 | 5 | classes: 6 | frc::NidecBrushless: 7 | ignored_bases: 8 | - wpi::SendableHelper 9 | methods: 10 | NidecBrushless: 11 | Set: 12 | Get: 13 | SetInverted: 14 | GetInverted: 15 | Disable: 16 | Enable: 17 | PIDWrite: 18 | rename: pidWrite 19 | StopMotor: 20 | GetDescription: 21 | GetChannel: 22 | InitSendable: 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Notifier.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::PyNotifier: 3 | rename: Notifier 4 | methods: 5 | PyNotifier: 6 | overloads: 7 | std::function: 8 | SetName: 9 | SetCallback: 10 | StartSingle: 11 | overloads: 12 | double: 13 | ignore: true 14 | units::second_t: 15 | StartPeriodic: 16 | overloads: 17 | double: 18 | ignore: true 19 | units::second_t: 20 | Stop: 21 | SetHALThreadPriority: 22 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PWMMotorController.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpi/sendable/SendableBuilder.h 4 | - frc/DMA.h 5 | 6 | classes: 7 | frc::PWMMotorController: 8 | ignored_bases: 9 | - wpi::SendableHelper 10 | attributes: 11 | m_pwm: 12 | methods: 13 | Set: 14 | SetVoltage: 15 | Get: 16 | GetVoltage: 17 | SetInverted: 18 | GetInverted: 19 | Disable: 20 | StopMotor: 21 | GetDescription: 22 | GetChannel: 23 | EnableDeadbandElimination: 24 | AddFollower: 25 | overloads: 26 | PWMMotorController&: 27 | keepalive: 28 | - [1, 2] 29 | T&&: 30 | ignore: true 31 | PWMMotorController: 32 | InitSendable: 33 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PWMSparkFlex.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::PWMSparkFlex: 4 | methods: 5 | PWMSparkFlex: 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PWMSparkMax.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::PWMSparkMax: 6 | methods: 7 | PWMSparkMax: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PWMSpeedController.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::PWMSpeedController: 6 | methods: 7 | Set: 8 | Get: 9 | SetInverted: 10 | GetInverted: 11 | Disable: 12 | StopMotor: 13 | PIDWrite: 14 | rename: pidWrite 15 | PWMSpeedController: 16 | InitSendable: 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PWMTalonFX.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::PWMTalonFX: 6 | methods: 7 | PWMTalonFX: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PWMTalonSRX.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::PWMTalonSRX: 6 | methods: 7 | PWMTalonSRX: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PWMVenom.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::PWMVenom: 6 | methods: 7 | PWMVenom: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PWMVictorSPX.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::PWMVictorSPX: 6 | methods: 7 | PWMVictorSPX: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/PneumaticsModuleType.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | PneumaticsModuleType: 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Potentiometer.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::Potentiometer: 3 | methods: 4 | Potentiometer: 5 | Get: 6 | SetPIDSourceType: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Preferences.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::Preferences: 4 | methods: 5 | GetInstance: 6 | ignore: true 7 | GetKeys: 8 | GetString: 9 | GetInt: 10 | GetDouble: 11 | GetFloat: 12 | GetBoolean: 13 | GetLong: 14 | SetString: 15 | PutString: 16 | InitString: 17 | SetInt: 18 | PutInt: 19 | InitInt: 20 | SetDouble: 21 | PutDouble: 22 | InitDouble: 23 | SetFloat: 24 | PutFloat: 25 | InitFloat: 26 | SetBoolean: 27 | PutBoolean: 28 | InitBoolean: 29 | SetLong: 30 | PutLong: 31 | InitLong: 32 | ContainsKey: 33 | Remove: 34 | RemoveAll: 35 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Relay.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | - wpi/SmallString.h 4 | 5 | classes: 6 | frc::Relay: 7 | ignored_bases: 8 | - wpi::SendableHelper 9 | enums: 10 | Value: 11 | Direction: 12 | methods: 13 | Relay: 14 | param_override: 15 | direction: 16 | default: frc::Relay::Direction::kBothDirections 17 | Set: 18 | Get: 19 | GetChannel: 20 | StopMotor: 21 | GetDescription: 22 | InitSendable: 23 | 24 | inline_code: | 25 | cls_Relay 26 | .def("__repr__", [](const Relay &self) { 27 | return py::str("").format(self.GetChannel()); 28 | }); 29 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Resource.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::Resource: 3 | methods: 4 | CreateResourceObject: 5 | Resource: 6 | Allocate: 7 | overloads: 8 | std::string&: 9 | uint32_t, std::string&: 10 | Free: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/RobotState.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::RobotState: 3 | nodelete: true 4 | methods: 5 | RobotState: 6 | ignore: true 7 | IsDisabled: 8 | IsEnabled: 9 | IsEStopped: 10 | IsOperatorControl: 11 | IsTeleop: 12 | IsAutonomous: 13 | IsTest: 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/RuntimeType.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | RuntimeType: 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/SD540.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::SD540: 6 | methods: 7 | SD540: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/SendableCameraWrapper.yml: -------------------------------------------------------------------------------- 1 | attributes: 2 | kProtocol: 3 | functions: 4 | GetSendableCameraWrapper: 5 | AddToSendableRegistry: 6 | classes: 7 | frc::SendableCameraWrapper: 8 | methods: 9 | SendableCameraWrapper: 10 | Wrap: 11 | overloads: 12 | cs::VideoSource&: 13 | CS_Source: 14 | InitSendable: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/SendableChooserBase.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::SendableChooserBase: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | attributes: 9 | kDefault: 10 | kOptions: 11 | kSelected: 12 | kActive: 13 | kInstance: 14 | m_defaultChoice: 15 | m_selected: 16 | m_haveSelected: 17 | m_instancePubs: 18 | m_activePubs: 19 | m_activeEntries: 20 | m_mutex: 21 | ignore: true 22 | m_instance: 23 | m_previousVal: 24 | s_instances: 25 | ignore: true 26 | methods: 27 | SendableChooserBase: 28 | ignore: true 29 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Servo.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::Servo: 6 | methods: 7 | Servo: 8 | Set: 9 | SetOffline: 10 | Get: 11 | SetAngle: 12 | GetAngle: 13 | GetMaxAngle: 14 | GetMinAngle: 15 | InitSendable: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/SharpIR.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpi/sendable/SendableBuilder.h 4 | 5 | classes: 6 | frc::SharpIR: 7 | ignored_bases: 8 | - wpi::SendableHelper 9 | methods: 10 | GP2Y0A02YK0F: 11 | GP2Y0A21YK0F: 12 | GP2Y0A41SK0F: 13 | GP2Y0A51SK0F: 14 | SharpIR: 15 | GetChannel: 16 | GetRange: 17 | InitSendable: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/SimpleWidget.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/shuffleboard/ShuffleboardContainer.h 3 | 4 | classes: 5 | frc::SimpleWidget: 6 | methods: 7 | SimpleWidget: 8 | GetEntry: 9 | overloads: 10 | '': 11 | std::string_view: 12 | BuildInto: 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/SlewRateLimiter.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::SlewRateLimiter: 3 | template_params: 4 | - Unit 5 | typealias: 6 | - Unit_t = units::unit_t 7 | - Rate = units::compound_unit> 8 | methods: 9 | SlewRateLimiter: 10 | Calculate: 11 | Reset: 12 | 13 | templates: 14 | SlewRateLimiter: 15 | qualname: frc::SlewRateLimiter 16 | params: 17 | - units::dimensionless::scalar 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Solenoid.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::Solenoid: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | methods: 9 | Solenoid: 10 | overloads: 11 | int, PneumaticsModuleType, int: 12 | PneumaticsModuleType, int: 13 | Set: 14 | Get: 15 | Toggle: 16 | GetChannel: 17 | IsDisabled: 18 | SetPulseDuration: 19 | StartPulse: 20 | InitSendable: 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Spark.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::Spark: 6 | methods: 7 | Spark: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/SynchronousInterrupt.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/DigitalSource.h 4 | 5 | classes: 6 | frc::SynchronousInterrupt: 7 | enums: 8 | WaitResult: 9 | methods: 10 | SynchronousInterrupt: 11 | overloads: 12 | DigitalSource&: 13 | DigitalSource*: 14 | std::shared_ptr: 15 | WaitForInterrupt: 16 | SetInterruptEdges: 17 | GetRisingTimestamp: 18 | GetFallingTimestamp: 19 | WakeupWaitingInterrupt: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Talon.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::Talon: 6 | methods: 7 | Talon: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Threads.yml: -------------------------------------------------------------------------------- 1 | 2 | functions: 3 | GetThreadPriority: 4 | ignore: true 5 | GetCurrentThreadPriority: 6 | SetThreadPriority: 7 | ignore: true 8 | SetCurrentThreadPriority: 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/TimedRobot.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::TimedRobot: 3 | attributes: 4 | kDefaultPeriod: 5 | methods: 6 | StartCompetition: 7 | EndCompetition: 8 | GetLoopStartTime: 9 | AddPeriodic: 10 | param_override: 11 | offset: 12 | default: 0_s 13 | TimedRobot: 14 | overloads: 15 | double: 16 | ignore: true 17 | units::second_t: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Timer.yml: -------------------------------------------------------------------------------- 1 | functions: 2 | Wait: 3 | GetTime: 4 | classes: 5 | frc::Timer: 6 | attributes: 7 | kRolloverTime: 8 | methods: 9 | Timer: 10 | Get: 11 | Reset: 12 | Start: 13 | Restart: 14 | Stop: 15 | HasPeriodPassed: 16 | GetFPGATimestamp: 17 | GetMatchTime: 18 | HasElapsed: 19 | AdvanceIfElapsed: 20 | IsRunning: 21 | GetTimestamp: 22 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/TimesliceRobot.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::TimesliceRobot: 4 | methods: 5 | TimesliceRobot: 6 | Schedule: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Utility.yml: -------------------------------------------------------------------------------- 1 | 2 | functions: 3 | wpi_assert_impl: 4 | wpi_assertEqual_impl: 5 | wpi_assertNotEqual_impl: 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Victor.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::Victor: 6 | methods: 7 | Victor: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/VictorSP.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - wpi/sendable/SendableBuilder.h 3 | 4 | classes: 5 | frc::VictorSP: 6 | methods: 7 | VictorSP: 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/WPILibVersion.yml: -------------------------------------------------------------------------------- 1 | 2 | functions: 3 | GetWPILibVersion: 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/Watchdog.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::Watchdog: 3 | methods: 4 | Watchdog: 5 | overloads: 6 | double, std::function: 7 | ignore: true 8 | units::second_t, std::function: 9 | double, Callable&&, Arg&&, Args&&...: 10 | ignore: true 11 | units::second_t, Callable&&, Arg&&, Args&&...: 12 | ignore: true 13 | GetTime: 14 | SetTimeout: 15 | overloads: 16 | double: 17 | ignore: true 18 | units::second_t: 19 | GetTimeout: 20 | IsExpired: 21 | AddEpoch: 22 | PrintEpochs: 23 | Reset: 24 | Enable: 25 | Disable: 26 | SuppressTimeoutMessage: 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/counter/EdgeConfiguration.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | EdgeConfiguration: 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/counter/ExternalDirectionCounter.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/DigitalSource.h 3 | 4 | classes: 5 | frc::ExternalDirectionCounter: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | methods: 9 | ExternalDirectionCounter: 10 | overloads: 11 | DigitalSource&, DigitalSource&: 12 | std::shared_ptr, std::shared_ptr: 13 | GetCount: 14 | SetReverseDirection: 15 | Reset: 16 | SetEdgeConfiguration: 17 | InitSendable: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/counter/Tachometer.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/DigitalSource.h 3 | 4 | classes: 5 | frc::Tachometer: 6 | ignored_bases: 7 | - wpi::SendableHelper 8 | methods: 9 | Tachometer: 10 | overloads: 11 | DigitalSource&: 12 | std::shared_ptr: 13 | GetFrequency: 14 | GetPeriod: 15 | GetEdgesPerRevolution: 16 | SetEdgesPerRevolution: 17 | GetRevolutionsPerSecond: 18 | GetRevolutionsPerMinute: 19 | GetStopped: 20 | GetSamplesToAverage: 21 | SetSamplesToAverage: 22 | SetMaxPeriod: 23 | SetUpdateWhenEmpty: 24 | InitSendable: 25 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/counter/UpDownCounter.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/DigitalSource.h 4 | 5 | classes: 6 | frc::UpDownCounter: 7 | ignored_bases: 8 | - wpi::SendableHelper 9 | methods: 10 | UpDownCounter: 11 | overloads: 12 | DigitalSource&, DigitalSource&: 13 | std::shared_ptr, std::shared_ptr: 14 | GetCount: 15 | SetReverseDirection: 16 | Reset: 17 | SetUpEdgeConfiguration: 18 | SetDownEdgeConfiguration: 19 | InitSendable: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/drive/RobotDriveBase.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/motorcontrol/MotorController.h 3 | - wpi/SmallString.h 4 | 5 | classes: 6 | frc::RobotDriveBase: 7 | attributes: 8 | m_deadband: 9 | m_maxOutput: 10 | kDefaultDeadband: 11 | kDefaultMaxOutput: 12 | enums: 13 | MotorType: 14 | methods: 15 | RobotDriveBase: 16 | SetDeadband: 17 | SetMaxOutput: 18 | FeedWatchdog: 19 | StopMotor: 20 | GetDescription: 21 | ApplyDeadband: 22 | Desaturate: 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/event/BooleanEvent.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::BooleanEvent: 4 | methods: 5 | BooleanEvent: 6 | GetAsBoolean: 7 | IfHigh: 8 | cpp_code: | 9 | [](BooleanEvent *self, std::function action) { 10 | self->IfHigh(std::move(action)); 11 | } 12 | CastTo: 13 | cpp_code: | # TODO: how to annotate this correctly? 14 | [](BooleanEvent *self, py::function constructor) -> py::object { 15 | return constructor(self, (std::function)*self); 16 | } 17 | param_override: 18 | ctor: 19 | no_default: true 20 | Rising: 21 | Falling: 22 | Debounce: 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/event/EventLoop.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::EventLoop: 4 | force_type_casters: 5 | - std::function 6 | methods: 7 | EventLoop: 8 | Bind: 9 | cpp_code: | 10 | [](EventLoop *self, std::function action) { 11 | self->Bind(std::move(action)); 12 | } 13 | Poll: 14 | Clear: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/interfaces/CounterBase.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::CounterBase: 3 | enums: 4 | EncodingType: 5 | methods: 6 | CounterBase: 7 | Get: 8 | Reset: 9 | GetPeriod: 10 | SetMaxPeriod: 11 | GetStopped: 12 | GetDirection: 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/interfaces/MotorController.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::MotorController: 4 | methods: 5 | Set: 6 | SetVoltage: 7 | Get: 8 | SetInverted: 9 | GetInverted: 10 | Disable: 11 | StopMotor: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/BuiltInLayouts.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | BuiltInLayouts: 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/BuiltInWidgets.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | BuiltInWidgets: 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/ComplexWidget.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpi/sendable/Sendable.h 4 | - wpi/sendable/SendableBuilder.h 5 | - frc/shuffleboard/ShuffleboardContainer.h 6 | 7 | classes: 8 | frc::ComplexWidget: 9 | # virtual base issue: robotpy-build/166 10 | force_no_trampoline: true 11 | methods: 12 | ComplexWidget: 13 | EnableIfActuator: 14 | DisableIfActuator: 15 | BuildInto: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/LayoutType.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::LayoutType: 4 | methods: 5 | LayoutType: 6 | GetLayoutName: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/RecordingController.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::RecordingController: 4 | methods: 5 | RecordingController: 6 | StartRecording: 7 | StopRecording: 8 | SetRecordingFileNameFormat: 9 | ClearRecordingFileNameFormat: 10 | AddEventMarker: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/Shuffleboard.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/shuffleboard/ShuffleboardTab.h 4 | 5 | classes: 6 | frc::Shuffleboard: 7 | attributes: 8 | kBaseTableName: 9 | methods: 10 | Update: 11 | GetTab: 12 | return_value_policy: reference_internal 13 | SelectTab: 14 | overloads: 15 | int: 16 | std::string_view: 17 | EnableActuatorWidgets: 18 | DisableActuatorWidgets: 19 | StartRecording: 20 | StopRecording: 21 | SetRecordingFileNameFormat: 22 | ClearRecordingFileNameFormat: 23 | AddEventMarker: 24 | overloads: 25 | std::string_view, std::string_view, ShuffleboardEventImportance: 26 | std::string_view, ShuffleboardEventImportance: 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/ShuffleboardComponentBase.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/shuffleboard/ShuffleboardContainer.h 4 | 5 | 6 | classes: 7 | frc::ShuffleboardComponentBase: 8 | # virtual base issue: robotpy-build/166 9 | force_no_trampoline: true 10 | attributes: 11 | m_properties: 12 | m_metadataDirty: 13 | m_column: 14 | m_row: 15 | m_width: 16 | m_height: 17 | methods: 18 | ShuffleboardComponentBase: 19 | ignore: true # cannot construct without trampoline 20 | SetType: 21 | BuildMetadata: 22 | GetParent: 23 | return_value_policy: reference_internal 24 | GetType: 25 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/ShuffleboardEventImportance.yml: -------------------------------------------------------------------------------- 1 | 2 | enums: 3 | ShuffleboardEventImportance: 4 | functions: 5 | ShuffleboardEventImportanceName: 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/ShuffleboardInstance.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - networktables/NetworkTableInstance.h 4 | 5 | classes: 6 | frc::detail::ShuffleboardInstance: 7 | rename: _ShuffleboardInstance 8 | base_qualnames: 9 | ShuffleboardRoot: frc::ShuffleboardRoot 10 | methods: 11 | ShuffleboardInstance: 12 | GetTab: 13 | return_value_policy: reference_internal 14 | Update: 15 | EnableActuatorWidgets: 16 | DisableActuatorWidgets: 17 | SelectTab: 18 | overloads: 19 | int: 20 | std::string_view: 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/ShuffleboardLayout.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::ShuffleboardLayout: 4 | # virtual base issue: robotpy-build/166 5 | force_no_trampoline: true 6 | methods: 7 | ShuffleboardLayout: 8 | BuildInto: 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/ShuffleboardRoot.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/shuffleboard/ShuffleboardTab.h 4 | 5 | classes: 6 | frc::ShuffleboardRoot: 7 | rename: _ShuffleboardRoot 8 | methods: 9 | GetTab: 10 | return_value_policy: reference_internal 11 | Update: 12 | EnableActuatorWidgets: 13 | DisableActuatorWidgets: 14 | SelectTab: 15 | overloads: 16 | int: 17 | std::string_view: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/ShuffleboardTab.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/shuffleboard/ShuffleboardRoot.h 4 | 5 | classes: 6 | frc::ShuffleboardTab: 7 | # virtual base issue: robotpy-build/166 8 | force_no_trampoline: true 9 | methods: 10 | ShuffleboardTab: 11 | return_value_policy: reference_internal 12 | GetRoot: 13 | BuildInto: 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/ShuffleboardValue.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::ShuffleboardValue: 4 | # virtual base issue: robotpy-build/166 5 | force_no_trampoline: true 6 | methods: 7 | ShuffleboardValue: 8 | ignore: true 9 | GetTitle: 10 | BuildInto: 11 | EnableIfActuator: 12 | DisableIfActuator: 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/SimpleWidget.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/shuffleboard/ShuffleboardContainer.h 4 | 5 | classes: 6 | frc::SimpleWidget: 7 | # virtual base issue: robotpy-build/166 8 | force_no_trampoline: true 9 | methods: 10 | SimpleWidget: 11 | GetEntry: 12 | overloads: 13 | '': 14 | return_value_policy: reference_internal 15 | std::string_view: 16 | return_value_policy: reference_internal 17 | BuildInto: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/shuffleboard/WidgetType.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::WidgetType: 4 | methods: 5 | WidgetType: 6 | GetWidgetName: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/ADIS16448_IMUSim.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/ADIS16448_IMU.h 4 | 5 | classes: 6 | frc::sim::ADIS16448_IMUSim: 7 | methods: 8 | ADIS16448_IMUSim: 9 | SetGyroAngleX: 10 | SetGyroAngleY: 11 | SetGyroAngleZ: 12 | SetGyroRateX: 13 | SetGyroRateY: 14 | SetGyroRateZ: 15 | SetAccelX: 16 | SetAccelY: 17 | SetAccelZ: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/ADIS16470_IMUSim.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/ADIS16470_IMU.h 4 | 5 | classes: 6 | frc::sim::ADIS16470_IMUSim: 7 | methods: 8 | ADIS16470_IMUSim: 9 | SetGyroAngleX: 10 | SetGyroAngleY: 11 | SetGyroAngleZ: 12 | SetGyroRateX: 13 | SetGyroRateY: 14 | SetGyroRateZ: 15 | SetAccelX: 16 | SetAccelY: 17 | SetAccelZ: 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/ADXL345Sim.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/ADXL345_I2C.h 4 | - frc/ADXL345_SPI.h 5 | 6 | classes: 7 | frc::sim::ADXL345Sim: 8 | methods: 9 | ADXL345Sim: 10 | overloads: 11 | const ADXL345_I2C&: 12 | const ADXL345_SPI&: 13 | SetX: 14 | SetY: 15 | SetZ: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/ADXL362Sim.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/ADXL362.h 4 | 5 | classes: 6 | frc::sim::ADXL362Sim: 7 | methods: 8 | ADXL362Sim: 9 | SetX: 10 | SetY: 11 | SetZ: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/ADXRS450_GyroSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/ADXRS450_Gyro.h 3 | 4 | classes: 5 | frc::sim::ADXRS450_GyroSim: 6 | methods: 7 | ADXRS450_GyroSim: 8 | SetAngle: 9 | SetRate: 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/AddressableLEDSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/AddressableLED.h 3 | 4 | classes: 5 | frc::sim::AddressableLEDSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | AddressableLEDSim: 10 | overloads: 11 | '': 12 | const AddressableLED&: 13 | CreateForChannel: 14 | CreateForIndex: 15 | RegisterInitializedCallback: 16 | GetInitialized: 17 | SetInitialized: 18 | RegisterOutputPortCallback: 19 | GetOutputPort: 20 | SetOutputPort: 21 | RegisterLengthCallback: 22 | GetLength: 23 | SetLength: 24 | RegisterRunningCallback: 25 | GetRunning: 26 | SetRunning: 27 | RegisterDataCallback: 28 | GetData: 29 | SetData: 30 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/AnalogEncoderSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/AnalogEncoder.h 3 | 4 | classes: 5 | frc::sim::AnalogEncoderSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | AnalogEncoderSim: 10 | SetPosition: 11 | SetTurns: 12 | GetTurns: 13 | GetPosition: 14 | Set: 15 | Get: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/AnalogGyroSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/AnalogGyro.h 3 | 4 | classes: 5 | frc::sim::AnalogGyroSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | AnalogGyroSim: 10 | overloads: 11 | const AnalogGyro&: 12 | int: 13 | RegisterAngleCallback: 14 | GetAngle: 15 | SetAngle: 16 | RegisterRateCallback: 17 | GetRate: 18 | SetRate: 19 | RegisterInitializedCallback: 20 | GetInitialized: 21 | SetInitialized: 22 | ResetData: 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/AnalogOutputSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/AnalogOutput.h 3 | 4 | classes: 5 | frc::sim::AnalogOutputSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | AnalogOutputSim: 10 | overloads: 11 | const AnalogOutput&: 12 | int: 13 | RegisterVoltageCallback: 14 | GetVoltage: 15 | SetVoltage: 16 | RegisterInitializedCallback: 17 | GetInitialized: 18 | SetInitialized: 19 | ResetData: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/AnalogTriggerSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/AnalogTrigger.h 3 | 4 | classes: 5 | frc::sim::AnalogTriggerSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | AnalogTriggerSim: 10 | overloads: 11 | const AnalogTrigger&: 12 | CreateForChannel: 13 | CreateForIndex: 14 | RegisterInitializedCallback: 15 | GetInitialized: 16 | SetInitialized: 17 | RegisterTriggerLowerBoundCallback: 18 | GetTriggerLowerBound: 19 | SetTriggerLowerBound: 20 | RegisterTriggerUpperBoundCallback: 21 | GetTriggerUpperBound: 22 | SetTriggerUpperBound: 23 | ResetData: 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/BatterySim.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::sim::BatterySim: 3 | force_type_casters: 4 | - units::ampere_t 5 | methods: 6 | Calculate: 7 | overloads: 8 | units::volt_t, units::ohm_t, std::span: 9 | units::volt_t, units::ohm_t, std::initializer_list: 10 | ignore: true 11 | std::span: 12 | std::initializer_list: 13 | ignore: true 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/BuiltInAccelerometerSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/BuiltInAccelerometer.h 3 | 4 | classes: 5 | frc::sim::BuiltInAccelerometerSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | BuiltInAccelerometerSim: 10 | overloads: 11 | '': 12 | const BuiltInAccelerometer&: 13 | RegisterActiveCallback: 14 | GetActive: 15 | SetActive: 16 | RegisterRangeCallback: 17 | GetRange: 18 | SetRange: 19 | RegisterXCallback: 20 | GetX: 21 | SetX: 22 | RegisterYCallback: 23 | GetY: 24 | SetY: 25 | RegisterZCallback: 26 | GetZ: 27 | SetZ: 28 | ResetData: 29 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/DIOSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/DigitalInput.h 3 | - frc/DigitalOutput.h 4 | 5 | classes: 6 | frc::sim::DIOSim: 7 | force_type_casters: 8 | - std::function 9 | methods: 10 | DIOSim: 11 | overloads: 12 | const DigitalInput&: 13 | const DigitalOutput&: 14 | int: 15 | RegisterInitializedCallback: 16 | GetInitialized: 17 | SetInitialized: 18 | RegisterValueCallback: 19 | GetValue: 20 | SetValue: 21 | RegisterPulseLengthCallback: 22 | GetPulseLength: 23 | SetPulseLength: 24 | RegisterIsInputCallback: 25 | GetIsInput: 26 | SetIsInput: 27 | RegisterFilterIndexCallback: 28 | GetFilterIndex: 29 | SetFilterIndex: 30 | ResetData: 31 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/DigitalPWMSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/DigitalOutput.h 3 | 4 | classes: 5 | frc::sim::DigitalPWMSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | DigitalPWMSim: 10 | overloads: 11 | const DigitalOutput&: 12 | CreateForChannel: 13 | CreateForIndex: 14 | RegisterInitializedCallback: 15 | GetInitialized: 16 | SetInitialized: 17 | RegisterDutyCycleCallback: 18 | GetDutyCycle: 19 | SetDutyCycle: 20 | RegisterPinCallback: 21 | GetPin: 22 | SetPin: 23 | ResetData: 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/DoubleSolenoidSim.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::sim::DoubleSolenoidSim: 4 | typealias: 5 | - frc::PneumaticsModuleType 6 | methods: 7 | DoubleSolenoidSim: 8 | overloads: 9 | std::shared_ptr, int, int: 10 | int, PneumaticsModuleType, int, int: 11 | PneumaticsModuleType, int, int: 12 | Get: 13 | Set: 14 | GetModuleSim: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/DutyCycleEncoderSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/DutyCycleEncoder.h 3 | 4 | classes: 5 | frc::sim::DutyCycleEncoderSim: 6 | methods: 7 | DutyCycleEncoderSim: 8 | overloads: 9 | const DutyCycleEncoder&: 10 | int: 11 | Get: 12 | Set: 13 | GetDistance: 14 | SetDistance: 15 | GetAbsolutePosition: 16 | SetAbsolutePosition: 17 | GetDistancePerRotation: 18 | IsConnected: 19 | SetConnected: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/DutyCycleSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/DutyCycle.h 3 | 4 | classes: 5 | frc::sim::DutyCycleSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | DutyCycleSim: 10 | overloads: 11 | const DutyCycle&: 12 | CreateForChannel: 13 | CreateForIndex: 14 | RegisterInitializedCallback: 15 | GetInitialized: 16 | SetInitialized: 17 | RegisterFrequencyCallback: 18 | GetFrequency: 19 | SetFrequency: 20 | RegisterOutputCallback: 21 | GetOutput: 22 | SetOutput: 23 | ResetData: 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/GenericHIDSim.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::sim::GenericHIDSim: 3 | methods: 4 | GenericHIDSim: 5 | overloads: 6 | const GenericHID&: 7 | int: 8 | NotifyNewData: 9 | SetRawButton: 10 | SetRawAxis: 11 | SetPOV: 12 | overloads: 13 | int, int: 14 | int: 15 | SetAxisCount: 16 | SetPOVCount: 17 | SetButtonCount: 18 | SetType: 19 | SetName: 20 | SetAxisType: 21 | GetOutput: 22 | GetOutputs: 23 | GetRumble: 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/JoystickSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/Joystick.h 3 | 4 | classes: 5 | frc::sim::JoystickSim: 6 | force_no_trampoline: true 7 | methods: 8 | JoystickSim: 9 | overloads: 10 | const Joystick&: 11 | int: 12 | SetX: 13 | SetY: 14 | SetZ: 15 | SetTwist: 16 | SetThrottle: 17 | SetTrigger: 18 | SetTop: 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/Mechanism2D.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::sim::Mechanism2D: 3 | methods: 4 | Mechanism2D: 5 | SetLigamentAngle: 6 | SetLigamentLength: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/PDPSim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/PowerDistributionPanel.h 3 | 4 | classes: 5 | frc::sim::PDPSim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | PDPSim: 10 | overloads: 11 | int: 12 | frc::PowerDistributionPanel&: 13 | RegisterInitializedCallback: 14 | GetInitialized: 15 | SetInitialized: 16 | RegisterTemperatureCallback: 17 | GetTemperature: 18 | SetTemperature: 19 | RegisterVoltageCallback: 20 | GetVoltage: 21 | SetVoltage: 22 | RegisterCurrentCallback: 23 | GetCurrent: 24 | SetCurrent: 25 | GetAllCurrents: 26 | SetAllCurrents: 27 | ResetData: 28 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/PowerDistributionSim.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/PowerDistribution.h 4 | 5 | classes: 6 | frc::sim::PowerDistributionSim: 7 | force_type_casters: 8 | - std::function 9 | methods: 10 | PowerDistributionSim: 11 | overloads: 12 | int: 13 | const PowerDistribution&: 14 | RegisterInitializedCallback: 15 | GetInitialized: 16 | SetInitialized: 17 | RegisterTemperatureCallback: 18 | GetTemperature: 19 | SetTemperature: 20 | RegisterVoltageCallback: 21 | GetVoltage: 22 | SetVoltage: 23 | RegisterCurrentCallback: 24 | GetCurrent: 25 | SetCurrent: 26 | GetAllCurrents: 27 | SetAllCurrents: 28 | ResetData: 29 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/RelaySim.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - frc/Relay.h 3 | 4 | classes: 5 | frc::sim::RelaySim: 6 | force_type_casters: 7 | - std::function 8 | methods: 9 | RelaySim: 10 | overloads: 11 | const Relay&: 12 | int: 13 | RegisterInitializedForwardCallback: 14 | GetInitializedForward: 15 | SetInitializedForward: 16 | RegisterInitializedReverseCallback: 17 | GetInitializedReverse: 18 | SetInitializedReverse: 19 | RegisterForwardCallback: 20 | GetForward: 21 | SetForward: 22 | RegisterReverseCallback: 23 | GetReverse: 24 | SetReverse: 25 | ResetData: 26 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/SPIAccelerometerSim.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::sim::SPIAccelerometerSim: 3 | force_type_casters: 4 | - std::function 5 | methods: 6 | SPIAccelerometerSim: 7 | RegisterActiveCallback: 8 | GetActive: 9 | SetActive: 10 | RegisterRangeCallback: 11 | GetRange: 12 | SetRange: 13 | RegisterXCallback: 14 | GetX: 15 | SetX: 16 | RegisterYCallback: 17 | GetY: 18 | SetY: 19 | RegisterZCallback: 20 | GetZ: 21 | SetZ: 22 | ResetData: 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/SendableChooserSim.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::sim::SendableChooserSim: 4 | methods: 5 | SendableChooserSim: 6 | overloads: 7 | std::string_view: 8 | nt::NetworkTableInstance, std::string_view: 9 | SetSelected: 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/SharpIRSim.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::SharpIRSim: 4 | methods: 5 | SharpIRSim: 6 | overloads: 7 | const SharpIR&: 8 | int: 9 | SetRange: 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/SimHooks.yml: -------------------------------------------------------------------------------- 1 | 2 | functions: 3 | SetRuntimeType: 4 | WaitForProgramStart: 5 | SetProgramStarted: 6 | GetProgramStarted: 7 | RestartTiming: 8 | PauseTiming: 9 | ResumeTiming: 10 | IsTimingPaused: 11 | StepTiming: 12 | StepTimingAsync: 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/SolenoidSim.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::sim::SolenoidSim: 3 | force_type_casters: 4 | - std::function 5 | typealias: 6 | - frc::PneumaticsModuleType 7 | methods: 8 | SolenoidSim: 9 | overloads: 10 | std::shared_ptr, int: 11 | int, PneumaticsModuleType, int: 12 | PneumaticsModuleType, int: 13 | GetOutput: 14 | SetOutput: 15 | RegisterOutputCallback: 16 | GetModuleSim: 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/semiwrap/simulation/UltrasonicSim.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - frc/Ultrasonic.h 4 | 5 | classes: 6 | frc::sim::UltrasonicSim: 7 | typealias: 8 | - frc::Ultrasonic 9 | methods: 10 | UltrasonicSim: 11 | overloads: 12 | const Ultrasonic&: 13 | int, int: 14 | SetRangeValid: 15 | SetRange: 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/tests/conftest.py: -------------------------------------------------------------------------------- 1 | import logging 2 | 3 | import pytest 4 | import ntcore 5 | import wpilib 6 | from wpilib.simulation._simulation import _resetWpilibSimulationData 7 | 8 | 9 | @pytest.fixture 10 | def cfg_logging(caplog): 11 | caplog.set_level(logging.INFO) 12 | 13 | 14 | @pytest.fixture(scope="function") 15 | def wpilib_state(): 16 | try: 17 | yield None 18 | finally: 19 | _resetWpilibSimulationData() 20 | 21 | 22 | @pytest.fixture(scope="function") 23 | def nt(cfg_logging, wpilib_state): 24 | instance = ntcore.NetworkTableInstance.getDefault() 25 | instance.startLocal() 26 | 27 | try: 28 | yield instance 29 | finally: 30 | instance.stopLocal() 31 | instance._reset() 32 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/tests/test_datalogmanager.py: -------------------------------------------------------------------------------- 1 | import pathlib 2 | import wpilib 3 | import pytest 4 | import sys 5 | 6 | 7 | @pytest.mark.skipif(sys.platform == "darwin", reason="DataLogManager crashes on exit") 8 | def test_get_log(tmp_path: pathlib.Path): 9 | log_dir = tmp_path / "wpilogs" 10 | log_dir.mkdir() 11 | wpilib.DataLogManager.start(str(log_dir)) 12 | log = wpilib.DataLogManager.getLog() 13 | assert log is not None 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/tests/test_mechanism2d.py: -------------------------------------------------------------------------------- 1 | from wpilib import Mechanism2d 2 | 3 | 4 | def test_create_mechanism(): 5 | m = Mechanism2d(100, 100) 6 | r1 = m.getRoot("r1", 10, 10) 7 | l1 = r1.appendLigament("l1", 4, 3) 8 | l2 = l1.appendLigament("l2", 4, 3) 9 | assert l2 is not None 10 | 11 | # TODO... check that they do something? 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/tests/test_wpilib_drive.py: -------------------------------------------------------------------------------- 1 | import wpilib.drive 2 | 3 | 4 | def test_wpilib_drive(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/tests/test_wpilib_interfaces.py: -------------------------------------------------------------------------------- 1 | import wpilib.interfaces 2 | 3 | 4 | def test_wpilib_interfaces(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/tests/test_wpilib_simulation.py: -------------------------------------------------------------------------------- 1 | import wpilib.simulation 2 | 3 | 4 | def test_wpilib_simulation(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/_impl/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-wpilib/wpilib/_impl/__init__.py -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/_impl/main.py: -------------------------------------------------------------------------------- 1 | import inspect 2 | import sys 3 | 4 | 5 | def run(robot_class, **kwargs): 6 | """ 7 | ``wpilib.run`` is no longer used. You should run your robot code via one of 8 | the following methods instead: 9 | 10 | * Windows: ``py -m robotpy [arguments]`` 11 | * Linux/macOS: ``python -m robotpy [arguments]`` 12 | 13 | In a virtualenv the ``robotpy`` command can be used directly. 14 | """ 15 | 16 | msg = inspect.cleandoc(inspect.getdoc(run) or "`wpilib.run` is no longer used") 17 | print(msg, file=sys.stderr) 18 | sys.exit(1) 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/counter/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__counter 2 | 3 | # autogenerated by 'semiwrap create-imports wpilib.counter wpilib.counter._counter' 4 | from ._counter import ( 5 | EdgeConfiguration, 6 | ExternalDirectionCounter, 7 | Tachometer, 8 | UpDownCounter, 9 | ) 10 | 11 | __all__ = [ 12 | "EdgeConfiguration", 13 | "ExternalDirectionCounter", 14 | "Tachometer", 15 | "UpDownCounter", 16 | ] 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/counter/counter.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpilib.counter._counter.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/drive/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__drive 2 | 3 | # autogenerated by 'semiwrap create-imports wpilib.drive wpilib.drive._drive' 4 | from ._drive import DifferentialDrive, MecanumDrive, RobotDriveBase 5 | 6 | __all__ = ["DifferentialDrive", "MecanumDrive", "RobotDriveBase"] 7 | 8 | del _init__drive 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/drive/drive.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpilib.drive._drive.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/event/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__event 2 | 3 | # autogenerated by 'semiwrap create-imports wpilib.event wpilib.event._event' 4 | from ._event import BooleanEvent, EventLoop, NetworkBooleanEvent 5 | 6 | __all__ = ["BooleanEvent", "EventLoop", "NetworkBooleanEvent"] 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/event/event.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpilib.event._event.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/interfaces/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__interfaces 2 | 3 | # autogenerated by 'semiwrap create-imports wpilib.interfaces wpilib.interfaces._interfaces' 4 | from ._interfaces import CounterBase, GenericHID, MotorController 5 | 6 | __all__ = ["CounterBase", "GenericHID", "MotorController"] 7 | 8 | del _init__interfaces 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/interfaces/interfaces.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpilib.interfaces._interfaces.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-wpilib/wpilib/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/shuffleboard/ShuffleboardData.h: -------------------------------------------------------------------------------- 1 | 2 | #pragma once 3 | 4 | #include 5 | #include 6 | 7 | namespace rpy { 8 | 9 | // 10 | // These functions must be called with the GIL held 11 | // 12 | 13 | void addShuffleboardData(py::str &key, std::shared_ptr data); 14 | void clearShuffleboardData(); 15 | void destroyShuffleboardData(); 16 | 17 | } // namespace rpy -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/shuffleboard/shuffleboard.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpilib.shuffleboard._shuffleboard.hpp" 3 | #include "ShuffleboardData.h" 4 | 5 | SEMIWRAP_PYBIND11_MODULE(m) 6 | { 7 | initWrapper(m); 8 | 9 | // ensure that the shuffleboard data is released when python shuts down 10 | static int unused; // the capsule needs something to reference 11 | py::capsule cleanup(&unused, [](void *) { 12 | rpy::destroyShuffleboardData(); 13 | }); 14 | m.add_object("_sbd_cleanup", cleanup); 15 | m.def("_clearShuffleboardData", &rpy::clearShuffleboardData); 16 | } 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/src/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpilib._wpilib.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) { initWrapper(m); } 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/src/rpy/ControlWord.cpp: -------------------------------------------------------------------------------- 1 | #include "rpy/ControlWord.h" 2 | 3 | #include 4 | 5 | namespace rpy { 6 | 7 | std::tuple GetControlState() { 8 | HAL_ControlWord controlWord; 9 | HAL_GetControlWord(&controlWord); 10 | 11 | bool enable = controlWord.enabled != 0 && controlWord.dsAttached != 0; 12 | bool auton = controlWord.autonomous != 0; 13 | bool test = controlWord.test != 0; 14 | 15 | return std::make_tuple(enable, auton, test); 16 | } 17 | 18 | } // namespace rpy 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/src/rpy/ControlWord.h: -------------------------------------------------------------------------------- 1 | #include 2 | 3 | namespace rpy { 4 | 5 | std::tuple GetControlState(); 6 | 7 | } // namespace rpy 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/src/rpy/SmartDashboardData.h: -------------------------------------------------------------------------------- 1 | 2 | #pragma once 3 | 4 | #include 5 | #include 6 | 7 | namespace rpy { 8 | 9 | // 10 | // These functions must be called with the GIL held 11 | // 12 | 13 | void addSmartDashboardData(py::str &key, std::shared_ptr data); 14 | void clearSmartDashboardData(); 15 | void destroySmartDashboardData(); 16 | 17 | } // namespace rpy -------------------------------------------------------------------------------- /subprojects/robotpy-wpilib/wpilib/sysid/__init__.py: -------------------------------------------------------------------------------- 1 | # autogenerated by 'semiwrap create-imports wpilib.sysid wpilib._wpilib.sysid' 2 | from .._wpilib.sysid import State, SysIdRoutineLog 3 | 4 | __all__ = ["State", "SysIdRoutineLog"] 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/README.md: -------------------------------------------------------------------------------- 1 | robotpy-wpimath 2 | =============== 3 | 4 | Python wrappers for WPILib's wpimath library. 5 | 6 | * Installation instructions can be found in the [RobotPy documentation](https://robotpy.readthedocs.io/en/latest/getting_started.html) 7 | * Documentation can be found at [readthedocs](https://robotpy.readthedocs.io/projects/wpimath/en/stable/api.html) 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/ComputerVisionUtil.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | functions: 4 | ObjectToRobotPose: 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/BangBangController.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::BangBangController: 4 | subpackage: controller 5 | ignored_bases: 6 | - wpi::SendableHelper 7 | methods: 8 | BangBangController: 9 | SetSetpoint: 10 | GetSetpoint: 11 | AtSetpoint: 12 | SetTolerance: 13 | GetTolerance: 14 | GetMeasurement: 15 | GetError: 16 | Calculate: 17 | overloads: 18 | double, double: 19 | double: 20 | InitSendable: 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/CentripetalAccelerationConstraint.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::CentripetalAccelerationConstraint: 3 | subpackage: constraint 4 | typealias: 5 | - frc::TrajectoryConstraint::MinMax 6 | methods: 7 | CentripetalAccelerationConstraint: 8 | MaxVelocity: 9 | MinMaxAcceleration: 10 | 11 | inline_code: |- 12 | cls_CentripetalAccelerationConstraint 13 | .def_static("fromFps", [](units::feet_per_second_squared_t maxCentripetalAcceleration) { 14 | return std::make_shared(maxCentripetalAcceleration); 15 | }, py::arg("maxCentripetalAcceleration")); 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/DifferentialDriveAccelerationLimiter.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::DifferentialDriveAccelerationLimiter: 4 | subpackage: controller 5 | methods: 6 | DifferentialDriveAccelerationLimiter: 7 | overloads: 8 | LinearSystem<2, 2, 2>, units::meter_t, units::meters_per_second_squared_t, units::radians_per_second_squared_t: 9 | ? LinearSystem<2, 2, 2>, units::meter_t, units::meters_per_second_squared_t, 10 | units::meters_per_second_squared_t, units::radians_per_second_squared_t 11 | : 12 | Calculate: 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/DifferentialDriveKinematicsConstraint.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::DifferentialDriveKinematicsConstraint: 3 | subpackage: constraint 4 | typealias: 5 | - frc::TrajectoryConstraint::MinMax 6 | methods: 7 | DifferentialDriveKinematicsConstraint: 8 | MaxVelocity: 9 | MinMaxAcceleration: 10 | 11 | inline_code: |- 12 | cls_DifferentialDriveKinematicsConstraint 13 | .def_static("fromFps", [](const DifferentialDriveKinematics& kinematics, 14 | units::feet_per_second_t maxSpeed) { 15 | return std::make_shared(kinematics, maxSpeed); 16 | }, py::arg("kinematics"), py::arg("maxSpeed")) 17 | ; 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/DifferentialDrivePoseEstimator3d.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::DifferentialDrivePoseEstimator3d: 4 | subpackage: estimator 5 | force_no_trampoline: true 6 | methods: 7 | DifferentialDrivePoseEstimator3d: 8 | overloads: 9 | DifferentialDriveKinematics&, const Rotation3d&, units::meter_t, units::meter_t, const Pose3d&: 10 | ? DifferentialDriveKinematics&, const Rotation3d&, units::meter_t, units::meter_t, 11 | const Pose3d&, const wpi::array&, const wpi::array& 13 | : 14 | ResetPosition: 15 | Update: 16 | UpdateWithTime: 17 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/DifferentialDriveVoltageConstraint.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::DifferentialDriveVoltageConstraint: 3 | subpackage: constraint 4 | typealias: 5 | - frc::TrajectoryConstraint::MinMax 6 | methods: 7 | DifferentialDriveVoltageConstraint: 8 | MaxVelocity: 9 | MinMaxAcceleration: 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/HolonomicDriveController.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::HolonomicDriveController: 4 | subpackage: controller 5 | methods: 6 | HolonomicDriveController: 7 | AtReference: 8 | SetTolerance: 9 | Calculate: 10 | overloads: 11 | const Pose2d&, const Pose2d&, units::meters_per_second_t, const Rotation2d&: 12 | const Pose2d&, const Trajectory::State&, const Rotation2d&: 13 | SetEnabled: 14 | getThetaController: 15 | ignore: true 16 | getXController: 17 | ignore: true 18 | getYController: 19 | ignore: true 20 | GetXController: 21 | GetYController: 22 | GetThetaController: 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/LTVDifferentialDriveController.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::LTVDifferentialDriveController: 4 | subpackage: controller 5 | methods: 6 | LTVDifferentialDriveController: 7 | AtReference: 8 | SetTolerance: 9 | Calculate: 10 | overloads: 11 | ? const Pose2d&, units::meters_per_second_t, units::meters_per_second_t, 12 | const Pose2d&, units::meters_per_second_t, units::meters_per_second_t 13 | : 14 | const Pose2d&, units::meters_per_second_t, units::meters_per_second_t, const Trajectory::State&: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/MaxVelocityConstraint.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::MaxVelocityConstraint: 4 | subpackage: constraint 5 | typealias: 6 | - frc::TrajectoryConstraint::MinMax 7 | methods: 8 | MaxVelocityConstraint: 9 | MaxVelocity: 10 | MinMaxAcceleration: 11 | 12 | inline_code: |- 13 | cls_MaxVelocityConstraint 14 | .def_static("fromFps", [](units::feet_per_second_t maxVelocity) { 15 | return std::make_shared(maxVelocity); 16 | }, py::arg("maxVelocity")) 17 | ; 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/MecanumDriveKinematicsConstraint.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::MecanumDriveKinematicsConstraint: 3 | subpackage: constraint 4 | typealias: 5 | - frc::TrajectoryConstraint::MinMax 6 | methods: 7 | MecanumDriveKinematicsConstraint: 8 | MaxVelocity: 9 | MinMaxAcceleration: 10 | 11 | inline_code: |- 12 | cls_MecanumDriveKinematicsConstraint 13 | .def_static("fromFps", [](const frc::MecanumDriveKinematics& kinematics, 14 | units::feet_per_second_t maxSpeed) { 15 | return std::make_shared(kinematics, maxSpeed); 16 | }, py::arg("kinematics"), py::arg("maxSpeed")) 17 | ; 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/MecanumDrivePoseEstimator3d.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::MecanumDrivePoseEstimator3d: 4 | subpackage: estimator 5 | force_no_trampoline: true 6 | methods: 7 | MecanumDrivePoseEstimator3d: 8 | overloads: 9 | MecanumDriveKinematics&, const Rotation3d&, const MecanumDriveWheelPositions&, const Pose3d&: 10 | ? MecanumDriveKinematics&, const Rotation3d&, const MecanumDriveWheelPositions&, 11 | const Pose3d&, const wpi::array&, const wpi::array& 13 | : 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/RectangularRegionConstraint.yml: -------------------------------------------------------------------------------- 1 | extra_includes: 2 | - PyTrajectoryConstraint.h 3 | 4 | classes: 5 | frc::RectangularRegionConstraint: 6 | template_params: 7 | - typename Constraint 8 | typealias: 9 | - frc::TrajectoryConstraint::MinMax 10 | methods: 11 | RectangularRegionConstraint: 12 | overloads: 13 | const Translation2d&, const Translation2d&, const Constraint&: 14 | const Rectangle2d&, const Constraint&: 15 | MaxVelocity: 16 | MinMaxAcceleration: 17 | IsPoseInRegion: 18 | 19 | templates: 20 | RectangularRegionConstraint: 21 | subpackage: constraint 22 | qualname: frc::RectangularRegionConstraint 23 | params: 24 | - frc::PyTrajectoryConstraint 25 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/SimulatedAnnealing.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - gilsafe_object.h 4 | 5 | classes: 6 | frc::SimulatedAnnealing: 7 | template_params: 8 | - State 9 | methods: 10 | SimulatedAnnealing: 11 | Solve: 12 | 13 | templates: 14 | SimulatedAnnealing: 15 | qualname: frc::SimulatedAnnealing 16 | subpackage: optimization 17 | params: 18 | - semiwrap::gilsafe_object 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/TrajectoryParameterizer.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::TrajectoryParameterizer: 3 | subpackage: trajectory 4 | force_type_casters: 5 | - units::unit_t 6 | - units::curvature_t 7 | methods: 8 | TimeParameterizeTrajectory: 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/TrajectoryUtil.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::TrajectoryUtil: 3 | subpackage: trajectory 4 | methods: 5 | ToPathweaverJson: 6 | FromPathweaverJson: 7 | SerializeTrajectory: 8 | DeserializeTrajectory: 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/controls/TravelingSalesman.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::TravelingSalesman: 4 | subpackage: path 5 | methods: 6 | TravelingSalesman: 7 | overloads: 8 | '': 9 | std::function: 10 | Solve: 11 | overloads: 12 | const wpi::array&, int: 13 | ignore: true 14 | std::span, int: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/filter/Debouncer.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::Debouncer: 4 | enums: 5 | DebounceType: 6 | methods: 7 | Debouncer: 8 | param_override: 9 | type: 10 | default: frc::Debouncer::DebounceType::kRising 11 | Calculate: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/filter/MedianFilter.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::MedianFilter: 3 | template_params: 4 | - T 5 | methods: 6 | MedianFilter: 7 | Calculate: 8 | LastValue: 9 | Reset: 10 | 11 | templates: 12 | MedianFilter: 13 | qualname: frc::MedianFilter 14 | params: 15 | - double 16 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/filter/SlewRateLimiter.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::SlewRateLimiter: 4 | template_params: 5 | - Unit 6 | typealias: 7 | - Unit_t = units::unit_t 8 | - Rate = units::compound_unit> 9 | methods: 10 | SlewRateLimiter: 11 | overloads: 12 | Rate_t, Rate_t, Unit_t: 13 | Rate_t: 14 | Rate_t, Unit_t: 15 | Calculate: 16 | LastValue: 17 | Reset: 18 | 19 | templates: 20 | SlewRateLimiter: 21 | qualname: frc::SlewRateLimiter 22 | params: 23 | - units::dimensionless::scalar 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/geometry/CoordinateAxis.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::CoordinateAxis: 4 | methods: 5 | CoordinateAxis: 6 | N: 7 | S: 8 | E: 9 | W: 10 | U: 11 | D: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/geometry/CoordinateSystem.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::CoordinateSystem: 4 | methods: 5 | CoordinateSystem: 6 | NWU: 7 | EDN: 8 | NED: 9 | Convert: 10 | overloads: 11 | const Translation3d&, const CoordinateSystem&, const CoordinateSystem&: 12 | const Rotation3d&, const CoordinateSystem&, const CoordinateSystem&: 13 | const Pose3d&, const CoordinateSystem&, const CoordinateSystem&: 14 | const Transform3d&, const CoordinateSystem&, const CoordinateSystem&: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/DifferentialDriveKinematics.yml: -------------------------------------------------------------------------------- 1 | 2 | extra_includes: 3 | - wpystruct.h 4 | 5 | classes: 6 | frc::DifferentialDriveKinematics: 7 | attributes: 8 | trackWidth: 9 | methods: 10 | DifferentialDriveKinematics: 11 | ToChassisSpeeds: 12 | ToWheelSpeeds: 13 | ToTwist2d: 14 | overloads: 15 | const units::meter_t, const units::meter_t [const]: 16 | const DifferentialDriveWheelPositions&, const DifferentialDriveWheelPositions& [const]: 17 | Interpolate: 18 | 19 | inline_code: | 20 | SetupWPyStruct(cls_DifferentialDriveKinematics); 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/DifferentialDriveOdometry.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::DifferentialDriveOdometry: 4 | force_no_trampoline: true 5 | methods: 6 | DifferentialDriveOdometry: 7 | ResetPosition: 8 | GetPose: 9 | Update: 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/DifferentialDriveOdometry3d.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::DifferentialDriveOdometry3d: 4 | force_no_trampoline: true 5 | methods: 6 | DifferentialDriveOdometry3d: 7 | ResetPosition: 8 | Update: 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/DifferentialDriveWheelPositions.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::DifferentialDriveWheelPositions: 4 | attributes: 5 | left: 6 | right: 7 | methods: 8 | operator==: 9 | operator!=: 10 | Interpolate: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/MecanumDriveOdometry.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::MecanumDriveOdometry: 4 | force_no_trampoline: true 5 | methods: 6 | MecanumDriveOdometry: 7 | ResetPosition: 8 | GetPose: 9 | UpdateWithTime: 10 | Update: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/MecanumDriveOdometry3d.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::MecanumDriveOdometry3d: 4 | force_no_trampoline: true 5 | methods: 6 | MecanumDriveOdometry3d: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/MecanumDriveWheelPositions.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::MecanumDriveWheelPositions: 4 | attributes: 5 | frontLeft: 6 | frontRight: 7 | rearLeft: 8 | rearRight: 9 | methods: 10 | operator==: 11 | operator!=: 12 | Interpolate: 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/SwerveDriveOdometry.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::SwerveDriveOdometry: 4 | force_no_trampoline: true 5 | template_params: 6 | - size_t NumModules 7 | methods: 8 | SwerveDriveOdometry: 9 | ResetPosition: 10 | GetPose: 11 | Update: 12 | templates: 13 | SwerveDrive2Odometry: 14 | qualname: frc::SwerveDriveOdometry 15 | params: 16 | - 2 17 | SwerveDrive3Odometry: 18 | qualname: frc::SwerveDriveOdometry 19 | params: 20 | - 3 21 | SwerveDrive4Odometry: 22 | qualname: frc::SwerveDriveOdometry 23 | params: 24 | - 4 25 | SwerveDrive6Odometry: 26 | qualname: frc::SwerveDriveOdometry 27 | params: 28 | - 6 29 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/kinematics/SwerveDriveOdometry3d.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::SwerveDriveOdometry3d: 4 | force_no_trampoline: true 5 | template_params: 6 | - size_t NumModules 7 | methods: 8 | SwerveDriveOdometry3d: 9 | 10 | templates: 11 | SwerveDrive2Odometry3d: 12 | qualname: frc::SwerveDriveOdometry3d 13 | params: 14 | - 2 15 | SwerveDrive3Odometry3d: 16 | qualname: frc::SwerveDriveOdometry3d 17 | params: 18 | - 3 19 | SwerveDrive4Odometry3d: 20 | qualname: frc::SwerveDriveOdometry3d 21 | params: 22 | - 4 23 | SwerveDrive6Odometry3d: 24 | qualname: frc::SwerveDriveOdometry3d 25 | params: 26 | - 6 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/spline/CubicHermiteSpline.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::CubicHermiteSpline: 4 | force_no_trampoline: true 5 | methods: 6 | CubicHermiteSpline: 7 | Coefficients: 8 | # otherwise we have to depend on numpy 9 | ignore: true 10 | GetInitialControlVector: 11 | GetFinalControlVector: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/spline/QuinticHermiteSpline.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::QuinticHermiteSpline: 4 | force_no_trampoline: true 5 | methods: 6 | QuinticHermiteSpline: 7 | Coefficients: 8 | ignore: true 9 | GetInitialControlVector: 10 | GetFinalControlVector: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/spline/SplineHelper.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::SplineHelper: 3 | methods: 4 | CubicControlVectorsFromWaypoints: 5 | QuinticControlVectorsFromWaypoints: 6 | QuinticSplinesFromWaypoints: 7 | CubicSplinesFromControlVectors: 8 | QuinticSplinesFromControlVectors: 9 | OptimizeCurvature: 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/semiwrap/spline/SplineParameterizer.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | frc::SplineParameterizer: 3 | force_no_default_constructor: true 4 | force_type_casters: 5 | - units::curvature_t 6 | methods: 7 | Parameterize: 8 | template_impls: 9 | - ['3'] 10 | - ['5'] 11 | 12 | frc::SplineParameterizer::MalformedSplineException: 13 | ignore: true 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/conftest.py: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/cpp/.gitignore: -------------------------------------------------------------------------------- 1 | *.py[ciod] 2 | *.so 3 | *.dylib 4 | 5 | /wpimath_test/wpimath_test.pc 6 | /wpimath_test/_init__wpimath_test.py 7 | /wpimath_test/trampolines -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/cpp/meson.build: -------------------------------------------------------------------------------- 1 | project('wpimath-test', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | wpimath_test_sources += files( 8 | 'wpimath_test/src/module.cpp', 9 | ) 10 | 11 | subdir('semiwrap/modules') 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/cpp/pyproject.toml: -------------------------------------------------------------------------------- 1 | [build-system] 2 | build-backend = "hatchling.build" 3 | requires = [ 4 | "semiwrap", "hatch-meson", "hatchling", 5 | ] 6 | 7 | [project] 8 | name = "wpimath_test" 9 | version = "0.1" 10 | description = "Test project for verifying robotpy-build behavior" 11 | authors = [ 12 | {name = "RobotPy Development Team", email = "robotpy@googlegroups.com"}, 13 | ] 14 | license = "BSD-3-Clause" 15 | 16 | [tool.hatch.build.hooks.semiwrap] 17 | [tool.hatch.build.hooks.meson] 18 | 19 | [tool.semiwrap] 20 | 21 | [tool.semiwrap.extension_modules."wpimath_test._wpimath_test"] 22 | name = "wpimath_test" 23 | depends = ["wpimath"] 24 | includes = ["wpimath_test/include"] 25 | 26 | [tool.semiwrap.extension_modules."wpimath_test._wpimath_test".headers] 27 | module = "module.h" 28 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/cpp/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/cpp/semiwrap/module.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | classes: 4 | SomeClass: 5 | attributes: 6 | kDefaultPeriod: 7 | five_ft: 8 | methods: 9 | checkDefaultByName: 10 | checkDefaultByNum1: 11 | param_override: 12 | period: 13 | default: 50_ms 14 | checkDefaultByNum2: 15 | param_override: 16 | period: 17 | default: 0.050_s 18 | ms2s: 19 | ft2m: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/cpp/wpimath_test/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__wpimath_test 2 | 3 | # autogenerated by 'robotpy-build create-imports wpimath_test' 4 | from ._wpimath_test import SomeClass 5 | 6 | __all__ = ["SomeClass"] 7 | 8 | del _init__wpimath_test 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call( 13 | [ 14 | sys.executable, 15 | "-m", 16 | "pip", 17 | "--disable-pip-version-check", 18 | "install", 19 | "-v", 20 | "--force-reinstall", 21 | "--no-build-isolation", 22 | "./cpp", 23 | ] 24 | ) 25 | 26 | subprocess.check_call([sys.executable, "-m", "pytest", "--ignore=cpp"]) 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/test_controller.py: -------------------------------------------------------------------------------- 1 | import wpimath.controller 2 | 3 | 4 | def test_todo(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/test_estimator.py: -------------------------------------------------------------------------------- 1 | import wpimath.estimator 2 | 3 | 4 | def test_todo(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/test_spline.py: -------------------------------------------------------------------------------- 1 | import wpimath.spline 2 | 3 | 4 | def test_todo(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/tests/test_system.py: -------------------------------------------------------------------------------- 1 | import wpimath.system 2 | import wpimath.system.plant 3 | 4 | 5 | def test_todo(): 6 | pass 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__wpimath # noqa: F401 2 | 3 | # Needed for stubgen 4 | from . import geometry 5 | 6 | # autogenerated by 'semiwrap create-imports wpimath wpimath._wpimath' 7 | from ._wpimath import ( 8 | angleModulus, 9 | applyDeadband, 10 | floorDiv, 11 | floorMod, 12 | inputModulus, 13 | objectToRobotPose, 14 | slewRateLimit, 15 | ) 16 | 17 | __all__ = [ 18 | "angleModulus", 19 | "applyDeadband", 20 | "floorDiv", 21 | "floorMod", 22 | "inputModulus", 23 | "objectToRobotPose", 24 | "slewRateLimit", 25 | ] 26 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/_controls/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__controls 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/_controls/controls.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpimath._controls._controls.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/_impl/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init_wpimath_cpp 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/_impl/src/type_casters/frc_eigen.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | // the FRC types are just aliases for Eigen types, so use that 4 | #include 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/_impl/src/type_casters/units_data_type_caster.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | namespace pybind11 { 6 | namespace detail { 7 | template <> struct handle_type_name { 8 | static constexpr auto name = _("wpimath.units.exabytes"); 9 | }; 10 | 11 | template <> struct handle_type_name { 12 | static constexpr auto name = _("wpimath.units.exabytes"); 13 | }; 14 | 15 | template <> struct handle_type_name { 16 | static constexpr auto name = _("wpimath.units.exabits"); 17 | }; 18 | 19 | template <> struct handle_type_name { 20 | static constexpr auto name = _("wpimath.units.exabits"); 21 | }; 22 | 23 | } // namespace detail 24 | } // namespace pybind11 25 | 26 | #include "_units_base_type_caster.h" 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/_impl/src/type_casters/units_moment_of_inertia_type_caster.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | namespace pybind11 { 6 | namespace detail { 7 | template <> struct handle_type_name { 8 | static constexpr auto name = _("wpimath.units.kilogram_square_meters"); 9 | }; 10 | 11 | template <> struct handle_type_name { 12 | static constexpr auto name = _("wpimath.units.kilogram_square_meters"); 13 | }; 14 | 15 | } // namespace detail 16 | } // namespace pybind11 17 | 18 | #include "_units_base_type_caster.h" 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/_impl/src/type_casters/units_substance_type_caster.h: -------------------------------------------------------------------------------- 1 | #pragma once 2 | 3 | #include 4 | 5 | namespace pybind11 { 6 | namespace detail { 7 | template <> struct handle_type_name { 8 | static constexpr auto name = _("wpimath.units.moles"); 9 | }; 10 | 11 | template <> struct handle_type_name { 12 | static constexpr auto name = _("wpimath.units.moles"); 13 | }; 14 | 15 | } // namespace detail 16 | } // namespace pybind11 17 | 18 | #include "_units_base_type_caster.h" 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/filter/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__filter 2 | 3 | # autogenerated by 'semiwrap create-imports wpimath.filter wpimath.filter._filter' 4 | from ._filter import Debouncer, LinearFilter, MedianFilter, SlewRateLimiter 5 | 6 | __all__ = ["Debouncer", "LinearFilter", "MedianFilter", "SlewRateLimiter"] 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/filter/filter.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpimath.filter._filter.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/geometry/geometry.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpimath.geometry._geometry.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/interpolation/interpolation.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpimath.interpolation._interpolation.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/kinematics/kinematics.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpimath.kinematics._kinematics.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/optimization/__init__.py: -------------------------------------------------------------------------------- 1 | # autogenerated by 'semiwrap create-imports wpimath.optimization wpimath._controls._controls.optimization' 2 | from .._controls._controls.optimization import SimulatedAnnealing 3 | 4 | __all__ = ["SimulatedAnnealing"] 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/path/__init__.py: -------------------------------------------------------------------------------- 1 | # autogenerated by 'semiwrap create-imports wpimath.path wpimath._controls._controls.path' 2 | from .._controls._controls.path import TravelingSalesman 3 | 4 | __all__ = ["TravelingSalesman"] 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-wpimath/wpimath/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/spline/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__spline 2 | 3 | # autogenerated by 'semiwrap create-imports wpimath.spline wpimath.spline._spline' 4 | from ._spline import ( 5 | CubicHermiteSpline, 6 | QuinticHermiteSpline, 7 | Spline3, 8 | Spline5, 9 | SplineHelper, 10 | SplineParameterizer, 11 | ) 12 | 13 | __all__ = [ 14 | "CubicHermiteSpline", 15 | "QuinticHermiteSpline", 16 | "Spline3", 17 | "Spline5", 18 | "SplineHelper", 19 | "SplineParameterizer", 20 | ] 21 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/spline/spline.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpimath.spline._spline.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) 5 | { 6 | initWrapper(m); 7 | } 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/src/wpimath.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include "semiwrap_init.wpimath._wpimath.hpp" 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) { initWrapper(m); } 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/system/plant/__init__.py: -------------------------------------------------------------------------------- 1 | from ..._controls._controls.plant import DCMotor, LinearSystemId 2 | 3 | __all__ = ["DCMotor", "LinearSystemId"] 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpimath/wpimath/trajectory/__init__.py: -------------------------------------------------------------------------------- 1 | # autogenerated by 'semiwrap create-imports wpimath.trajectory wpimath._controls._controls.trajectory' 2 | from .._controls._controls.trajectory import ( 3 | ExponentialProfileMeterVolts, 4 | Trajectory, 5 | TrajectoryConfig, 6 | TrajectoryGenerator, 7 | TrajectoryParameterizer, 8 | TrajectoryUtil, 9 | TrapezoidProfile, 10 | TrapezoidProfileRadians, 11 | ) 12 | 13 | __all__ = [ 14 | "ExponentialProfileMeterVolts", 15 | "Trajectory", 16 | "TrajectoryConfig", 17 | "TrajectoryGenerator", 18 | "TrajectoryParameterizer", 19 | "TrajectoryUtil", 20 | "TrapezoidProfile", 21 | "TrapezoidProfileRadians", 22 | ] 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/.gitignore: -------------------------------------------------------------------------------- 1 | *.py[ciod] 2 | *.egg-info 3 | 4 | *.so 5 | *.dll 6 | *.dylib 7 | 8 | .vscode 9 | 10 | __pycache__ 11 | /wpinet/include 12 | /wpinet/lib 13 | /wpinet/_init__wpinet.py 14 | /wpinet/wpinet.pc 15 | /wpinet/trampolines 16 | /wpinet/version.py 17 | /dist 18 | /build 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/README.md: -------------------------------------------------------------------------------- 1 | robotpy-wpinet 2 | ============== 3 | 4 | Python wrappers for WPILib's wpinet library. 5 | 6 | * Installation instructions can be found in the [RobotPy documentation](https://robotpy.readthedocs.io/en/latest/getting_started.html) 7 | * Documentation can be found at [readthedocs](https://robotpy.readthedocs.io/projects/wpinet/en/stable/api.html) 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/examples/portfwd.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import argparse 4 | import time 5 | import wpinet 6 | 7 | if __name__ == "__main__": 8 | parser = argparse.ArgumentParser() 9 | parser.add_argument("port", type=int, help="Local port number") 10 | parser.add_argument("remoteHost", help="Remote IP address / DNS name") 11 | parser.add_argument("remotePort", type=int, help="remote port number") 12 | args = parser.parse_args() 13 | 14 | wpinet.PortForwarder.getInstance().add(args.port, args.remoteHost, args.remotePort) 15 | 16 | while True: 17 | time.sleep(1) 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/meson.build: -------------------------------------------------------------------------------- 1 | project('robotpy-wpinet', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | wpinet_sources += files( 8 | 'wpinet/src/main.cpp', 9 | ) 10 | 11 | subdir('semiwrap/modules') 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/semiwrap/PortForwarder.yml: -------------------------------------------------------------------------------- 1 | classes: 2 | wpi::PortForwarder: 3 | nodelete: true 4 | methods: 5 | GetInstance: 6 | return_value_policy: reference 7 | Add: 8 | Remove: 9 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/semiwrap/WebServer.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | classes: 4 | wpi::WebServer: 5 | nodelete: true 6 | methods: 7 | GetInstance: 8 | return_value_policy: reference 9 | Start: 10 | Stop: 11 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/tests/test_wpinet.py: -------------------------------------------------------------------------------- 1 | import wpinet 2 | 3 | 4 | def test_existance(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/wpinet/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__wpinet 2 | 3 | 4 | # autogenerated by 'semiwrap create-imports wpinet wpinet._wpinet' 5 | from ._wpinet import PortForwarder, WebServer 6 | 7 | __all__ = ["PortForwarder", "WebServer"] 8 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/wpinet/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-wpinet/wpinet/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-wpinet/wpinet/src/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) { initWrapper(m); } 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/.gitignore: -------------------------------------------------------------------------------- 1 | *.py[ciod] 2 | *.egg-info 3 | 4 | *.so 5 | *.dll 6 | *.dylib 7 | 8 | .vscode 9 | 10 | __pycache__ 11 | /wpiutil/trampolines 12 | /wpiutil/_init__wpiutil.py 13 | /wpiutil/version.py 14 | /dist 15 | /build 16 | 17 | *.pc 18 | *.pybind11.json 19 | 20 | /tests/cpp/build 21 | /tests/cpp/wpiutil_test/_initmodule.py 22 | /tests/cpp/wpiutil_test/pkgcfg.py 23 | /tests/cpp/wpiutil_test/version.py -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/meson.build: -------------------------------------------------------------------------------- 1 | project('robotpy-wpiutil', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | wpiutil_sources += files( 8 | 'wpiutil/src/main.cpp', 9 | 'wpiutil/src/safethread_gil.cpp', 10 | 'wpiutil/src/stacktracehook.cpp', 11 | 'wpiutil/src/wpistruct/wpystruct_fns.cpp', 12 | ) 13 | 14 | subdir('semiwrap/modules') 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/DataLogBackgroundWriter.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | classes: 4 | wpi::log::DataLogBackgroundWriter: 5 | methods: 6 | DataLogBackgroundWriter: 7 | overloads: 8 | std::string_view, std::string_view, double, std::string_view: 9 | wpi::Logger&, std::string_view, std::string_view, double, std::string_view: 10 | ignore: true 11 | std::function data)>, double, std::string_view: 12 | wpi::Logger&, std::function data)>, double, std::string_view: 13 | ignore: true 14 | SetFilename: 15 | Flush: 16 | Pause: 17 | Resume: 18 | Stop: 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/RawFrame.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | defaults: 4 | ignore: true 5 | 6 | enums: 7 | WPI_TimestampSource: 8 | value_prefix: WPI_TIMESRC 9 | rename: TimestampSource 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/Sendable.yml: -------------------------------------------------------------------------------- 1 | --- 2 | 3 | extra_includes: 4 | - wpi/sendable/SendableBuilder.h 5 | 6 | classes: 7 | wpi::Sendable: 8 | methods: 9 | InitSendable: 10 | virtual_xform: | 11 | [&](py::function fn) { 12 | auto builderHandle = py::cast(builder, py::return_value_policy::reference); 13 | fn(builderHandle); 14 | } -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/SendableHelper.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | wpi::SendableHelper: 4 | ignore: true # CRTP 5 | methods: 6 | GetName: 7 | SetName: 8 | overloads: 9 | std::string_view: 10 | std::string_view, std::string_view: 11 | std::string_view, int: 12 | std::string_view, int, int: 13 | GetSubsystem: 14 | SetSubsystem: 15 | AddChild: 16 | overloads: 17 | std::shared_ptr: 18 | void*: 19 | SendableHelper: 20 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/StackTrace.yml: -------------------------------------------------------------------------------- 1 | functions: 2 | GetStackTrace: 3 | GetStackTraceDefault: 4 | SetGetStackTraceImpl: 5 | ignore: true -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/WPyStruct.yml: -------------------------------------------------------------------------------- 1 | functions: 2 | forEachNested: 3 | subpackage: wpistruct 4 | no_release_gil: true 5 | getTypeName: 6 | subpackage: wpistruct 7 | no_release_gil: true 8 | getSchema: 9 | subpackage: wpistruct 10 | no_release_gil: true 11 | getSize: 12 | subpackage: wpistruct 13 | no_release_gil: true 14 | pack: 15 | subpackage: wpistruct 16 | no_release_gil: true 17 | packArray: 18 | subpackage: wpistruct 19 | no_release_gil: true 20 | packInto: 21 | subpackage: wpistruct 22 | no_release_gil: true 23 | unpack: 24 | subpackage: wpistruct 25 | no_release_gil: true 26 | unpackArray: 27 | subpackage: wpistruct 28 | no_release_gil: true 29 | unpackInto: 30 | subpackage: wpistruct 31 | no_release_gil: true 32 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/modules/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/semiwrap/trampolines/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/conftest.py: -------------------------------------------------------------------------------- 1 | 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/cpp/meson.build: -------------------------------------------------------------------------------- 1 | project('wpiutil-test', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | py = import('python').find_installation() 6 | 7 | py.extension_module( 8 | 'module', 9 | sources: files( 10 | 'wpiutil_test/module.cpp', 11 | 'wpiutil_test/sendable_test.cpp', 12 | 'wpiutil_test/struct_test.cpp', 13 | ), 14 | install: true, 15 | subdir: 'wpiutil_test', 16 | dependencies: [dependency('semiwrap'), dependency('wpiutil')], 17 | ) 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/cpp/pyproject.toml: -------------------------------------------------------------------------------- 1 | [build-system] 2 | build-backend = "hatchling.build" 3 | requires = [ 4 | "hatch-meson", "hatchling" 5 | ] 6 | 7 | [project] 8 | name = "wpiutil_test" 9 | version = "0.0.1" 10 | 11 | [tool.hatch.build.hooks.meson] 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/cpp/wpiutil_test/__init__.py: -------------------------------------------------------------------------------- 1 | import wpiutil 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call( 13 | [ 14 | sys.executable, 15 | "-m", 16 | "pip", 17 | "--disable-pip-version-check", 18 | "install", 19 | "-v", 20 | "--force-reinstall", 21 | "--no-build-isolation", 22 | "./cpp", 23 | ], 24 | ) 25 | 26 | subprocess.check_call([sys.executable, "-m", "pytest"]) 27 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/test_array.py: -------------------------------------------------------------------------------- 1 | from wpiutil_test import module 2 | 3 | 4 | def test_load_array_int(): 5 | assert module.load_array_int((1, 2, 3, 4)) == (1, 2, 3, 4) 6 | assert module.load_array_int([1, 2, 3, 4]) == (1, 2, 3, 4) 7 | 8 | 9 | def test_load_array_annotation(): 10 | assert ( 11 | module.load_array_int.__doc__ 12 | == "load_array_int(arg0: Tuple[typing.SupportsInt, typing.SupportsInt, typing.SupportsInt, typing.SupportsInt]) -> Tuple[int, int, int, int]\n" 13 | ) 14 | assert ( 15 | module.load_array_int1.__doc__ 16 | == "load_array_int1(arg0: Tuple[typing.SupportsInt]) -> Tuple[int]\n" 17 | ) 18 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/test_ct_string.py: -------------------------------------------------------------------------------- 1 | from wpiutil_test import module 2 | 3 | 4 | def test_const_string(): 5 | assert module.const_string() == "#12" 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/test_smallset.py: -------------------------------------------------------------------------------- 1 | from wpiutil_test import module 2 | 3 | 4 | def test_smallset_load(): 5 | assert module.load_smallset_int({1, 2, 3, 4}) == {1, 2, 3, 4} 6 | 7 | 8 | def test_smallsetbool_load(): 9 | assert module.load_smallset_int({True, True, False, True}) == { 10 | True, 11 | True, 12 | False, 13 | True, 14 | } 15 | 16 | 17 | def test_smallset_cast(): 18 | assert module.cast_smallset() == {1, 2, 3, 4} 19 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/test_smallvector.py: -------------------------------------------------------------------------------- 1 | from wpiutil_test import module 2 | 3 | 4 | def test_smallvec_load(): 5 | assert module.load_smallvec_int([1, 2, 3, 4]) == [1, 2, 3, 4] 6 | 7 | 8 | def test_smallvecbool_load(): 9 | assert module.load_smallvec_int([True, True, False, True]) == [ 10 | True, 11 | True, 12 | False, 13 | True, 14 | ] 15 | 16 | 17 | def test_smallvec_cast(): 18 | assert module.cast_smallvec() == [1, 2, 3, 4] 19 | 20 | 21 | def test_smallvecimpl_load(): 22 | assert module.load_smallvecimpl_int([1, 2, 3, 4]) == [1, 2, 3, 4] 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/test_stacktrace.py: -------------------------------------------------------------------------------- 1 | import wpiutil 2 | 3 | 4 | def test_python_stack_trace(): 5 | st = wpiutil._wpiutil.getStackTrace(0) 6 | assert __file__ in st 7 | 8 | st = wpiutil._wpiutil.getStackTraceDefault(0) 9 | assert __file__ not in st 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/tests/test_stringmap.py: -------------------------------------------------------------------------------- 1 | from wpiutil_test import module 2 | 3 | 4 | def test_stringmap_load(): 5 | assert module.load_stringmap_int({"one": 11, "two": 22, "three": 33}) == { 6 | "one": 11, 7 | "two": 22, 8 | "three": 33, 9 | } 10 | 11 | 12 | def test_stringmap_cast(): 13 | assert module.cast_stringmap() == {"one": 1, "two": 2} 14 | -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/wpiutil/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-wpiutil/wpiutil/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/wpiutil/src/type_casters/wpi_smallset_type_caster.h: -------------------------------------------------------------------------------- 1 | 2 | #pragma once 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | 9 | namespace pybind11 10 | { 11 | namespace detail 12 | { 13 | 14 | template struct type_caster> 15 | : set_caster, Type> { }; 16 | 17 | } // namespace detail 18 | } // namespace pybind11 -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/wpiutil/src/type_casters/wpi_smallvector_type_caster.h: -------------------------------------------------------------------------------- 1 | 2 | #pragma once 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | 9 | namespace pybind11 10 | { 11 | namespace detail 12 | { 13 | 14 | template struct type_caster> 15 | : list_caster, Type> { }; 16 | 17 | } // namespace detail 18 | } // namespace pybind11 -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/wpiutil/src/type_casters/wpi_string_map_caster.h: -------------------------------------------------------------------------------- 1 | 2 | #pragma once 3 | 4 | #include 5 | #include 6 | 7 | #include 8 | 9 | namespace pybind11 10 | { 11 | namespace detail 12 | { 13 | 14 | template 15 | struct type_caster> 16 | : map_caster, std::string, Value> { }; 17 | 18 | } // namespace detail 19 | } // namespace pybind11 -------------------------------------------------------------------------------- /subprojects/robotpy-wpiutil/wpiutil/wpistruct/typing.py: -------------------------------------------------------------------------------- 1 | from typing import ClassVar, Protocol 2 | 3 | try: 4 | from typing import TypeGuard 5 | except ImportError: 6 | try: 7 | from typing_extensions import TypeGuard 8 | except ImportError: 9 | # Runtime fallback for Python 3.9 without typing_extensions 10 | class TypeGuard: 11 | def __class_getitem__(cls, key): 12 | return bool 13 | 14 | 15 | class StructSerializable(Protocol): 16 | """Any type that can be serialized or deserialized as a WPILib Struct.""" 17 | 18 | WPIStruct: ClassVar 19 | 20 | 21 | def is_wpistruct_type(cls: type) -> TypeGuard[type[StructSerializable]]: 22 | """Returns True if the given type supports WPILib Struct serialization.""" 23 | return hasattr(cls, "WPIStruct") 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/.gitignore: -------------------------------------------------------------------------------- 1 | *.py[cod] 2 | *.so 3 | *.dll 4 | *.egg-info 5 | 6 | /build 7 | /dist 8 | 9 | /xrp/_init__xrp.py 10 | /xrp/pkgcfg.py 11 | /xrp/version.py 12 | /xrp/extension/lib 13 | /xrp/trampolines -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/README.md: -------------------------------------------------------------------------------- 1 | robotpy-xrp 2 | ============ 3 | 4 | RobotPy support for the WPILib XRP vendor library. 5 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/meson.build: -------------------------------------------------------------------------------- 1 | project('robotpy-xrp', ['cpp'], 2 | default_options: ['warning_level=1', 'cpp_std=c++20', 3 | 'b_colorout=auto', 'optimization=2', 'b_pie=true']) 4 | 5 | subdir('semiwrap') 6 | 7 | xrp_sources += files( 8 | 'xrp/src/main.cpp', 9 | ) 10 | 11 | subdir('semiwrap/modules') 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/semiwrap/.gitignore: -------------------------------------------------------------------------------- 1 | /meson.build 2 | /modules/meson.build 3 | /trampolines/meson.build 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/semiwrap/XRPGyro.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::XRPGyro: 4 | methods: 5 | XRPGyro: 6 | GetAngle: 7 | GetRate: 8 | GetRateX: 9 | GetRateY: 10 | GetRateZ: 11 | GetAngleX: 12 | GetAngleY: 13 | GetAngleZ: 14 | Reset: 15 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/semiwrap/XRPMotor.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::XRPMotor: 4 | methods: 5 | XRPMotor: 6 | Set: 7 | Get: 8 | SetInverted: 9 | GetInverted: 10 | Disable: 11 | StopMotor: 12 | GetDescription: 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/semiwrap/XRPOnBoardIO.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::XRPOnBoardIO: 4 | attributes: 5 | kMessageInterval: 6 | m_nextMessageTime: 7 | methods: 8 | XRPOnBoardIO: 9 | GetUserButtonPressed: 10 | SetLed: 11 | GetLed: 12 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/semiwrap/XRPRangefinder.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::XRPRangefinder: 4 | methods: 5 | GetDistance: 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/semiwrap/XRPReflectanceSensor.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::XRPReflectanceSensor: 4 | methods: 5 | GetLeftReflectanceValue: 6 | GetRightReflectanceValue: 7 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/semiwrap/XRPServo.yml: -------------------------------------------------------------------------------- 1 | 2 | classes: 3 | frc::XRPServo: 4 | methods: 5 | XRPServo: 6 | SetAngle: 7 | GetAngle: 8 | SetPosition: 9 | GetPosition: 10 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/tests/requirements.txt: -------------------------------------------------------------------------------- 1 | pytest 2 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/tests/run_tests.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | from os.path import abspath, dirname 5 | import sys 6 | import subprocess 7 | 8 | if __name__ == "__main__": 9 | root = abspath(dirname(__file__)) 10 | os.chdir(root) 11 | 12 | subprocess.check_call([sys.executable, "-m", "pytest"]) 13 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/tests/test_xrp.py: -------------------------------------------------------------------------------- 1 | import xrp 2 | 3 | 4 | def test_xrp(): 5 | pass 6 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/xrp/__init__.py: -------------------------------------------------------------------------------- 1 | from . import _init__xrp 2 | 3 | # autogenerated by 'semiwrap create-imports xrp xrp._xrp' 4 | from ._xrp import ( 5 | XRPGyro, 6 | XRPMotor, 7 | XRPOnBoardIO, 8 | XRPRangefinder, 9 | XRPReflectanceSensor, 10 | XRPServo, 11 | ) 12 | 13 | __all__ = [ 14 | "XRPGyro", 15 | "XRPMotor", 16 | "XRPOnBoardIO", 17 | "XRPRangefinder", 18 | "XRPReflectanceSensor", 19 | "XRPServo", 20 | ] 21 | 22 | del _init__xrp 23 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/xrp/extension/__init__.py: -------------------------------------------------------------------------------- 1 | from .main import loadExtension 2 | 3 | __all__ = ["loadExtension"] 4 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/xrp/extension/main.py: -------------------------------------------------------------------------------- 1 | import logging 2 | import os 3 | from os.path import abspath, dirname, join 4 | 5 | logger = logging.getLogger("xrp.extension") 6 | 7 | 8 | def loadExtension(): 9 | try: 10 | import hal 11 | except ImportError as e: 12 | # really, should never happen... 13 | raise ImportError("you must install robotpy-hal!") from e 14 | 15 | from ..version import version 16 | 17 | logger.info("WPILib XRP client %s", version) 18 | 19 | root = join(abspath(dirname(__file__)), "lib") 20 | ext = join(root, os.listdir(root)[0]) 21 | retval = hal.loadOneExtension(ext) 22 | if retval != 0: 23 | logger.warn("loading extension may have failed (error=%d)", retval) 24 | -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/xrp/py.typed: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/robotpy/mostrobotpy/becf4b1f17190c00792312a0f68d1adee6fcbe8b/subprojects/robotpy-xrp/xrp/py.typed -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/xrp/src/main.cpp: -------------------------------------------------------------------------------- 1 | 2 | #include 3 | 4 | SEMIWRAP_PYBIND11_MODULE(m) { 5 | initWrapper(m); 6 | } -------------------------------------------------------------------------------- /subprojects/robotpy-xrp/xrp/xrp.pc: -------------------------------------------------------------------------------- 1 | # automatically generated by semiwrap.cmd_gen_pkgconf 2 | prefix=${pcfiledir} 3 | pkgconf_pypi_initpy=xrp._init__xrp 4 | 5 | Name: xrp 6 | Description: semiwrap pybind11 module 7 | Version: 8 | Cflags: -I${prefix} 9 | Requires: robotpy-native-xrp wpilib wpimath_geometry 10 | --------------------------------------------------------------------------------