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:
@@ -0,0 +1,34 @@
|
||||
#
|
||||
# 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 typing
|
||||
import commands2
|
||||
from subsystems.drivetrain import Drivetrain
|
||||
|
||||
|
||||
class ArcadeDrive(commands2.Command):
|
||||
def __init__(
|
||||
self,
|
||||
drive: Drivetrain,
|
||||
forward: typing.Callable[[], float],
|
||||
rotation: typing.Callable[[], float],
|
||||
) -> None:
|
||||
"""Creates a new ArcadeDrive. This command will drive your robot according to the velocity supplier
|
||||
lambdas. This command does not terminate.
|
||||
|
||||
:param drivetrain: The drivetrain subsystem on which this command will run
|
||||
:param forward: Callable supplier of forward/backward velocity
|
||||
:param rotation: Callable supplier of rotational velocity
|
||||
"""
|
||||
|
||||
self.drive = drive
|
||||
self.forward = forward
|
||||
self.rotation = rotation
|
||||
|
||||
self.addRequirements(self.drive)
|
||||
|
||||
def execute(self) -> None:
|
||||
self.drive.arcadeDrive(self.forward(), self.rotation())
|
||||
@@ -0,0 +1,28 @@
|
||||
#
|
||||
# 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 commands2
|
||||
|
||||
from commands.drivedistance import DriveDistance
|
||||
from commands.turndegrees import TurnDegrees
|
||||
from subsystems.drivetrain import Drivetrain
|
||||
|
||||
|
||||
class AutonomousDistance(commands2.SequentialCommandGroup):
|
||||
def __init__(self, drive: Drivetrain) -> None:
|
||||
"""Creates a new Autonomous Drive based on distance. This will drive out for a specified distance,
|
||||
turn around and drive back.
|
||||
|
||||
:param drivetrain: The drivetrain subsystem on which this command will run
|
||||
"""
|
||||
super().__init__()
|
||||
|
||||
self.addCommands(
|
||||
DriveDistance(-0.5, 10, drive),
|
||||
TurnDegrees(-0.5, 180, drive),
|
||||
DriveDistance(-0.5, 10, drive),
|
||||
TurnDegrees(0.5, 180, drive),
|
||||
)
|
||||
@@ -0,0 +1,30 @@
|
||||
#
|
||||
# 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 commands2
|
||||
|
||||
from commands.drivetime import DriveTime
|
||||
from commands.turntime import TurnTime
|
||||
from subsystems.drivetrain import Drivetrain
|
||||
|
||||
|
||||
class AutonomousTime(commands2.SequentialCommandGroup):
|
||||
def __init__(self, drive: Drivetrain) -> None:
|
||||
"""Creates a new Autonomous Drive based on time. This will drive out for a period of time, turn
|
||||
around for time (equivalent to time to turn around) and drive forward again. This should mimic
|
||||
driving out, turning around and driving back.
|
||||
|
||||
:param drivetrain: The drive subsystem on which this command will run
|
||||
|
||||
"""
|
||||
super().__init__()
|
||||
|
||||
self.addCommands(
|
||||
DriveTime(-0.6, 2.0, drive),
|
||||
TurnTime(-0.5, 1.3, drive),
|
||||
DriveTime(-0.6, 2.0, drive),
|
||||
TurnTime(0.5, 1.3, drive),
|
||||
)
|
||||
@@ -0,0 +1,43 @@
|
||||
#
|
||||
# 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 commands2
|
||||
|
||||
from subsystems.drivetrain import Drivetrain
|
||||
|
||||
|
||||
class DriveDistance(commands2.Command):
|
||||
def __init__(self, velocity: float, inches: float, drive: Drivetrain) -> None:
|
||||
"""Creates a new DriveDistance. This command will drive your your robot for a desired distance at
|
||||
a desired velocity.
|
||||
|
||||
:param velocity: The velocity at which the robot will drive
|
||||
:param inches: The number of inches the robot will drive
|
||||
:param drive: The drivetrain subsystem on which this command will run
|
||||
"""
|
||||
|
||||
self.distance = inches
|
||||
self.velocity = velocity
|
||||
self.drive = drive
|
||||
self.addRequirements(drive)
|
||||
|
||||
def initialize(self) -> None:
|
||||
"""Called when the command is initially scheduled."""
|
||||
self.drive.arcadeDrive(0, 0)
|
||||
self.drive.resetEncoders()
|
||||
|
||||
def execute(self) -> None:
|
||||
"""Called every time the scheduler runs while the command is scheduled."""
|
||||
self.drive.arcadeDrive(self.velocity, 0)
|
||||
|
||||
def end(self, interrupted: bool) -> None:
|
||||
"""Called once the command ends or is interrupted."""
|
||||
self.drive.arcadeDrive(0, 0)
|
||||
|
||||
def isFinished(self) -> bool:
|
||||
"""Returns true when the command should end."""
|
||||
# Compare distance travelled from start to desired distance
|
||||
return abs(self.drive.getAverageDistanceInch()) >= self.distance
|
||||
46
robotpyExamples/examples/RomiReference/commands/drivetime.py
Normal file
46
robotpyExamples/examples/RomiReference/commands/drivetime.py
Normal file
@@ -0,0 +1,46 @@
|
||||
#
|
||||
# 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 commands2
|
||||
import wpilib
|
||||
|
||||
from subsystems.drivetrain import Drivetrain
|
||||
|
||||
|
||||
class DriveTime(commands2.Command):
|
||||
"""Creates a new DriveTime. This command will drive your robot for a desired velocity and time."""
|
||||
|
||||
def __init__(self, velocity: float, time: float, drive: Drivetrain) -> None:
|
||||
"""Creates a new DriveTime. This command will drive your robot for a desired velocity and time.
|
||||
|
||||
:param velocity: The velocity which the robot will drive. Negative is in reverse.
|
||||
:param time: How much time to drive in seconds
|
||||
:param drive: The drivetrain subsystem on which this command will run
|
||||
"""
|
||||
|
||||
self.velocity = velocity
|
||||
self.duration = time
|
||||
self.drive = drive
|
||||
self.addRequirements(drive)
|
||||
|
||||
self.startTime = 0.0
|
||||
|
||||
def initialize(self) -> None:
|
||||
"""Called when the command is initially scheduled."""
|
||||
self.startTime = wpilib.Timer.getTimestamp()
|
||||
self.drive.arcadeDrive(0, 0)
|
||||
|
||||
def execute(self) -> None:
|
||||
"""Called every time the scheduler runs while the command is scheduled."""
|
||||
self.drive.arcadeDrive(self.velocity, 0)
|
||||
|
||||
def end(self, interrupted: bool) -> None:
|
||||
"""Called once the command ends or is interrupted."""
|
||||
self.drive.arcadeDrive(0, 0)
|
||||
|
||||
def isFinished(self) -> bool:
|
||||
"""Returns true when the command should end"""
|
||||
return wpilib.Timer.getTimestamp() - self.startTime >= self.duration
|
||||
@@ -0,0 +1,57 @@
|
||||
#
|
||||
# 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 math
|
||||
import commands2
|
||||
|
||||
from subsystems.drivetrain import Drivetrain
|
||||
|
||||
|
||||
class TurnDegrees(commands2.Command):
|
||||
def __init__(self, velocity: float, degrees: float, drive: Drivetrain) -> None:
|
||||
"""Creates a new TurnDegrees. This command will turn your robot for a desired rotation (in
|
||||
degrees) and rotational velocity.
|
||||
|
||||
:param velocity: The velocity which the robot will drive. Negative is in reverse.
|
||||
:param degrees: Degrees to turn. Leverages encoders to compare distance.
|
||||
:param drive: The drive subsystem on which this command will run
|
||||
"""
|
||||
|
||||
self.degrees = degrees
|
||||
self.velocity = velocity
|
||||
self.drive = drive
|
||||
self.addRequirements(drive)
|
||||
|
||||
def initialize(self) -> None:
|
||||
"""Called when the command is initially scheduled."""
|
||||
# Set motors to stop, read encoder values for starting point
|
||||
self.drive.arcadeDrive(0, 0)
|
||||
self.drive.resetEncoders()
|
||||
|
||||
def execute(self) -> None:
|
||||
"""Called every time the scheduler runs while the command is scheduled."""
|
||||
self.drive.arcadeDrive(0, self.velocity)
|
||||
|
||||
def end(self, interrupted: bool) -> None:
|
||||
"""Called once the command ends or is interrupted."""
|
||||
self.drive.arcadeDrive(0, 0)
|
||||
|
||||
def isFinished(self) -> bool:
|
||||
"""Returns true when the command should end."""
|
||||
|
||||
# Need to convert distance travelled to degrees. The Standard
|
||||
# Romi Chassis found here, https://www.pololu.com/category/203/romi-chassis-kits,
|
||||
# has a wheel placement diameter (149 mm) - width of the wheel (8 mm) = 141 mm
|
||||
# or 5.551 inches. We then take into consideration the width of the tires.
|
||||
inchPerDegree = math.pi * 5.551 / 360.0
|
||||
|
||||
# Compare distance travelled from start to distance based on degree turn
|
||||
return self._getAverageTurningDistance() >= inchPerDegree * self.degrees
|
||||
|
||||
def _getAverageTurningDistance(self) -> float:
|
||||
leftDistance = abs(self.drive.getLeftDistanceInch())
|
||||
rightDistance = abs(self.drive.getRightDistanceInch())
|
||||
return (leftDistance + rightDistance) / 2.0
|
||||
48
robotpyExamples/examples/RomiReference/commands/turntime.py
Normal file
48
robotpyExamples/examples/RomiReference/commands/turntime.py
Normal file
@@ -0,0 +1,48 @@
|
||||
#
|
||||
# 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 commands2
|
||||
import wpilib
|
||||
|
||||
from subsystems.drivetrain import Drivetrain
|
||||
|
||||
|
||||
class TurnTime(commands2.Command):
|
||||
"""Creates a new TurnTime command. This command will turn your robot for a
|
||||
desired rotational velocity and time.
|
||||
"""
|
||||
|
||||
def __init__(self, velocity: float, time: float, drive: Drivetrain) -> None:
|
||||
"""Creates a new TurnTime.
|
||||
|
||||
:param velocity: The velocity which the robot will turn. Negative is in reverse.
|
||||
:param time: How much time to turn in seconds
|
||||
:param drive: The drive subsystem on which this command will run
|
||||
"""
|
||||
|
||||
self.rotationalVelocity = velocity
|
||||
self.duration = time
|
||||
self.drive = drive
|
||||
self.addRequirements(drive)
|
||||
|
||||
self.startTime = 0.0
|
||||
|
||||
def initialize(self) -> None:
|
||||
"""Called when the command is initially scheduled."""
|
||||
self.startTime = wpilib.Timer.getTimestamp()
|
||||
self.drive.arcadeDrive(0, 0)
|
||||
|
||||
def execute(self) -> None:
|
||||
"""Called every time the scheduler runs while the command is scheduled."""
|
||||
self.drive.arcadeDrive(0, self.rotationalVelocity)
|
||||
|
||||
def end(self, interrupted: bool) -> None:
|
||||
"""Called once the command ends or is interrupted."""
|
||||
self.drive.arcadeDrive(0, 0)
|
||||
|
||||
def isFinished(self) -> bool:
|
||||
"""Returns true when the command should end"""
|
||||
return wpilib.Timer.getTimestamp() - self.startTime >= self.duration
|
||||
97
robotpyExamples/examples/RomiReference/robot.py
Normal file
97
robotpyExamples/examples/RomiReference/robot.py
Normal file
@@ -0,0 +1,97 @@
|
||||
#!/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.
|
||||
#
|
||||
|
||||
#
|
||||
# Example that shows how to connect to a ROMI from RobotPy
|
||||
#
|
||||
# Requirements
|
||||
# ------------
|
||||
#
|
||||
# You must have the robotpy-halsim-ws package installed. This is best done via:
|
||||
#
|
||||
# # Windows
|
||||
# py -3 -m pip install robotpy[commands2,sim]
|
||||
#
|
||||
# # Linux/macOS
|
||||
# pip3 install robotpy[commands2,sim]
|
||||
#
|
||||
# Run the program
|
||||
# ---------------
|
||||
#
|
||||
# Use the dedicated ROMI command:
|
||||
#
|
||||
# # Windows
|
||||
# py -3 -m robotpy run-romi
|
||||
#
|
||||
# # Linux/macOS
|
||||
# python -m robotpy run-romi
|
||||
#
|
||||
# If your ROMI isn't at the default address, use --host/--port:
|
||||
#
|
||||
# python -m robotpy run-romi --host 10.0.0.2 --port 3300
|
||||
#
|
||||
# By default the WPILib simulation GUI will be displayed. To disable the display
|
||||
# you can add the --nogui option.
|
||||
#
|
||||
|
||||
import typing
|
||||
|
||||
import wpilib
|
||||
import commands2
|
||||
|
||||
from robotcontainer import RobotContainer
|
||||
|
||||
|
||||
class MyRobot(commands2.TimedCommandRobot):
|
||||
"""
|
||||
Command v2 robots are encouraged to inherit from TimedCommandRobot, which
|
||||
has an implementation of robotPeriodic which runs the scheduler for you
|
||||
"""
|
||||
|
||||
autonomousCommand: typing.Optional[commands2.Command] = None
|
||||
|
||||
def __init__(self) -> None:
|
||||
"""
|
||||
This function is run when the robot is first started up and should be used for any
|
||||
initialization code.
|
||||
"""
|
||||
|
||||
super().__init__()
|
||||
# Instantiate our RobotContainer. This will perform all our button bindings, and put our
|
||||
# autonomous chooser on the dashboard.
|
||||
self.container = RobotContainer()
|
||||
|
||||
def disabledInit(self) -> None:
|
||||
"""This function is called once each time the robot enters Disabled mode."""
|
||||
|
||||
def disabledPeriodic(self) -> None:
|
||||
"""This function is called periodically when disabled"""
|
||||
|
||||
def autonomousInit(self) -> None:
|
||||
"""This autonomous runs the autonomous command selected by your RobotContainer class."""
|
||||
self.autonomousCommand = self.container.getAutonomousCommand()
|
||||
|
||||
if self.autonomousCommand:
|
||||
self.autonomousCommand.schedule()
|
||||
|
||||
def autonomousPeriodic(self) -> None:
|
||||
"""This function is called periodically during autonomous"""
|
||||
|
||||
def teleopInit(self) -> None:
|
||||
# This makes sure that the autonomous stops running when
|
||||
# teleop starts running. If you want the autonomous to
|
||||
# continue until interrupted by another command, remove
|
||||
# this line or comment it out.
|
||||
if self.autonomousCommand:
|
||||
self.autonomousCommand.cancel()
|
||||
|
||||
def teleopPeriodic(self) -> None:
|
||||
"""This function is called periodically during operator control"""
|
||||
|
||||
def utilityInit(self) -> None:
|
||||
# Cancels all running commands at the start of utility mode
|
||||
commands2.CommandScheduler.getInstance().cancelAll()
|
||||
90
robotpyExamples/examples/RomiReference/robotcontainer.py
Normal file
90
robotpyExamples/examples/RomiReference/robotcontainer.py
Normal file
@@ -0,0 +1,90 @@
|
||||
#
|
||||
# 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 typing
|
||||
|
||||
import commands2
|
||||
import commands2.button
|
||||
import wpilib
|
||||
import romi
|
||||
|
||||
from commands.arcadedrive import ArcadeDrive
|
||||
from commands.autonomousdistance import AutonomousDistance
|
||||
from commands.autonomoustime import AutonomousTime
|
||||
|
||||
from subsystems.drivetrain import Drivetrain
|
||||
|
||||
|
||||
class RobotContainer:
|
||||
"""
|
||||
This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
"declarative" paradigm, very little robot logic should actually be handled in the :class:`.Robot`
|
||||
periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
|
||||
subsystems, commands, and button mappings) should be declared here.
|
||||
"""
|
||||
|
||||
def __init__(self) -> None:
|
||||
# The robot's subsystems and commands are defined here...
|
||||
self.drivetrain = Drivetrain()
|
||||
self.onboardIO = romi.OnBoardIO(
|
||||
romi.OnBoardIO.ChannelMode.INPUT, romi.OnBoardIO.ChannelMode.INPUT
|
||||
)
|
||||
|
||||
# Assumes a gamepad plugged into channnel 0
|
||||
self.controller = wpilib.Joystick(0)
|
||||
|
||||
# Create SmartDashboard chooser for autonomous routines
|
||||
self.chooser = wpilib.SendableChooser()
|
||||
|
||||
# NOTE: The I/O pin functionality of the 5 exposed I/O pins depends on the hardware "overlay"
|
||||
# that is specified when launching the wpilib-ws server on the Romi raspberry pi.
|
||||
# By default, the following are available (listed in order from inside of the board to outside):
|
||||
# - DIO 8 (mapped to Arduino pin 11, closest to the inside of the board)
|
||||
# - Analog In 0 (mapped to Analog Channel 6 / Arduino Pin 4)
|
||||
# - Analog In 1 (mapped to Analog Channel 2 / Arduino Pin 20)
|
||||
# - PWM 2 (mapped to Arduino Pin 21)
|
||||
# - PWM 3 (mapped to Arduino Pin 22)
|
||||
#
|
||||
# Your subsystem configuration should take the overlays into account
|
||||
|
||||
self._configureButtonBindings()
|
||||
|
||||
def _configureButtonBindings(self):
|
||||
"""Use this method to define your button->command mappings. Buttons can be created by
|
||||
instantiating a :class:`.GenericHID` or one of its subclasses (:class`.Joystick or
|
||||
:class:`.XboxController`), and then passing it to a :class:`.JoystickButton`.
|
||||
"""
|
||||
|
||||
# Default command is arcade drive. This will run unless another command
|
||||
# is scheduler over it
|
||||
self.drivetrain.setDefaultCommand(self.getArcadeDriveCommand())
|
||||
|
||||
# Example of how to use the onboard IO
|
||||
onboardButtonA = commands2.button.Trigger(self.onboardIO.getButtonAPressed)
|
||||
onboardButtonA.onTrue(commands2.PrintCommand("Button A Pressed")).onFalse(
|
||||
commands2.PrintCommand("Button A Released")
|
||||
)
|
||||
|
||||
# Setup SmartDashboard options
|
||||
self.chooser.setDefaultOption(
|
||||
"Auto Routine Distance", AutonomousDistance(self.drivetrain)
|
||||
)
|
||||
self.chooser.addOption("Auto Routine Time", AutonomousTime(self.drivetrain))
|
||||
wpilib.SmartDashboard.putData(self.chooser)
|
||||
|
||||
def getAutonomousCommand(self) -> typing.Optional[commands2.Command]:
|
||||
return self.chooser.getSelected()
|
||||
|
||||
def getArcadeDriveCommand(self) -> ArcadeDrive:
|
||||
"""Use this to pass the teleop command to the main robot class.
|
||||
|
||||
:returns: the command to run in teleop
|
||||
"""
|
||||
return ArcadeDrive(
|
||||
self.drivetrain,
|
||||
lambda: -self.controller.getRawAxis(1),
|
||||
lambda: -self.controller.getRawAxis(2),
|
||||
)
|
||||
103
robotpyExamples/examples/RomiReference/subsystems/drivetrain.py
Normal file
103
robotpyExamples/examples/RomiReference/subsystems/drivetrain.py
Normal file
@@ -0,0 +1,103 @@
|
||||
#
|
||||
# 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 math
|
||||
|
||||
import commands2
|
||||
import wpilib
|
||||
import romi
|
||||
|
||||
|
||||
class Drivetrain(commands2.Subsystem):
|
||||
kCountsPerRevolution = 1440.0
|
||||
kWheelDiameterInch = 2.75591
|
||||
|
||||
def __init__(self) -> None:
|
||||
|
||||
# The Romi has the left and right motors set to
|
||||
# PWM channels 0 and 1 respectively
|
||||
self.leftMotor = wpilib.Spark(0)
|
||||
self.rightMotor = wpilib.Spark(1)
|
||||
|
||||
# We need to invert one side of the drivetrain so that positive voltages
|
||||
# result in both sides moving forward. Depending on how your robot's
|
||||
# gearbox is constructed, you might have to invert the left side instead.
|
||||
self.rightMotor.setInverted(True)
|
||||
|
||||
# The Romi has onboard encoders that are hardcoded
|
||||
# to use DIO pins 4/5 and 6/7 for the left and right
|
||||
self.leftEncoder = wpilib.Encoder(4, 5)
|
||||
self.rightEncoder = wpilib.Encoder(6, 7)
|
||||
|
||||
# Set up the differential drive controller
|
||||
self.drive = wpilib.DifferentialDrive(self.leftMotor, self.rightMotor)
|
||||
|
||||
# Set up the RomiGyro
|
||||
self.gyro = romi.RomiGyro()
|
||||
|
||||
# Use inches as unit for encoder distances
|
||||
self.leftEncoder.setDistancePerPulse(
|
||||
(math.pi * self.kWheelDiameterInch) / self.kCountsPerRevolution
|
||||
)
|
||||
self.rightEncoder.setDistancePerPulse(
|
||||
(math.pi * self.kWheelDiameterInch) / self.kCountsPerRevolution
|
||||
)
|
||||
self.resetEncoders()
|
||||
|
||||
def arcadeDrive(self, fwd: float, rot: float) -> None:
|
||||
"""
|
||||
Drives the robot using arcade controls.
|
||||
|
||||
:param fwd: the commanded forward movement
|
||||
:param rot: the commanded rotation
|
||||
"""
|
||||
self.drive.arcadeDrive(fwd, rot)
|
||||
|
||||
def resetEncoders(self) -> None:
|
||||
"""Resets the drive encoders to currently read a position of 0."""
|
||||
self.leftEncoder.reset()
|
||||
self.rightEncoder.reset()
|
||||
|
||||
def getLeftEncoderCount(self) -> int:
|
||||
return self.leftEncoder.get()
|
||||
|
||||
def getRightEncoderCount(self) -> int:
|
||||
return self.rightEncoder.get()
|
||||
|
||||
def getLeftDistanceInch(self) -> float:
|
||||
return self.leftEncoder.getDistance()
|
||||
|
||||
def getRightDistanceInch(self) -> float:
|
||||
return self.rightEncoder.getDistance()
|
||||
|
||||
def getAverageDistanceInch(self) -> float:
|
||||
"""Gets the average distance of the TWO encoders."""
|
||||
return (self.getLeftDistanceInch() + self.getRightDistanceInch()) / 2.0
|
||||
|
||||
def getGyroAngleX(self) -> float:
|
||||
"""Current angle of the Romi around the X-axis.
|
||||
|
||||
:returns: The current angle of the Romi in degrees
|
||||
"""
|
||||
return self.gyro.getAngleX()
|
||||
|
||||
def getGyroAngleY(self) -> float:
|
||||
"""Current angle of the Romi around the Y-axis.
|
||||
|
||||
:returns: The current angle of the Romi in degrees
|
||||
"""
|
||||
return self.gyro.getAngleY()
|
||||
|
||||
def getGyroAngleZ(self) -> float:
|
||||
"""Current angle of the Romi around the Z-axis.
|
||||
|
||||
:returns: The current angle of the Romi in degrees
|
||||
"""
|
||||
return self.gyro.getAngleZ()
|
||||
|
||||
def resetGyro(self) -> None:
|
||||
"""Reset the gyro"""
|
||||
self.gyro.reset()
|
||||
Reference in New Issue
Block a user