Skip to content
Merged
26 changes: 3 additions & 23 deletions external_samples/color_range_sensor.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
# @fileoverview This is a sample for a color/range sensor
# @author [email protected] (Alan Smith)

from typing import Protocol, Self
from component import Component, InvalidPortException
from typing import Protocol
from component import Component
from port import Port, PortType

class DistanceCallable(Protocol):
Expand All @@ -32,29 +32,9 @@ def __call__(self, hue : int, saturation : int, value : int) -> None:

class ColorRangeSensor(Component):
def __init__(self, port : Port):
'''REV Robotics Color Sensor v3. Part number REV-31-1557. https://www.revrobotics.com/rev-31-1557'''
super().__init__( port, expectedType = PortType.I2C_PORT)

def get_manufacturer(self) -> str:
return "REV Robotics"

def get_name(self) -> str:
return "Color Sensor v3"

def get_part_number(self) -> str:
return "REV-31-1557"

def get_url(self) -> str:
return "https://www.revrobotics.com/rev-31-1557"

def get_version(self) -> tuple[int, int, int]:
return (1, 0, 0)

def reset(self) -> None:
pass

def periodic(self) -> None:
pass

# Component specific methods

def get_color_rgb(self) -> tuple[int, int, int]:
Expand Down
49 changes: 5 additions & 44 deletions external_samples/component.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
# @fileoverview This is an abstract class for all components
# @author [email protected] (Alan Smith)

from abc import ABC, abstractmethod
from abc import ABC
from typing import Protocol
from port import Port, PortType

Expand All @@ -38,57 +38,18 @@ def __init__(self, port : Port, expectedType : PortType):

self.port = port

# Returns the manufacturer of the component
@abstractmethod
def get_manufacturer(self) -> str:
def opmode_start(self) -> None:
pass

# Returns the name of the component
@abstractmethod
def get_name(self) -> str:
def opmode_periodic(self) -> None:
pass

# Returns the part number of the component
@abstractmethod
def get_part_number(self) -> str:
pass

# Returns the URL of the component
@abstractmethod
def get_url(self) -> str:
pass

# Returns the version of the software (returned as a (major, minor, patch) tuple where
# major, minor and patch are all positive integers
# This MUST follow semantic versioning as described here: https://semver.org/
@abstractmethod
def get_version(self) -> tuple[int, int, int]:
pass

def start(self) -> None:
pass

def update(self) -> None:
pass

# This stops all movement (if any) for the component
def stop(self) -> None:
pass

# This performs any reset required (if any) at the beginning of each opmode
# This might remove any registered callbacks
@abstractmethod
def reset(self) -> None:
# Subclasses should override opmode_end to stop all movement (if any) for the component
def opmode_end(self) -> None:
pass

# Returns the port this connects to of the PortType enumeration
def get_connection_port_type(self) -> PortType | None:
if self.port:
return self.port.get_type()
return None

# This is called periodically when an opmode is running. The component might use this
# to talk to hardware and then call callbacks
@abstractmethod
def periodic(self) -> None:
pass
33 changes: 4 additions & 29 deletions external_samples/expansion_hub_motor.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,45 +20,20 @@

__author__ = "[email protected] (Liz Looney)"

from typing import Self
from component import Component, InvalidPortException
from component import Component
from port import Port, PortType
import expansion_hub
from wpilib_placeholders import expansion_hub
import wpimath

class ExpansionHubMotor(Component):
def __init__(self, port : Port):
'''REV Robotics Expansion Hub Motor'''
super().__init__(port, PortType.EXPANSION_HUB_MOTOR)
self.expansion_hub_motor = expansion_hub.ExpansionHubMotor(self.port.port1.location, self.port.port2.location)

def get_manufacturer(self) -> str:
return "REV Robotics"

def get_name(self) -> str:
return "Expansion Hub Motor"

def get_part_number(self) -> str:
return ""

def get_url(self) -> str:
return ""

def get_version(self) -> tuple[int, int, int]:
return (1, 0, 0)

def start(self) -> None:
def opmode_start(self) -> None:
self.expansion_hub_motor.setEnabled(True)

def stop(self) -> None:
# TODO: Send stop command to motor.
pass

def reset(self) -> None:
pass

def periodic(self) -> None:
pass

# Component specific methods

# Methods from expansion_hub.ExpansionHubMotor
Expand Down
40 changes: 6 additions & 34 deletions external_samples/expansion_hub_servo.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,47 +20,19 @@

__author__ = "[email protected] (Liz Looney)"

from typing import Self
from component import Component, PortType, InvalidPortException
from component import Component
from port import Port, PortType
import expansion_hub
from wpilib_placeholders import expansion_hub
import wpimath

class ExpansionHubServo(Component):
def __init__(self, port : Port):
'''REV Robotics Expansion Hub Servo'''
super().__init__(port, PortType.EXPANSION_HUB_SERVO)
self.expansion_hub_servo = expansion_hub.ExpansionHubServo(self.port.port1.location, self.port.port2.location)

def get_manufacturer(self) -> str:
return "REV Robotics"

def get_name(self) -> str:
return "Expansion Hub Servo"

def get_part_number(self) -> str:
return ""

def get_url(self) -> str:
return ""

def get_version(self) -> tuple[int, int, int]:
return (1, 0, 0)

