From 161c9be99e95743b2803fc2ef44976bb4e38b900 Mon Sep 17 00:00:00 2001 From: hdjwis Date: Wed, 25 Feb 2026 00:44:14 +0000 Subject: [PATCH 1/6] added push motor limit switch --- arduino/sensors/sensors.ino | 19 +++++++++---------- config/auger_config.yaml | 1 + src/auger/auger/auger_node.py | 10 ++++++++-- src/rovr_control/rovr_control/read_serial.py | 16 +++++++++++----- 4 files changed, 29 insertions(+), 17 deletions(-) diff --git a/arduino/sensors/sensors.ino b/arduino/sensors/sensors.ino index dc9ac952..705fd153 100644 --- a/arduino/sensors/sensors.ino +++ b/arduino/sensors/sensors.ino @@ -1,14 +1,14 @@ // Define a struct to hold the sensor data struct SensorData { - int leftMotorPotentiometer; - int rightMotorPotentiometer; - bool bottomLimitSwitch; + int tiltPotentiometer; + bool dumpLimitSwitch; + bool extensionLimitSwitch; }; // Define the sensor pins here -#define LEFT_MOTOR_POT_PIN A0 -#define RIGHT_MOTOR_POT_PIN A1 -#define RELAY_PIN 7 +#define TILT_POTENTIOMETER A0 +#define DUMP_LIMIT_SWITCH A1 +#define EXTENSION_LIMIT_SWITCH 7 void setup() { // Initialize serial communication @@ -26,10 +26,9 @@ void loop() { SensorData data; // Read from the analog inputs (potentiometers) - data.leftMotorPotentiometer = analogRead(LEFT_MOTOR_POT_PIN); // Read left motor potentiometer value - data.rightMotorPotentiometer = analogRead(RIGHT_MOTOR_POT_PIN); // Read right motor potentiometer value - - data.bottomLimitSwitch = analogRead(bottom_limit_switch); //bottom limit switch value + data.tiltPotentiometer = analogRead(TILT_POTENTIOMETER); // Read left motor potentiometer value + data.dumpLimitSwitch = analogRead(DUMP_LIMIT_SWITCH); // Read right motor potentiometer value + data.extensionLimitSwitch = analogRead(EXTENSION_LIMIT_SWITCH); //bottom limit switch value // Send the struct over the serial bus to the Nvidia Jetson Serial.write((byte *)&data, sizeof(SensorData)); diff --git a/config/auger_config.yaml b/config/auger_config.yaml index 5d2a7153..abd1036f 100644 --- a/config/auger_config.yaml +++ b/config/auger_config.yaml @@ -9,6 +9,7 @@ MAX_EXTEND_PUSH_MOTOR_VELOCITY: 600 # in RPM push_motor_position: 0 tilt_actuator_position: 0 + extension_limit_switch: true TILT_ACTUATOR_CURRENT_THRESHOLD: 0 MAX_PUSH_MOTOR_POSITION: 0 MIN_PUSH_MOTOR_POSITION: 0 diff --git a/src/auger/auger/auger_node.py b/src/auger/auger/auger_node.py index d91f98c2..f726912d 100644 --- a/src/auger/auger/auger_node.py +++ b/src/auger/auger/auger_node.py @@ -80,6 +80,7 @@ def __init__(self): self.MAX_SPIN_MOTOR_CURRENT = self.get_parameter("MAX_SPIN_MOTOR_CURRENT").value self.push_motor_position = self.get_parameter("push_motor_position").value self.tilt_actuator_position = self.get_parameter("tilt_actuator_position").value + self.extension_limit_switch = self.get_parameter("extension_limit_switch").value self.TILT_ACTUATOR_CURRENT_THRESHOLD = self.get_parameter( "TILT_ACTUATOR_CURRENT_THRESHOLD" ) @@ -197,6 +198,9 @@ def __init__(self): Potentiometers, "potentiometer", self.push_motor_position_callback, 10 ) + self.limit_switch_sub = self.create_subscription( + Bool, "ExtensionLimitSwitch", self.limit_switch_callback, 10 + ) # TODO Define publishers here # Define subsystem methods here @@ -354,8 +358,7 @@ def set_motor_push_position( if motor_get_pos_future.result().success: current_pos = motor_get_pos_future.result().data if (speed <= 0 and current_pos <= desired_position) or ( - speed > 0 and current_pos >= desired_position - ): + speed > 0 and current_pos >= desired_position) or (self.extension_limit_switch): break else: self.get_logger().warn("WARNING: Failed to read push motor position") @@ -526,6 +529,9 @@ def stop_spin_callback(self, request, response): def push_motor_position_callback(self, msg): self.tilt_actuator_position = msg.data + def limit_switch_callback(self, msg): + + def extend_push_callback(self, request, response): """ This service requests to extend the push motor at full speed. diff --git a/src/rovr_control/rovr_control/read_serial.py b/src/rovr_control/rovr_control/read_serial.py index 1d5e83fe..64f7f335 100644 --- a/src/rovr_control/rovr_control/read_serial.py +++ b/src/rovr_control/rovr_control/read_serial.py @@ -13,7 +13,8 @@ def __init__(self): super().__init__("read_serial") self.potentiometerPub = self.create_publisher(Int16, "potentiometer", 10) - self.LimitSwitchPub = self.create_publisher(Bool, "DumperLimitSwitch", 10) + self.DumperLimitSwitchPub = self.create_publisher(Bool, "DumperLimitSwitch", 10) + self.ExtensionLimitSwitchPub = self.create_publisher(Bool, "ExtensionLimitSwitch", 10) # Services to control the relay-driven agitator motor self.srv_bigonoff = self.create_service( @@ -52,15 +53,20 @@ def timer_callback(self): return data = self.arduino.read(4) # Pause until 4 bytes are read # Use h for integers and ? for booleans - decoded = struct.unpack("h?", data) + decoded = struct.unpack("h??", data) potentiometer_msg = Int16() potentiometer_msg.data = decoded[0] self.potentiometerPub.publish(potentiometer_msg) - bool_msg = Bool() - bool_msg.data = decoded[1] - self.LimitSwitchPub.publish(bool_msg) + dumper_bool_msg = Bool() + dumper_bool_msg.data = decoded[1] + self.DumperLimitSwitchPub.publish(dumper_bool_msg) + + extension_bool_msg = Bool() + extension_bool_msg.data = decoded[2] + self.ExtensionLimitSwitchPub.publish(extension_bool_msg) + def big_on_off_callback(self, request, response): # request.data == True → ON, False → OFF From c974f96ba1e3d89a0b48950c90c1e0407e8a52c7 Mon Sep 17 00:00:00 2001 From: hdjwis Date: Wed, 25 Feb 2026 01:15:41 +0000 Subject: [PATCH 2/6] added auger stowed check in dumper --- config/auger_config.yaml | 1 + src/auger/auger/auger_node.py | 22 ++++++++++++++++++++-- src/dumper/dumper/dumper_node.py | 21 ++++++++++++++------- 3 files changed, 35 insertions(+), 9 deletions(-) diff --git a/config/auger_config.yaml b/config/auger_config.yaml index abd1036f..071e1ad6 100644 --- a/config/auger_config.yaml +++ b/config/auger_config.yaml @@ -10,6 +10,7 @@ push_motor_position: 0 tilt_actuator_position: 0 extension_limit_switch: true + STOWED: true TILT_ACTUATOR_CURRENT_THRESHOLD: 0 MAX_PUSH_MOTOR_POSITION: 0 MIN_PUSH_MOTOR_POSITION: 0 diff --git a/src/auger/auger/auger_node.py b/src/auger/auger/auger_node.py index f726912d..cea0598a 100644 --- a/src/auger/auger/auger_node.py +++ b/src/auger/auger/auger_node.py @@ -37,6 +37,8 @@ def __init__(self): self.cli_motor_get = self.create_client(MotorCommandGet, "motor/get") # Define parameters here + self.declare_parameter("STOWED", True) + self.declare_parameter("extension_limit_switch", True) self.declare_parameter("POWER_LIMIT", 1) self.declare_parameter("SCREW_SPEED", 4000) self.declare_parameter( @@ -81,6 +83,7 @@ def __init__(self): self.push_motor_position = self.get_parameter("push_motor_position").value self.tilt_actuator_position = self.get_parameter("tilt_actuator_position").value self.extension_limit_switch = self.get_parameter("extension_limit_switch").value + self.stowed = self.get_parameter("STOWED").value self.TILT_ACTUATOR_CURRENT_THRESHOLD = self.get_parameter( "TILT_ACTUATOR_CURRENT_THRESHOLD" ) @@ -199,9 +202,12 @@ def __init__(self): ) self.limit_switch_sub = self.create_subscription( - Bool, "ExtensionLimitSwitch", self.limit_switch_callback, 10 + Bool, "ExtensionLimitSwitch", 10 ) # TODO Define publishers here + self.stowed_pub = self.create_publisher( + Bool, "stowed", self.stowed_callback, 10 + ) # Define subsystem methods here @@ -247,6 +253,12 @@ def set_actuator_tilt_extension(self, tilt: bool) -> bool: # gets motor current until it is 0 which means it has hit an limit # switch + if tilt: + self.stowed = False + msg = Bool() + msg.data = self.stowed + self.stowed_pub.publish(msg) + while True: motor_get_future = self.cli_motor_get.call_async( MotorCommandGet.Request( @@ -267,6 +279,12 @@ def set_actuator_tilt_extension(self, tilt: bool) -> bool: time.sleep(0.1) + if not tilt: + self.stowed = True + msg = Bool() + msg.data = self.stowed + self.stowed_pub.publish(msg) + return True def stop_actuator_tilt(self) -> bool: @@ -530,7 +548,7 @@ def push_motor_position_callback(self, msg): self.tilt_actuator_position = msg.data def limit_switch_callback(self, msg): - + self.extension_limit_switch = msg.data def extend_push_callback(self, request, response): """ diff --git a/src/dumper/dumper/dumper_node.py b/src/dumper/dumper/dumper_node.py index 48aa0470..1978c247 100644 --- a/src/dumper/dumper/dumper_node.py +++ b/src/dumper/dumper/dumper_node.py @@ -77,8 +77,12 @@ def __init__(self): self.KillSwitch_sub = self.create_subscription( Bool, "DumperLimitSwitch", self.killSwitch_callback, 10 ) + + self.auger_stowed_sub = self.create_subscription( + Bool, "stowed", self.auger_stowed_callback, 10 + ) self.limitSwitchBottom = False - # self.auger_stowed = True + self.auger_stowed = True # Define subsystem methods here def set_power(self, dumper_power: float) -> None: @@ -124,9 +128,9 @@ def toggle_callback(self, request, response): return response def dump_dumper(self) -> None: - # if not self.auger_stowed: - # self.get_logger().info("The auger is already extended") - # return + if not self.auger_stowed: + self.get_logger().info("The auger is already extended") + return self.get_logger().info("Extending the dumper") self.dumped_state = True @@ -152,9 +156,9 @@ def dump_callback(self, request, response): return response def store_dumper(self) -> None: # get the variables - # if not self.auger_stowed: - # self.get_logger().info("The Auger is already extended") - # return + if not self.auger_stowed: + self.get_logger().info("The Auger is already extended") + return self.get_logger().info("Retracting the dumper") self.dumped_state = False self.long_service_running = True @@ -184,6 +188,9 @@ def dumper_current_callback(self, msg): def killSwitch_callback(self, msg): # position control... self.LimitSwitchBottom = msg.data + + def auger_stowed_callback(self, msg): + self.auger_stowed = msg.data def main(args=None): From 51f6ca99cffce322e99d7d18d7a0b00a540ea44d Mon Sep 17 00:00:00 2001 From: hdjwis Date: Wed, 25 Feb 2026 01:33:51 +0000 Subject: [PATCH 3/6] added check for dumper stowed in auger node --- src/auger/auger/auger_node.py | 38 +++++++++++++++++++++++--------- src/dumper/dumper/dumper_node.py | 19 ++++++++++++---- 2 files changed, 42 insertions(+), 15 deletions(-) diff --git a/src/auger/auger/auger_node.py b/src/auger/auger/auger_node.py index cea0598a..134bdf0a 100644 --- a/src/auger/auger/auger_node.py +++ b/src/auger/auger/auger_node.py @@ -37,7 +37,8 @@ def __init__(self): self.cli_motor_get = self.create_client(MotorCommandGet, "motor/get") # Define parameters here - self.declare_parameter("STOWED", True) + self.declare_parameter("AUGER_STOWED", True) + self.declare_parameter("DUMPER_STOWED", True) self.declare_parameter("extension_limit_switch", True) self.declare_parameter("POWER_LIMIT", 1) self.declare_parameter("SCREW_SPEED", 4000) @@ -83,7 +84,8 @@ def __init__(self): self.push_motor_position = self.get_parameter("push_motor_position").value self.tilt_actuator_position = self.get_parameter("tilt_actuator_position").value self.extension_limit_switch = self.get_parameter("extension_limit_switch").value - self.stowed = self.get_parameter("STOWED").value + self.auger_stowed = self.get_parameter("AUGER_STOWED").value + self.dumper_stowed = self.get_parameter("DUMPER_STOWED").value self.TILT_ACTUATOR_CURRENT_THRESHOLD = self.get_parameter( "TILT_ACTUATOR_CURRENT_THRESHOLD" ) @@ -202,13 +204,22 @@ def __init__(self): ) self.limit_switch_sub = self.create_subscription( - Bool, "ExtensionLimitSwitch", 10 + Bool, "ExtensionLimitSwitch", self.limit_switch_callback, 10 ) + + self.dumper_stowed_sub = self.create_subscription( + Bool, "dumper_stowed", self.dumper_stowed_callback, 10 + ) + # TODO Define publishers here - self.stowed_pub = self.create_publisher( - Bool, "stowed", self.stowed_callback, 10 + self.auger_stowed_pub = self.create_publisher( + Bool, "auger_stowed", 10 ) + + + + # Define subsystem methods here def set_actuator_tilt_extension(self, tilt: bool) -> bool: @@ -254,10 +265,10 @@ def set_actuator_tilt_extension(self, tilt: bool) -> bool: # gets motor current until it is 0 which means it has hit an limit # switch if tilt: - self.stowed = False + self.auger_stowed = False msg = Bool() - msg.data = self.stowed - self.stowed_pub.publish(msg) + msg.data = self.auger_stowed + self.auger_stowed_pub.publish(msg) while True: motor_get_future = self.cli_motor_get.call_async( @@ -280,10 +291,10 @@ def set_actuator_tilt_extension(self, tilt: bool) -> bool: time.sleep(0.1) if not tilt: - self.stowed = True + self.auger_stowed = True msg = Bool() - msg.data = self.stowed - self.stowed_pub.publish(msg) + msg.data = self.auger_stowed + self.auger_stowed_pub.publish(msg) return True @@ -466,6 +477,8 @@ def stop_auger_spin(self) -> bool: def extend_digger(self) -> bool: """Tilt and extend""" + if not self.dumper_stowed: + return False tilt_success = self.set_actuator_tilt_extension(True) if not tilt_success: @@ -550,6 +563,9 @@ def push_motor_position_callback(self, msg): def limit_switch_callback(self, msg): self.extension_limit_switch = msg.data + def dumper_stowed_callback(self, msg): + self.dumper_stowed = msg.data + def extend_push_callback(self, request, response): """ This service requests to extend the push motor at full speed. diff --git a/src/dumper/dumper/dumper_node.py b/src/dumper/dumper/dumper_node.py index 1978c247..04cc3a86 100644 --- a/src/dumper/dumper/dumper_node.py +++ b/src/dumper/dumper/dumper_node.py @@ -79,8 +79,14 @@ def __init__(self): ) self.auger_stowed_sub = self.create_subscription( - Bool, "stowed", self.auger_stowed_callback, 10 + Bool, "auger_stowed", self.auger_stowed_callback, 10 ) + + self.dumper_stowed_pub = self.create_publisher( + Bool, "dumper_stowed", 10 + ) + + self.dumper_stowed = True self.limitSwitchBottom = False self.auger_stowed = True @@ -140,6 +146,10 @@ def dump_dumper(self) -> None: MotorCommandSet.Request(type="position", can_id=self.DUMPER_MOTOR, value=90) ) + self.dumper_stowed = False + msg = Bool() + msg.data = self.dumper_stowed + self.dumper_stowed_pub.publish(msg) while not future.done(): # While loop makes the motor keep going till limit switch is hit if self.cancel_current_srv: self.cancel_current_srv = False @@ -156,9 +166,6 @@ def dump_callback(self, request, response): return response def store_dumper(self) -> None: # get the variables - if not self.auger_stowed: - self.get_logger().info("The Auger is already extended") - return self.get_logger().info("Retracting the dumper") self.dumped_state = False self.long_service_running = True @@ -172,6 +179,10 @@ def store_dumper(self) -> None: # get the variables time.sleep(0.1) self.stop() + self.dumper_stowed = True + msg = Bool() + msg.data = self.dumper_stowed + self.dumper_stowed_pub.publish(msg) self.long_service_running = False self.get_logger().info("Done storing the dumper") From 659770f535ce74731fcc3fdcd862446b442e96a3 Mon Sep 17 00:00:00 2001 From: hdjwis Date: Fri, 27 Feb 2026 00:38:43 +0000 Subject: [PATCH 4/6] updated drivetrain safety check to use extension position --- config/motor_control.yaml | 2 +- src/auger/auger/auger_node.py | 9 +++++++++ src/drivetrain/drivetrain/drivetrain_node.py | 18 ++++++++++-------- 3 files changed, 20 insertions(+), 9 deletions(-) diff --git a/config/motor_control.yaml b/config/motor_control.yaml index a756c74c..2b271ac4 100644 --- a/config/motor_control.yaml +++ b/config/motor_control.yaml @@ -16,7 +16,7 @@ DIGGER_ACTUATORS_kP_coupling: 0.004 # kP for digger actuator position syncing DIGGER_PITCH_kP: 2.5 # kP for tipping while digging TIPPING_SPEED_ADJUSTMENT: false # determines if pitch speed adjustment is used - DIGGER_SAFETY_ZONE: 120 # Measured in potentiometer units (0 to 1023) + EXTENSION_SAFETY_ZONE: 0 # Measured in potentiometer units (0 to 1023) CURRENT_SPIKE_THRESHOLD: 1.8 # Threshold for current spike detection (measured in Amps) CURRENT_SPIKE_TIME: 0.2 # Time in seconds to consider it a current spike (measured in seconds) BUCKETS_CURRENT_SPIKE_THRESHOLD: 12.0 # Threshold for current spike detection (measured in Amps) diff --git a/src/auger/auger/auger_node.py b/src/auger/auger/auger_node.py index 134bdf0a..827e2cd3 100644 --- a/src/auger/auger/auger_node.py +++ b/src/auger/auger/auger_node.py @@ -20,6 +20,8 @@ from rovr_interfaces.srv import SetExtension from rovr_interfaces.msg import Potentiometers from std_srvs.srv import Trigger +from std_msgs.msg import Bool, Float32 + class Auger(Node): @@ -216,6 +218,10 @@ def __init__(self): Bool, "auger_stowed", 10 ) + self.extension_pos_sub = self.create_publisher( + Float32, "extension_pos", 10 + ) + @@ -386,6 +392,9 @@ def set_motor_push_position( if motor_get_pos_future.result().success: current_pos = motor_get_pos_future.result().data + msg = Float32() + msg.data = current_pos + self.extension_pos_sub.publish(msg) if (speed <= 0 and current_pos <= desired_position) or ( speed > 0 and current_pos >= desired_position) or (self.extension_limit_switch): break diff --git a/src/drivetrain/drivetrain/drivetrain_node.py b/src/drivetrain/drivetrain/drivetrain_node.py index 5910eb0c..496c98e0 100644 --- a/src/drivetrain/drivetrain/drivetrain_node.py +++ b/src/drivetrain/drivetrain/drivetrain_node.py @@ -30,7 +30,7 @@ def __init__(self): self.declare_parameter("GAZEBO_SIMULATION", False) self.declare_parameter("MAX_DRIVETRAIN_RPM", 10000) self.declare_parameter("DRIVETRAIN_TYPE", "velocity") - self.declare_parameter("DIGGER_SAFETY_ZONE", 120) # Measured in potentiometer units (0 to 1023) + self.declare_parameter("EXTENSION_SAFETY_ZONE", 0) # Measured in potentiometer units (0 to 1023) # Assign the ROS Parameters to member variables below # self.FRONT_LEFT_DRIVE = self.get_parameter("FRONT_LEFT_DRIVE").value @@ -40,11 +40,11 @@ def __init__(self): self.GAZEBO_SIMULATION = self.get_parameter("GAZEBO_SIMULATION").value self.MAX_DRIVETRAIN_RPM = self.get_parameter("MAX_DRIVETRAIN_RPM").value self.DRIVETRAIN_TYPE = self.get_parameter("DRIVETRAIN_TYPE").value - self.DIGGER_SAFETY_ZONE = self.get_parameter("DIGGER_SAFETY_ZONE").value + self.EXTENSION_SAFETY_ZONE = self.get_parameter("EXTENSION_SAFETY_ZONE").value # Define publishers and subscribers here self.cmd_vel_sub = self.create_subscription(Twist, "cmd_vel", self.cmd_vel_callback, 10) - self.lift_pose_subscription = self.create_subscription(Float32, "lift_pose", self.lift_pose_callback, 10) + self.extension_sub = self.create_subscription(Float32, "extension_pos", self.extension_callback, 10) if self.GAZEBO_SIMULATION: self.gazebo_front_left_wheel_pub = self.create_publisher(Float64, "front_left_wheel/cmd_vel", 10) @@ -66,17 +66,19 @@ def __init__(self): self.get_logger().info("BACK_RIGHT_DRIVE has been set to: " + str(self.BACK_RIGHT_DRIVE)) self.get_logger().info("GAZEBO_SIMULATION has been set to: " + str(self.GAZEBO_SIMULATION)) self.get_logger().info("MAX_DRIVETRAIN_RPM has been set to: " + str(self.MAX_DRIVETRAIN_RPM)) - self.get_logger().info("DIGGER_SAFETY_ZONE has been set to: " + str(self.DIGGER_SAFETY_ZONE)) + self.get_logger().info("EXTENSION_SAFETY_ZONE has been set to: " + str(self.EXTENSION_SAFETY_ZONE)) + + # Current position of the lift motor in potentiometer units (0 to 1023) - self.current_lift_position = None # We don't know the current position yet + self.extension_pos = None # We don't know the current position yet # Define subsystem methods here def drive(self, forward_power: float, turning_power: float) -> None: """This method drives the robot with the desired forward and turning power.""" if ( - (self.current_lift_position is None or self.current_lift_position > self.DIGGER_SAFETY_ZONE) + (self.extension_pos is None or self.extension_pos > self.EXTENSION_SAFETY_ZONE) and not self.GAZEBO_SIMULATION and (forward_power != 0 or turning_power != 0) ): @@ -165,9 +167,9 @@ def cmd_vel_callback(self, msg: Twist) -> None: self.drive(msg.linear.x, msg.angular.z) # Define the subscriber callback for the lift pose topic - def lift_pose_callback(self, msg: Float32): + def extension_callback(self, msg: Float32): # Average the two potentiometer values - self.current_lift_position = msg.data + self.extension_pos = msg.data def main(args=None): From 09cedc20305abd186a9687c22445d781f6cc1032 Mon Sep 17 00:00:00 2001 From: Michael Foley <114529526+Michael-Foley@users.noreply.github.com> Date: Tue, 3 Mar 2026 19:36:04 -0600 Subject: [PATCH 5/6] changed arduino limit switch readins to analog because they are booleans. --- arduino/sensors/sensors.ino | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/arduino/sensors/sensors.ino b/arduino/sensors/sensors.ino index 705fd153..d1fb934a 100644 --- a/arduino/sensors/sensors.ino +++ b/arduino/sensors/sensors.ino @@ -27,8 +27,8 @@ void loop() { // Read from the analog inputs (potentiometers) data.tiltPotentiometer = analogRead(TILT_POTENTIOMETER); // Read left motor potentiometer value - data.dumpLimitSwitch = analogRead(DUMP_LIMIT_SWITCH); // Read right motor potentiometer value - data.extensionLimitSwitch = analogRead(EXTENSION_LIMIT_SWITCH); //bottom limit switch value + data.dumpLimitSwitch = digitalRead(DUMP_LIMIT_SWITCH); + data.extensionLimitSwitch = digitalRead(EXTENSION_LIMIT_SWITCH); // Send the struct over the serial bus to the Nvidia Jetson Serial.write((byte *)&data, sizeof(SensorData)); From a3eeb64989854e5ce18ba16e5e25acd82deef63d Mon Sep 17 00:00:00 2001 From: Michael Foley <114529526+Michael-Foley@users.noreply.github.com> Date: Tue, 3 Mar 2026 19:46:11 -0600 Subject: [PATCH 6/6] fixed formatting --- src/auger/auger/auger_node.py | 20 ++- src/drivetrain/drivetrain/drivetrain_node.py | 123 ++++++++++++++----- src/dumper/dumper/dumper_node.py | 44 +++++-- src/rovr_control/rovr_control/read_serial.py | 5 +- 4 files changed, 133 insertions(+), 59 deletions(-) diff --git a/src/auger/auger/auger_node.py b/src/auger/auger/auger_node.py index 827e2cd3..53a5ae56 100644 --- a/src/auger/auger/auger_node.py +++ b/src/auger/auger/auger_node.py @@ -23,7 +23,6 @@ from std_msgs.msg import Bool, Float32 - class Auger(Node): def __init__(self): "Initialize the ROS 2 Auger node" @@ -214,17 +213,9 @@ def __init__(self): ) # TODO Define publishers here - self.auger_stowed_pub = self.create_publisher( - Bool, "auger_stowed", 10 - ) - - self.extension_pos_sub = self.create_publisher( - Float32, "extension_pos", 10 - ) + self.auger_stowed_pub = self.create_publisher(Bool, "auger_stowed", 10) - - - + self.extension_pos_sub = self.create_publisher(Float32, "extension_pos", 10) # Define subsystem methods here @@ -395,8 +386,11 @@ def set_motor_push_position( msg = Float32() msg.data = current_pos self.extension_pos_sub.publish(msg) - if (speed <= 0 and current_pos <= desired_position) or ( - speed > 0 and current_pos >= desired_position) or (self.extension_limit_switch): + if ( + (speed <= 0 and current_pos <= desired_position) + or (speed > 0 and current_pos >= desired_position) + or (self.extension_limit_switch) + ): break else: self.get_logger().warn("WARNING: Failed to read push motor position") diff --git a/src/drivetrain/drivetrain/drivetrain_node.py b/src/drivetrain/drivetrain/drivetrain_node.py index 496c98e0..f82b4923 100644 --- a/src/drivetrain/drivetrain/drivetrain_node.py +++ b/src/drivetrain/drivetrain/drivetrain_node.py @@ -30,7 +30,9 @@ def __init__(self): self.declare_parameter("GAZEBO_SIMULATION", False) self.declare_parameter("MAX_DRIVETRAIN_RPM", 10000) self.declare_parameter("DRIVETRAIN_TYPE", "velocity") - self.declare_parameter("EXTENSION_SAFETY_ZONE", 0) # Measured in potentiometer units (0 to 1023) + self.declare_parameter( + "EXTENSION_SAFETY_ZONE", 0 + ) # Measured in potentiometer units (0 to 1023) # Assign the ROS Parameters to member variables below # self.FRONT_LEFT_DRIVE = self.get_parameter("FRONT_LEFT_DRIVE").value @@ -43,32 +45,60 @@ def __init__(self): self.EXTENSION_SAFETY_ZONE = self.get_parameter("EXTENSION_SAFETY_ZONE").value # Define publishers and subscribers here - self.cmd_vel_sub = self.create_subscription(Twist, "cmd_vel", self.cmd_vel_callback, 10) - self.extension_sub = self.create_subscription(Float32, "extension_pos", self.extension_callback, 10) + self.cmd_vel_sub = self.create_subscription( + Twist, "cmd_vel", self.cmd_vel_callback, 10 + ) + self.extension_sub = self.create_subscription( + Float32, "extension_pos", self.extension_callback, 10 + ) if self.GAZEBO_SIMULATION: - self.gazebo_front_left_wheel_pub = self.create_publisher(Float64, "front_left_wheel/cmd_vel", 10) - self.gazebo_back_left_wheel_pub = self.create_publisher(Float64, "back_left_wheel/cmd_vel", 10) - self.gazebo_front_right_wheel_pub = self.create_publisher(Float64, "front_right_wheel/cmd_vel", 10) - self.gazebo_back_right_wheel_pub = self.create_publisher(Float64, "back_right_wheel/cmd_vel", 10) + self.gazebo_front_left_wheel_pub = self.create_publisher( + Float64, "front_left_wheel/cmd_vel", 10 + ) + self.gazebo_back_left_wheel_pub = self.create_publisher( + Float64, "back_left_wheel/cmd_vel", 10 + ) + self.gazebo_front_right_wheel_pub = self.create_publisher( + Float64, "front_right_wheel/cmd_vel", 10 + ) + self.gazebo_back_right_wheel_pub = self.create_publisher( + Float64, "back_right_wheel/cmd_vel", 10 + ) # Define service clients here self.cli_motor_set = self.create_client(MotorCommandSet, "motor/set") # Define services (methods callable from the outside) here - self.srv_stop = self.create_service(Trigger, "drivetrain/stop", self.stop_callback) - self.srv_drive = self.create_service(Drive, "drivetrain/drive", self.drive_callback) + self.srv_stop = self.create_service( + Trigger, "drivetrain/stop", self.stop_callback + ) + self.srv_drive = self.create_service( + Drive, "drivetrain/drive", self.drive_callback + ) # Print the ROS Parameters to the terminal below # - self.get_logger().info("FRONT_LEFT_DRIVE has been set to: " + str(self.FRONT_LEFT_DRIVE)) - self.get_logger().info("FRONT_RIGHT_DRIVE has been set to: " + str(self.FRONT_RIGHT_DRIVE)) - self.get_logger().info("BACK_LEFT_DRIVE has been set to: " + str(self.BACK_LEFT_DRIVE)) - self.get_logger().info("BACK_RIGHT_DRIVE has been set to: " + str(self.BACK_RIGHT_DRIVE)) - self.get_logger().info("GAZEBO_SIMULATION has been set to: " + str(self.GAZEBO_SIMULATION)) - self.get_logger().info("MAX_DRIVETRAIN_RPM has been set to: " + str(self.MAX_DRIVETRAIN_RPM)) - self.get_logger().info("EXTENSION_SAFETY_ZONE has been set to: " + str(self.EXTENSION_SAFETY_ZONE)) - - + self.get_logger().info( + "FRONT_LEFT_DRIVE has been set to: " + str(self.FRONT_LEFT_DRIVE) + ) + self.get_logger().info( + "FRONT_RIGHT_DRIVE has been set to: " + str(self.FRONT_RIGHT_DRIVE) + ) + self.get_logger().info( + "BACK_LEFT_DRIVE has been set to: " + str(self.BACK_LEFT_DRIVE) + ) + self.get_logger().info( + "BACK_RIGHT_DRIVE has been set to: " + str(self.BACK_RIGHT_DRIVE) + ) + self.get_logger().info( + "GAZEBO_SIMULATION has been set to: " + str(self.GAZEBO_SIMULATION) + ) + self.get_logger().info( + "MAX_DRIVETRAIN_RPM has been set to: " + str(self.MAX_DRIVETRAIN_RPM) + ) + self.get_logger().info( + "EXTENSION_SAFETY_ZONE has been set to: " + str(self.EXTENSION_SAFETY_ZONE) + ) # Current position of the lift motor in potentiometer units (0 to 1023) self.extension_pos = None # We don't know the current position yet @@ -78,7 +108,10 @@ def drive(self, forward_power: float, turning_power: float) -> None: """This method drives the robot with the desired forward and turning power.""" if ( - (self.extension_pos is None or self.extension_pos > self.EXTENSION_SAFETY_ZONE) + ( + self.extension_pos is None + or self.extension_pos > self.EXTENSION_SAFETY_ZONE + ) and not self.GAZEBO_SIMULATION and (forward_power != 0 or turning_power != 0) ): @@ -106,25 +139,45 @@ def drive(self, forward_power: float, turning_power: float) -> None: # Send velocity (not duty cycle) motor commands to the motor_control_node self.cli_motor_set.call_async( - MotorCommandSet.Request(can_id=self.FRONT_LEFT_DRIVE, type=self.DRIVETRAIN_TYPE, value=leftPower) + MotorCommandSet.Request( + can_id=self.FRONT_LEFT_DRIVE, type=self.DRIVETRAIN_TYPE, value=leftPower + ) ) self.cli_motor_set.call_async( - MotorCommandSet.Request(can_id=self.BACK_LEFT_DRIVE, type=self.DRIVETRAIN_TYPE, value=leftPower) + MotorCommandSet.Request( + can_id=self.BACK_LEFT_DRIVE, type=self.DRIVETRAIN_TYPE, value=leftPower + ) ) self.cli_motor_set.call_async( - MotorCommandSet.Request(can_id=self.FRONT_RIGHT_DRIVE, type=self.DRIVETRAIN_TYPE, value=rightPower) + MotorCommandSet.Request( + can_id=self.FRONT_RIGHT_DRIVE, + type=self.DRIVETRAIN_TYPE, + value=rightPower, + ) ) self.cli_motor_set.call_async( - MotorCommandSet.Request(can_id=self.BACK_RIGHT_DRIVE, type=self.DRIVETRAIN_TYPE, value=rightPower) + MotorCommandSet.Request( + can_id=self.BACK_RIGHT_DRIVE, + type=self.DRIVETRAIN_TYPE, + value=rightPower, + ) ) # Publish the wheel speeds to the gazebo simulation if self.GAZEBO_SIMULATION: if self.DRIVETRAIN_TYPE == "velocity": - self.gazebo_front_left_wheel_pub.publish(Float64(data=leftPower / self.MAX_DRIVETRAIN_RPM)) - self.gazebo_back_left_wheel_pub.publish(Float64(data=leftPower / self.MAX_DRIVETRAIN_RPM)) - self.gazebo_front_right_wheel_pub.publish(Float64(data=rightPower / self.MAX_DRIVETRAIN_RPM)) - self.gazebo_back_right_wheel_pub.publish(Float64(data=rightPower / self.MAX_DRIVETRAIN_RPM)) + self.gazebo_front_left_wheel_pub.publish( + Float64(data=leftPower / self.MAX_DRIVETRAIN_RPM) + ) + self.gazebo_back_left_wheel_pub.publish( + Float64(data=leftPower / self.MAX_DRIVETRAIN_RPM) + ) + self.gazebo_front_right_wheel_pub.publish( + Float64(data=rightPower / self.MAX_DRIVETRAIN_RPM) + ) + self.gazebo_back_right_wheel_pub.publish( + Float64(data=rightPower / self.MAX_DRIVETRAIN_RPM) + ) else: self.gazebo_front_left_wheel_pub.publish(Float64(data=leftPower)) self.gazebo_back_left_wheel_pub.publish(Float64(data=leftPower)) @@ -135,16 +188,24 @@ def drive(self, forward_power: float, turning_power: float) -> None: def stop(self) -> None: """This method stops the drivetrain.""" self.cli_motor_set.call_async( - MotorCommandSet.Request(can_id=self.FRONT_LEFT_DRIVE, type="duty_cycle", value=0.0) + MotorCommandSet.Request( + can_id=self.FRONT_LEFT_DRIVE, type="duty_cycle", value=0.0 + ) ) self.cli_motor_set.call_async( - MotorCommandSet.Request(can_id=self.BACK_LEFT_DRIVE, type="duty_cycle", value=0.0) + MotorCommandSet.Request( + can_id=self.BACK_LEFT_DRIVE, type="duty_cycle", value=0.0 + ) ) self.cli_motor_set.call_async( - MotorCommandSet.Request(can_id=self.FRONT_RIGHT_DRIVE, type="duty_cycle", value=0.0) + MotorCommandSet.Request( + can_id=self.FRONT_RIGHT_DRIVE, type="duty_cycle", value=0.0 + ) ) self.cli_motor_set.call_async( - MotorCommandSet.Request(can_id=self.BACK_RIGHT_DRIVE, type="duty_cycle", value=0.0) + MotorCommandSet.Request( + can_id=self.BACK_RIGHT_DRIVE, type="duty_cycle", value=0.0 + ) ) # Define service callback methods here diff --git a/src/dumper/dumper/dumper_node.py b/src/dumper/dumper/dumper_node.py index 04cc3a86..8f484649 100644 --- a/src/dumper/dumper/dumper_node.py +++ b/src/dumper/dumper/dumper_node.py @@ -34,10 +34,16 @@ def __init__(self): # Define services (methods callable from the outside) here self.srv_toggle = self.create_service( - Trigger, "dumper/toggle", self.toggle_callback, callback_group=self.service_cb_group + Trigger, + "dumper/toggle", + self.toggle_callback, + callback_group=self.service_cb_group, ) self.srv_stop = self.create_service( - Trigger, "dumper/stop", self.stop_callback, callback_group=self.stop_service_cb_group + Trigger, + "dumper/stop", + self.stop_callback, + callback_group=self.stop_service_cb_group, ) self.srv_setPower = self.create_service( SetPower, @@ -47,10 +53,16 @@ def __init__(self): ) self.srv_dumpDumper = self.create_service( - Trigger, "dumper/storeDumper", self.dump_callback, callback_group=self.service_cb_group + Trigger, + "dumper/storeDumper", + self.dump_callback, + callback_group=self.service_cb_group, ) self.srv_storeDumper = self.create_service( - Trigger, "dumper/dumpDumper", self.store_callback, callback_group=self.service_cb_group + Trigger, + "dumper/dumpDumper", + self.store_callback, + callback_group=self.service_cb_group, ) # Define default values for our ROS parameters below # @@ -61,7 +73,9 @@ def __init__(self): self.DUMPER_POWER = self.get_parameter("DUMPER_POWER").value # Print the ROS Parameters to the terminal below # - self.get_logger().info("DUMPER_MOTOR has been set to: " + str(self.DUMPER_MOTOR)) + self.get_logger().info( + "DUMPER_MOTOR has been set to: " + str(self.DUMPER_MOTOR) + ) # Current state of the dumper self.dumped_state = False @@ -77,14 +91,12 @@ def __init__(self): self.KillSwitch_sub = self.create_subscription( Bool, "DumperLimitSwitch", self.killSwitch_callback, 10 ) - + self.auger_stowed_sub = self.create_subscription( Bool, "auger_stowed", self.auger_stowed_callback, 10 ) - self.dumper_stowed_pub = self.create_publisher( - Bool, "dumper_stowed", 10 - ) + self.dumper_stowed_pub = self.create_publisher(Bool, "dumper_stowed", 10) self.dumper_stowed = True self.limitSwitchBottom = False @@ -102,7 +114,9 @@ def set_power(self, dumper_power: float) -> None: def stop(self) -> None: """This method stops the dumper.""" self.cli_motor_set.call_async( - MotorCommandSet.Request(type="duty_cycle", can_id=self.DUMPER_MOTOR, value=0.0) + MotorCommandSet.Request( + type="duty_cycle", can_id=self.DUMPER_MOTOR, value=0.0 + ) ) def toggle(self) -> None: @@ -150,7 +164,9 @@ def dump_dumper(self) -> None: msg = Bool() msg.data = self.dumper_stowed self.dumper_stowed_pub.publish(msg) - while not future.done(): # While loop makes the motor keep going till limit switch is hit + while ( + not future.done() + ): # While loop makes the motor keep going till limit switch is hit if self.cancel_current_srv: self.cancel_current_srv = False break @@ -170,7 +186,9 @@ def store_dumper(self) -> None: # get the variables self.dumped_state = False self.long_service_running = True self.cli_motor_set.call_async( - MotorCommandSet.Request(type="duty_cycle", can_id=self.DUMPER_MOTOR, value=self.DUMPER_POWER) + MotorCommandSet.Request( + type="duty_cycle", can_id=self.DUMPER_MOTOR, value=self.DUMPER_POWER + ) ) while not self.limitSwitchBottom: if self.cancel_current_srv: @@ -199,7 +217,7 @@ def dumper_current_callback(self, msg): def killSwitch_callback(self, msg): # position control... self.LimitSwitchBottom = msg.data - + def auger_stowed_callback(self, msg): self.auger_stowed = msg.data diff --git a/src/rovr_control/rovr_control/read_serial.py b/src/rovr_control/rovr_control/read_serial.py index 64f7f335..48a243c0 100644 --- a/src/rovr_control/rovr_control/read_serial.py +++ b/src/rovr_control/rovr_control/read_serial.py @@ -14,7 +14,9 @@ def __init__(self): self.potentiometerPub = self.create_publisher(Int16, "potentiometer", 10) self.DumperLimitSwitchPub = self.create_publisher(Bool, "DumperLimitSwitch", 10) - self.ExtensionLimitSwitchPub = self.create_publisher(Bool, "ExtensionLimitSwitch", 10) + self.ExtensionLimitSwitchPub = self.create_publisher( + Bool, "ExtensionLimitSwitch", 10 + ) # Services to control the relay-driven agitator motor self.srv_bigonoff = self.create_service( @@ -67,7 +69,6 @@ def timer_callback(self): extension_bool_msg.data = decoded[2] self.ExtensionLimitSwitchPub.publish(extension_bool_msg) - def big_on_off_callback(self, request, response): # request.data == True → ON, False → OFF cmd = b"1" if request.data else b"0"