Skip to content

Commit

Permalink
Deleted the auto_cycle() method
Browse files Browse the repository at this point in the history
  • Loading branch information
Isopod00 committed Aug 21, 2024
1 parent 6a7ba3d commit 0a1e800
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 55 deletions.
54 changes: 0 additions & 54 deletions src/rovr_control/rovr_control/main_control_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
# Provides a “navigation as a library” capability
from nav2_simple_commander.robot_navigator import (
BasicNavigator,
TaskResult,
)

# Import ROS 2 formatted message types
Expand Down Expand Up @@ -284,47 +283,6 @@ async def auto_offload_procedure(self) -> None:
self.get_logger().warn("Autonomous Offload Procedure Terminated\n")
self.end_autonomous() # Return to Teleop mode

# TODO: This autonomous routine has not been tested yet!
async def auto_cycle_procedure(self) -> None:
"""This method lays out the procedure for doing a complete autonomous cycle!"""
self.get_logger().info("\nStarting an Autonomous Cycle!")
try: # Wrap the autonomous procedure in a try-except
# Navigate to the dig_location, run the dig procedure,
# then navigate to the berm zone and run the offload procedure
if self.field_calibrated.done() and self.field_calibrated.result() is False:
self.get_logger().error("Field coordinates must be calibrated first!")
self.end_autonomous() # Return to Teleop mode
return
self.nav2.goToPose(self.dig_location) # Navigate to the dig location
while not self.nav2.isTaskComplete(): # Wait for the dig location to be reached
await asyncio.sleep(0.1) # Allows other async tasks to continue running (this is non-blocking)
if self.nav2.getResult() == TaskResult.FAILED:
self.get_logger().error("Failed to reach the dig location!")
self.end_autonomous() # Return to Teleop mode
return
self.autonomous_digging_process = asyncio.ensure_future(
self.auto_dig_procedure()
) # Start the auto dig process
while not self.autonomous_digging_process.done(): # Wait for the dig process to complete
await asyncio.sleep(0.1) # Allows other async tasks to continue running (this is non-blocking)
self.nav2.goToPose(self.autonomous_berm_location) # Navigate to the berm zone
while not self.nav2.isTaskComplete(): # Wait for the berm zone to be reached
await asyncio.sleep(0.1) # Allows other async tasks to continue running (this is non-blocking)
if self.nav2.getResult() == TaskResult.FAILED:
self.get_logger().error("Failed to reach the berm zone!")
self.end_autonomous() # Return to Teleop mode
return
self.autonomous_offload_process = asyncio.ensure_future(
self.auto_offload_procedure()
) # Start the auto offload process
while not self.autonomous_offload_process.done(): # Wait for the offload process to complete
await asyncio.sleep(0.1) # Allows other async tasks to continue running (this is non-blocking)
self.get_logger().info("Completed an Autonomous Cycle!\n")
self.end_autonomous() # Return to Teleop mode
except asyncio.CancelledError: # Put termination code here
self.get_logger().info("Autonomous Cycle Terminated\n")
self.end_autonomous() # Return to Teleop mode

def skimmer_goal_callback(self, msg: Bool) -> None:
"""Update the member variable accordingly."""
self.skimmer_goal_reached = msg.data
Expand Down Expand Up @@ -435,18 +393,6 @@ def joystick_callback(self, msg: Joy) -> None:
self.autonomous_offload_process.cancel() # Terminate the auto offload process
self.autonomous_offload_process = None

# # Check if the autonomous cycle button is pressed
# if msg.buttons[RIGHT_BUMPER] == 1 and buttons[RIGHT_BUMPER] == 0:
# if self.state == states["Teleop"]:
# self.stop_all_subsystems() # Stop all subsystems
# self.state = states["Autonomous"]
# self.autonomous_cycle_process = asyncio.ensure_future(
# self.auto_cycle_procedure()
# ) # Start the autonomous cycle!
# elif self.state == states["Autonomous"]:
# self.autonomous_cycle_process.cancel() # Terminate the autonomous cycle process
# self.autonomous_cycle_process = None

# Update button states (this allows us to detect changing button states)
for index in range(len(buttons)):
buttons[index] = msg.buttons[index]
Expand Down
5 changes: 4 additions & 1 deletion src/rovr_interfaces/action/CalibrateFieldCoordinates.action
Original file line number Diff line number Diff line change
@@ -1,2 +1,5 @@
# Request
---
---
# Result
---
# Feedback

0 comments on commit 0a1e800

Please sign in to comment.