Skip to content
Merged
Show file tree
Hide file tree
Changes from 18 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
63 changes: 63 additions & 0 deletions external_samples/color_range_sensor.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
from component import Component, PortType, InvalidPortException
from collections.abc import Callable, Protocol

class DistanceCallable(Protocol):
def __call__(self, distance : float) -> None:
pass
class ColorCallable(Protocol):
def __call__(self, hue : int, saturation : int, value : int) -> None:
pass

class ColorRangeSensor(Component):
# Required methods
def __init__(self, ports : list[tuple[PortType, int]]):
self.is_pressed = None
portType, port = ports[0]
if portType != PortType.I2C_PORT:
raise InvalidPortException
self.port = 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, str]:
return (1, 0, "")
def stop(self) -> None:
# send stop command to sensor
pass
def reset(self) -> None:
pass
def get_connection_port_type(self) -> list[PortType]:
return [PortType.I2C_PORT]
def periodic(self) -> None:
pass

# Component specific methods
def get_color_rgb(self) -> list[int, int, int]:
'''gets the color in rgb (red, green, blue)'''
pass
def get_color_hsv(self) -> list[int, int, int]:
'''gets the color in hsv (hue, saturation, value)'''
pass
def get_distance_mm(self) -> float:
'''gets the distance of the object seen'''
pass

def register_when_less_than_distance(self, distance : float, callback: DistanceCallable) -> None:
'''Event when item is seen closer than a distance'''
self.less_than_distance_callback = callback

def register_when_hue_in_range(self, min_hue : int, max_hue : int, callback: ColorCallable) -> None:
'''Event when hue is in range'''
self.hue_in_range_callback = callback

def register_when_saturation_in_range(self, min_saturation : int, max_saturation : int, callback : ColorCallable) -> None:
'''Event when saturation is in range'''
self.saturation_in_range_callback = callback



68 changes: 68 additions & 0 deletions external_samples/component.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
from abc import ABC, abstractmethod
from enum import Enum
from collections.abc import Callable, Protocol

class EmptyCallable(Protocol):
def __call__(self) -> None:
pass
class PortType(Enum):
CAN_PORT = 1
SMART_IO_PORT = 2
SMART_MOTOR_PORT = 3
SERVO_PORT = 4
I2C_PORT = 5
USB_PORT = 6

class InvalidPortException(Exception):
pass

# This is an abstract class
class Component:
@abstractmethod
def __init__(self, ports : list[tuple[PortType, int]]):
pass
# This is the manufacturer of the component
@abstractmethod
def get_manufacturer(self) -> str:
pass
# This is the name of the component
@abstractmethod
def get_name(self) -> str:
pass
# This is the part number of the component
@abstractmethod
def get_part_number(self) -> str:
pass
# This is the URL of the component
@abstractmethod
def get_url(self) -> str:
pass
# This is the version of the software (returned as a (major, minor, revision) tuple where
# major and minor are positive integers
# revision is an optional string
@abstractmethod
def get_version(self) -> tuple[int, int, str]:
pass

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

# any reset required (if any) at the beginning of each opmode
# This might remove any registered callbacks
@abstractmethod
def reset(self) -> None:
pass

# This returns a list (can be empty, one, or multiple) of the ports this connects to
# of the PortType enumeration
@abstractmethod
def get_connection_port_type(self) -> list[PortType]:
pass

# 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
53 changes: 53 additions & 0 deletions external_samples/rev_touch_sensor.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
from component import Component, PortType, InvalidPortException, EmptyCallable

class RevTouchSensor(Component):
def __init__(self, ports : list[tuple[PortType, int]]):
self.is_pressed = None
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It seems like is_pressed should be a boolean, so the value should be False instead of None.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It can't be, because when the system boots up you don't know if the touch sensor is currently pressed or not. If you start out saying it isn't, then you'll get an immediate callback for pressed even though that isn't accurate. So you have to start out before your first read with something that knows it hasn't read hardware yet.

Leaving this comment open to see if you agree or not.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK. That makes sense.

