|
| 1 | +# Copyright 2025 Google LLC |
| 2 | +# |
| 3 | +# Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +# you may not use this file except in compliance with the License. |
| 5 | +# You may obtain a copy of the License at |
| 6 | +# |
| 7 | +# https://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +# |
| 9 | +# Unless required by applicable law or agreed to in writing, software |
| 10 | +# distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +# See the License for the specific language governing permissions and |
| 13 | +# limitations under the License. |
| 14 | + |
| 15 | +"""This is the expansion_hub_motor module. |
| 16 | +
|
| 17 | +This component wraps the expansion_hub.ExpansionHubMotor class, providing |
| 18 | +support for a motor connected to a REV Expansion Hub. |
| 19 | +""" |
| 20 | + |
| 21 | +__author__ = "[email protected] (Liz Looney)" |
| 22 | + |
| 23 | +from typing import Self |
| 24 | +from component import Component, PortType, InvalidPortException |
| 25 | +import expansion_hub |
| 26 | +import wpimath |
| 27 | + |
| 28 | +# TODO(lizlooney): Update port types. |
| 29 | + |
| 30 | +class ExpansionHubMotor(Component): |
| 31 | + def __init__(self, ports : list[tuple[PortType, int]]): |
| 32 | + port_type, hub_number = ports[0] |
| 33 | + if port_type != PortType.USB_PORT: |
| 34 | + raise InvalidPortException |
| 35 | + port_type, motor_number = ports[1] |
| 36 | + if port_type != PortType.USB_PORT: |
| 37 | + raise InvalidPortException |
| 38 | + self.expansion_hub_motor = expansion_hub.ExpansionHubMotor(hub_number, motor_number) |
| 39 | + |
| 40 | + def get_manufacturer(self) -> str: |
| 41 | + return "REV Robotics" |
| 42 | + |
| 43 | + def get_name(self) -> str: |
| 44 | + return "Expansion Hub Motor" |
| 45 | + |
| 46 | + def get_part_number(self) -> str: |
| 47 | + return "" |
| 48 | + |
| 49 | + def get_url(self) -> str: |
| 50 | + return "" |
| 51 | + |
| 52 | + def get_version(self) -> tuple[int, int, int]: |
| 53 | + return (1, 0, 0) |
| 54 | + |
| 55 | + def start(self) -> None: |
| 56 | + self.expansion_hub_motor.setEnabled(True) |
| 57 | + |
| 58 | + def stop(self) -> None: |
| 59 | + # TODO: Send stop command to motor. |
| 60 | + pass |
| 61 | + |
| 62 | + def reset(self) -> None: |
| 63 | + pass |
| 64 | + |
| 65 | + def get_connection_port_type(self) -> list[PortType]: |
| 66 | + return [PortType.USB_PORT, PortType.USB_PORT] |
| 67 | + |
| 68 | + def periodic(self) -> None: |
| 69 | + pass |
| 70 | + |
| 71 | + # Alternative constructor to create an instance from a hub number and a motor port. |
| 72 | + @classmethod |
| 73 | + def from_hub_number_and_motor_number(cls: type[Self], hub_number: int, motor_number: int) -> Self: |
| 74 | + return cls([(PortType.USB_PORT, hub_number), (PortType.USB_PORT, motor_number)]) |
| 75 | + |
| 76 | + # Component specific methods |
| 77 | + |
| 78 | + # Methods from expansion_hub.ExpansionHubMotor |
| 79 | + |
| 80 | + def setPercentagePower(self, power: float): |
| 81 | + self.expansion_hub_motor.setPercentagePower(power) |
| 82 | + |
| 83 | + def setVoltage(self, voltage: wpimath.units.volts): |
| 84 | + self.expansion_hub_motor.setVoltage(voltage) |
| 85 | + |
| 86 | + def setPositionSetpoint(self, setpoint: float): |
| 87 | + self.expansion_hub_motor.setPositionSetpoint(setpoint) |
| 88 | + |
| 89 | + def setVelocitySetpoint(self, setpoint: float): |
| 90 | + self.expansion_hub_motor.setVelocitySetpoint(setpoint) |
| 91 | + |
| 92 | + def setEnabled(self, enabled: bool): |
| 93 | + self.expansion_hub_motor.setEnabled(enabled) |
| 94 | + |
| 95 | + def setFloatOn0(self, floatOn0: bool): |
| 96 | + self.expansion_hub_motor.setFloatOn0(floatOn0) |
| 97 | + |
| 98 | + def getCurrent(self) -> float: |
| 99 | + return self.expansion_hub_motor.getCurrent() |
| 100 | + |
| 101 | + def setDistancePerCount(self, perCount: float): |
| 102 | + self.expansion_hub_motor.setDistancePerCount(perCount) |
| 103 | + |
| 104 | + def isHubConnected(self) -> bool: |
| 105 | + return self.expansion_hub_motor.isHubConnected() |
| 106 | + |
| 107 | + def getEncoder(self) -> float: |
| 108 | + return self.expansion_hub_motor.getEncoder() |
| 109 | + |
| 110 | + def getEncoderVelocity(self) -> float: |
| 111 | + return self.expansion_hub_motor.getEncoderVelocity() |
| 112 | + |
| 113 | + def setReversed(self, reversed: bool): |
| 114 | + self.expansion_hub_motor.setReversed(reversed) |
| 115 | + |
| 116 | + def resetEncoder(self): |
| 117 | + self.expansion_hub_motor.resetEncoder() |
| 118 | + |
| 119 | + def getVelocityPidConstants(self) -> expansion_hub.ExpansionHubPidConstants: |
| 120 | + return self.expansion_hub_motor.getVelocityPidConstants() |
| 121 | + |
| 122 | + def getPositionPidConstants(self) -> expansion_hub.ExpansionHubPidConstants: |
| 123 | + return self.expansion_hub_motor.getPositionPidConstants() |
0 commit comments