def start(self) -> None:
def opmode_start(self) -> None:
self.expansion_hub_servo.setEnabled(True)
pass

def stop(self) -> None:
# TODO: Send stop command to servo.
pass

def reset(self) -> None:
pass

def get_connection_port_type(self) -> list[PortType]:
return [PortType.USB_PORT, PortType.USB_PORT]

def periodic(self) -> None:
pass

# Component specific methods

Expand All @@ -78,7 +50,7 @@ def setEnabled(self, enabled: bool):
def isHubConnected(self) -> bool:
return self.expansion_hub_servo.isHubConnected()

def setFramePeriod(self, framePeriod: int):
def setFramePeriod(self, framePeriod: wpimath.units.microseconds):
self.expansion_hub_servo.setFramePeriod(framePeriod)

def setPulseWidth(self, pulseWidth: int):
Expand Down
2 changes: 1 addition & 1 deletion external_samples/port.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
# @author [email protected] (Alan Smith)
from abc import ABC, abstractmethod
from enum import Enum
from typing import Final, Self
from typing import Final

_BASE_COMPOUND: Final[int] = 256

Expand Down
26 changes: 5 additions & 21 deletions external_samples/rev_touch_sensor.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,36 +16,20 @@
# @fileoverview This is a sample for a touch sensor
# @author [email protected] (Alan Smith)

from typing import Self
from component import Component, PortType, InvalidPortException, EmptyCallable
from component import Component, EmptyCallable
from port import Port, PortType

class RevTouchSensor(Component):
def __init__(self, port : Port):
'''REV Robotics Touch Sensor. Part number REV-31-1425. https://www.revrobotics.com/rev-31-1425'''
super().__init__(port, PortType.SMART_IO_PORT)
self._is_pressed = None

def get_manufacturer(self) -> str:
return "REV Robotics"

def get_name(self) -> str:
return "Touch Sensor"

def get_part_number(self) -> str:
return "REV-31-1425"

def get_url(self) -> str:
return "https://www.revrobotics.com/rev-31-1425/"

def get_version(self) -> tuple[int, int, int]:
return (1, 0, 0)

def reset(self) -> None:
def opmode_stop(self) -> None:
self.pressed_callback = None
self.released_callback = None
pass

def periodic(self) -> None:
def opmode_periodic(self) -> None:
old = self._is_pressed
self._read_hardware()
if old != self._is_pressed:
Expand All @@ -57,7 +41,7 @@ def periodic(self) -> None:
# Component specific methods

def _read_hardware(self):
# here read hardware to get the current value of the sensor and set self._is_pressed
# TODO: Read hardware to get the current value of the sensor and set self._is_pressed
pass

def is_pressed(self) -> bool:
Expand Down
11 changes: 2 additions & 9 deletions external_samples/smart_motor.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,7 @@
# @fileoverview This is a sample for a smart motor
# @author [email protected] (Alan Smith)

from typing import Self
from component import Component, PortType, InvalidPortException
from component import Component
from port import Port, PortType

class SmartMotor(Component):
Expand All @@ -39,16 +38,10 @@ def get_url(self) -> str:
def get_version(self) -> tuple[int, int, int]:
return (1, 0, 0)

def stop(self) -> None:
def opmode_end(self) -> None:
# TODO: send stop command to motor
pass

def reset(self) -> None:
pass

def periodic(self) -> None:
pass

# Component specific methods

def set_speed(self, speed: float) -> None:
Expand Down
11 changes: 2 additions & 9 deletions external_samples/spark_mini.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,7 @@

__author__ = "[email protected] (Liz Looney)"

from typing import Self
from component import Component, PortType, InvalidPortException
from component import Component
from port import Port, PortType

import wpilib
Expand Down Expand Up @@ -51,16 +50,10 @@ def get_url(self) -> str:
def get_version(self) -> tuple[int, int, int]:
return (1, 0, 0)

def stop(self) -> None:
def opmode_end(self) -> None:
# TODO: send stop command to motor
pass

def reset(self) -> None:
pass

def periodic(self) -> None:
pass

# Component specific methods

# Methods from wpilib.PWMMotorController
Expand Down
11 changes: 2 additions & 9 deletions external_samples/sparkfun_led_stick.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,7 @@

__author__ = "[email protected] (Liz Looney)"

from typing import Self
from component import Component, PortType, InvalidPortException
from component import Component
from port import Port, PortType
import wpilib

Expand All @@ -38,15 +37,9 @@ def get_url(self) -> str:
def get_version(self) -> tuple[int, int, int]:
return (1, 0, 0)

def stop(self) -> None:
def opmode_end(self) -> None:
self.turn_all_off()

def reset(self) -> None:
pass

def periodic(self) -> None:
pass

# SparkFunLEDStick methods

def set_color(self, position: int, color: wpilib.Color) -> None:
Expand Down
14 changes: 14 additions & 0 deletions python/wpilib_placeholders/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
"""Placeholder classes for future wpilib."""

from .expansion_hub import ExpansionHubPidConstants, ExpansionHubMotor, ExpansionHubServo, ExpansionHub
from .op_mode_robot import OpModeRobot
from .periodic_op_mode import PeriodicOpMode

__all__ = [
'ExpansionHubPidConstants',
'ExpansionHubMotor',
'ExpansionHubServo',
'ExpansionHub',
'OpModeRobot',
'PeriodicOpMode',
]
Loading