portType, port = ports[0]
if portType != PortType.SMART_IO_PORT:
raise InvalidPortException
self.port = port
# Required methods
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, str]:
return (1, 0, "")
def stop(self) -> None:
pass
def reset(self) -> None:
self.pressed_callback = None
self.released_callback = None
pass
def get_connection_port_type(self) -> list[PortType]:
return [PortType.SMART_IO_PORT]
def periodic(self) -> None:
old = self.is_pressed
self._read_hardware()
if old != self.is_pressed:
if self.is_pressed and self.pressed_callback:
self.pressed_callback()
elif old and self.released_callback:
self.released_callback()
def _read_hardware(self):
# here read hardware to get the current value of the sensor and set self.is_pressed
pass

def is_pressed(self) -> bool:
'''Returns if the touch sensor is pressed or not'''
return self.is_pressed

# Events
def register_when_pressed(self, callback: EmptyCallable) -> None:
'''Event when touch sensor is first pressed'''
self.pressed_callback = callback


def register_when_released(self, callback: EmptyCallable) -> None:
'''Event when touch sensor is first released'''
self.released_callback = callback
42 changes: 42 additions & 0 deletions external_samples/servo.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
from component import Component, PortType, InvalidPortException
from collections.abc import Callable

class Servo(Component):
# Required methods
def __init__(self, ports : list[tuple[PortType, int]]):
self.is_pressed = None
portType, port = ports[0]
if portType != PortType.SERVO_PORT:
raise InvalidPortException
self.port = port
def get_manufacturer(self) -> str:
return "REV Robotics"
def get_name(self) -> str:
return "SRS Servo"
def get_part_number(self) -> str:
return "REV-41-1097"
def get_url(self) -> str:
return "https://www.revrobotics.com/rev-41-1097/"
def get_version(self) -> tuple[int, int, str]:
return (1, 0, "")
def stop(self) -> None:
# De-energize servo port
pass
def reset(self) -> None:
pass
def get_connection_port_type(self) -> list[PortType]:
return [PortType.SERVO_PORT]
def periodic(self) -> None:
pass

# Component specific methods
def set_position(self, pos: float) -> None:
'''Set the servo to a position between 0 and 1'''
# sends to the hardware the position of the servo
pass
def set_angle_degrees(self, angle: float) -> None:
'''Set the servo to an angle between 0 and 270'''
self.set_position(angle / 270.0)



51 changes: 51 additions & 0 deletions external_samples/smart_motor.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
from component import Component, PortType, InvalidPortException

class SmartMotor(Component):
# Required methods
def __init__(self, ports : list[tuple[PortType, int]]):
self.is_pressed = None
portType, port = ports[0]
if portType != PortType.SMART_MOTOR_PORT:
raise InvalidPortException
self.port = port
def get_manufacturer(self) -> str:
return "REV Robotics"
def get_name(self) -> str:
return "DC Motor"
def get_part_number(self) -> str:
return "REV-xx-xxxx"
def get_url(self) -> str:
return "https://www.revrobotics.com/rev-xx-xxxx"
def get_version(self) -> tuple[int, int, str]:
return (1, 0, "")
def stop(self) -> None:
# send stop command to motor
pass
def reset(self) -> None:
pass
def get_connection_port_type(self) -> list[PortType]:
return [PortType.SMART_MOTOR_PORT]
def periodic(self) -> None:
pass

# Component specific methods
def set_speed(self, speed: float) -> None:
'''Set the motor to a speed between -1 and 1'''
# sends to the hardware the speed of the motor

def set_angle_degrees(self, angle: float) -> None:
'''Set the motor to an angle between 0 and 270'''
self.set_position(angle / 270.0)

def get_num_relative_encoder_ticks(self) -> int:
'''Get the number of relative motor ticks since reset of encoder'''
pass

def get_angle_degrees(self) -> float:
'''Get the angle position of the motor'''
pass

def reset_relative_encoder(self) -> None:
'''Reset the relative encoder value to 0'''
pass