mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[robotpy][examples] Split examples and snippets (#8944)
This also updates the bazel scripts to behave more like the C++ and Java examples, and updates the copybara scripts to be able to sync up `mostrobotpy`
This commit is contained in:
63
robotpyExamples/examples/SwerveBot/robot.py
Normal file
63
robotpyExamples/examples/SwerveBot/robot.py
Normal file
@@ -0,0 +1,63 @@
|
||||
#!/usr/bin/env python3
|
||||
#
|
||||
# Copyright (c) FIRST and other WPILib contributors.
|
||||
# Open Source Software; you can modify and/or share it under the terms of
|
||||
# the WPILib BSD license file in the root directory of this project.
|
||||
#
|
||||
|
||||
import wpilib
|
||||
import wpimath
|
||||
import drivetrain
|
||||
|
||||
|
||||
class MyRobot(wpilib.TimedRobot):
|
||||
def __init__(self) -> None:
|
||||
"""Robot initialization function"""
|
||||
super().__init__()
|
||||
self.controller = wpilib.NiDsXboxController(0)
|
||||
self.swerve = drivetrain.Drivetrain()
|
||||
|
||||
# Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 to 1.
|
||||
self.xvelocityLimiter = wpimath.SlewRateLimiter(3)
|
||||
self.yvelocityLimiter = wpimath.SlewRateLimiter(3)
|
||||
self.rotLimiter = wpimath.SlewRateLimiter(3)
|
||||
|
||||
def autonomousPeriodic(self) -> None:
|
||||
self.driveWithJoystick(False)
|
||||
self.swerve.updateOdometry()
|
||||
|
||||
def teleopPeriodic(self) -> None:
|
||||
self.driveWithJoystick(True)
|
||||
|
||||
def driveWithJoystick(self, fieldRelative: bool) -> None:
|
||||
# Get the x velocity. We are inverting this because Xbox controllers return
|
||||
# negative values when we push forward.
|
||||
xVelocity = (
|
||||
-self.xvelocityLimiter.calculate(
|
||||
wpimath.applyDeadband(self.controller.getLeftY(), 0.02)
|
||||
)
|
||||
* drivetrain.kMaxVelocity
|
||||
)
|
||||
|
||||
# Get the y velocity or sideways/strafe velocity. We are inverting this because
|
||||
# we want a positive value when we pull to the left. Xbox controllers
|
||||
# return positive values when you pull to the right by default.
|
||||
yVelocity = (
|
||||
-self.yvelocityLimiter.calculate(
|
||||
wpimath.applyDeadband(self.controller.getLeftX(), 0.02)
|
||||
)
|
||||
* drivetrain.kMaxVelocity
|
||||
)
|
||||
|
||||
# Get the rate of angular rotation. We are inverting this because we want a
|
||||
# positive value when we pull to the left (remember, CCW is positive in
|
||||
# mathematics). Xbox controllers return positive values when you pull to
|
||||
# the right by default.
|
||||
rot = (
|
||||
-self.rotLimiter.calculate(
|
||||
wpimath.applyDeadband(self.controller.getRightX(), 0.02)
|
||||
)
|
||||
* drivetrain.kMaxAngularVelocity
|
||||
)
|
||||
|
||||
self.swerve.drive(xVelocity, yVelocity, rot, fieldRelative, self.getPeriod())
|
||||
Reference in New Issue
Block a user