diff --git a/NaviGator/hardware_drivers/navigator_ball_launcher/navigator_ball_launcher/driver.py b/NaviGator/hardware_drivers/navigator_ball_launcher/navigator_ball_launcher/driver.py index f78f22784..a729fd271 100644 --- a/NaviGator/hardware_drivers/navigator_ball_launcher/navigator_ball_launcher/driver.py +++ b/NaviGator/hardware_drivers/navigator_ball_launcher/navigator_ball_launcher/driver.py @@ -33,7 +33,7 @@ def __init__(self, port: str): self.heard_nack = False self.drops = 0 self.temp_timer = None - print("done init") + rospy.loginfo("Ball launcher device initialized") def get_drop_count(self) -> int: return self.drops @@ -51,10 +51,10 @@ def _check_for_valid_response(self, event: str): elif not self.heard_ack: rospy.logerr(f"Failed to {event} (no response from board)") - def _check_for_dropped_ball(self): + def _check_for_dropped_ball(self, _): self._check_for_valid_response("drop ball") - def _check_for_spun(self): + def _check_for_spun(self, _): self._check_for_valid_response("set spin") def drop_ball(self, _: EmptyRequest): @@ -84,7 +84,6 @@ def spin(self, request: SetBoolRequest): return {} def on_packet_received(self, packet: AckPacket | NackPacket) -> None: - print("inc packet", packet) if isinstance(packet, AckPacket): self.heard_ack = True elif isinstance(packet, NackPacket): diff --git a/NaviGator/hardware_drivers/navigator_ball_launcher/nodes/driver.py b/NaviGator/hardware_drivers/navigator_ball_launcher/nodes/driver.py index f1a40b340..2c95f899e 100755 --- a/NaviGator/hardware_drivers/navigator_ball_launcher/nodes/driver.py +++ b/NaviGator/hardware_drivers/navigator_ball_launcher/nodes/driver.py @@ -4,5 +4,6 @@ if __name__ == "__main__": rospy.init_node("ball_launcher") - device = BallLauncherDevice(str(rospy.get_param("~port"))) + port = str(rospy.get_param("~port")) + device = BallLauncherDevice(port) rospy.spin()