From 3c027bc0fd84fc533476db73d2bbf1dcaf089b7a Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Mon, 24 Apr 2023 18:14:10 -0400 Subject: [PATCH 1/9] Updated poses for the warehouse world --- .../turtlebot4_python_tutorials/nav_through_poses.py | 12 ++++++------ .../turtlebot4_python_tutorials/nav_to_pose.py | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/nav_through_poses.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/nav_through_poses.py index 0f04fd5..b1a8f46 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/nav_through_poses.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/nav_through_poses.py @@ -40,12 +40,12 @@ def main(): # Set goal poses goal_pose = [] - goal_pose.append(navigator.getPoseStamped([0.0, -1.0], TurtleBot4Directions.NORTH)) - goal_pose.append(navigator.getPoseStamped([1.7, -1.0], TurtleBot4Directions.EAST)) - goal_pose.append(navigator.getPoseStamped([1.6, -3.5], TurtleBot4Directions.NORTH)) - goal_pose.append(navigator.getPoseStamped([6.75, -3.46], TurtleBot4Directions.NORTH_WEST)) - goal_pose.append(navigator.getPoseStamped([7.4, -1.0], TurtleBot4Directions.SOUTH)) - goal_pose.append(navigator.getPoseStamped([-1.0, -1.0], TurtleBot4Directions.WEST)) + goal_pose.append(navigator.getPoseStamped([-3.0, 0.0], TurtleBot4Directions.EAST)) + goal_pose.append(navigator.getPoseStamped([-3.0, -3.0], TurtleBot4Directions.NORTH)) + goal_pose.append(navigator.getPoseStamped([3.0, -3.0], TurtleBot4Directions.NORTH_WEST)) + goal_pose.append(navigator.getPoseStamped([9.0, -1.0], TurtleBot4Directions.WEST)) + goal_pose.append(navigator.getPoseStamped([9.0, 1.0], TurtleBot4Directions.SOUTH)) + goal_pose.append(navigator.getPoseStamped([-1.0, 1.0], TurtleBot4Directions.EAST)) # Undock navigator.undock() diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/nav_to_pose.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/nav_to_pose.py index fce9235..093063b 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/nav_to_pose.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/nav_to_pose.py @@ -39,7 +39,7 @@ def main(): navigator.waitUntilNav2Active() # Set goal poses - goal_pose = navigator.getPoseStamped([13.0, 5.0], TurtleBot4Directions.EAST) + goal_pose = navigator.getPoseStamped([-13.0, 9.0], TurtleBot4Directions.EAST) # Undock navigator.undock() From 2931dea269eba00dbb7b9b60690c0c2060fb0714 Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Mon, 1 May 2023 23:26:37 -0400 Subject: [PATCH 2/9] Add Patrol Loop example --- turtlebot4_python_tutorials/setup.py | 1 + .../patrol_loop.py | 138 ++++++++++++++++++ 2 files changed, 139 insertions(+) create mode 100644 turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py diff --git a/turtlebot4_python_tutorials/setup.py b/turtlebot4_python_tutorials/setup.py index 4a63e98..7a81ace 100644 --- a/turtlebot4_python_tutorials/setup.py +++ b/turtlebot4_python_tutorials/setup.py @@ -26,6 +26,7 @@ 'nav_through_poses = turtlebot4_python_tutorials.nav_through_poses:main', 'follow_waypoints = turtlebot4_python_tutorials.follow_waypoints:main', 'create_path = turtlebot4_python_tutorials.create_path:main', + 'patrol_loop = turtlebot4_python_tutorials.patrol_loop:main', ], }, ) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py new file mode 100644 index 0000000..9fe6def --- /dev/null +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py @@ -0,0 +1,138 @@ +#!/usr/bin/env python3 + +# Copyright 2023 Clearpath Robotics, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# @author Hilary Luo (hluo@clearpathrobotics.com) + +import rclpy + +from rclpy.node import Node +from rclpy.qos import qos_profile_sensor_data +from rclpy.executors import SingleThreadedExecutor +from threading import Lock, Thread +from time import sleep + +from sensor_msgs.msg import BatteryState +from turtlebot4_navigation.turtlebot4_navigator import TurtleBot4Directions, TurtleBot4Navigator + +BATTERY_HIGH = 0.95 +BATTERY_LOW = 0.2 # when the robot will go charge +BATTERY_CRITICAL = 0.1 # when the robot will shutdown + +class BatteryMonitor(Node): + + def __init__(self, lock): + super().__init__('battery_monitor') + + self.lock = lock + + # Subscribe to the /battery_state topic + self.battery_state_subscriber = self.create_subscription( + BatteryState, + '/battery_state', + self.battery_state_callback, + qos_profile_sensor_data) + + # Callbacks + def battery_state_callback(self, batt_msg: BatteryState): + with self.lock: + self.battery_percent = batt_msg.percentage + + def thread_function(self): + executor = SingleThreadedExecutor() + executor.add_node(self) + executor.spin() + +def main(args=None): + rclpy.init(args=args) + + lock = Lock() + battery_monitor = BatteryMonitor(lock) + + navigator = TurtleBot4Navigator() + battery_percent = None + position_index = 0 + + thread = Thread(target=battery_monitor.thread_function, daemon=True) + thread.start() + + # Start on dock + if not navigator.getDockedStatus(): + navigator.info('Docking before intialising pose') + navigator.dock() + + # Set initial pose + initial_pose = navigator.getPoseStamped([0.0, 0.0], TurtleBot4Directions.NORTH) + navigator.setInitialPose(initial_pose) + + # Wait for Nav2 + navigator.waitUntilNav2Active() + + # Undock + navigator.undock() + + # Prepare goal poses + goal_pose = [] + goal_pose.append(navigator.getPoseStamped([-5.0, 1.0], TurtleBot4Directions.EAST)) + goal_pose.append(navigator.getPoseStamped([-5.0, -23.0], TurtleBot4Directions.NORTH)) + goal_pose.append(navigator.getPoseStamped([9.0, -23.0], TurtleBot4Directions.NORTH_WEST)) + goal_pose.append(navigator.getPoseStamped([10.0, 2.0], TurtleBot4Directions.WEST)) + + while True: + with lock: + battery_percent = battery_monitor.battery_percent + + if (battery_percent is not None): + navigator.info(f'Battery is at {(battery_percent*100):.2f}% charge') + + # Check battery charge level + if (battery_percent < BATTERY_CRITICAL): + navigator.error("Battery critically low. Charge or power down") + break + elif (battery_percent < BATTERY_LOW): + # Go near the dock + navigator.info('Docking for charge') + navigator.startToPose(navigator.getPoseStamped([-1.0, 1.0], TurtleBot4Directions.EAST)) + navigator.dock() + + if not navigator.getDockedStatus(): + navigator.error("Robot failed to dock") + break + + # Wait until charged + navigator.info('Charging...') + while (battery_percent < BATTERY_HIGH): + sleep(15) + with lock: + battery_percent = battery_monitor.battery_percent + print(f'Battery is at {(battery_percent*100):.2f}% charge', end='\r') + + # Undock + navigator.undock() + position_index = 0 + + else: + #Navigate to next position + navigator.startToPose(goal_pose[position_index]) + + position_index = position_index + 1 + if position_index >= len(goal_pose): + position_index = 0 + + battery_monitor.destroy_node() + rclpy.shutdown() + +if __name__ == '__main__': + main() From 631a50b5d29230f064bc09926e13f4afca0e8aba Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Tue, 2 May 2023 13:41:03 -0400 Subject: [PATCH 3/9] Added mail delivery example --- turtlebot4_python_tutorials/setup.py | 1 + .../mail_delivery.py | 72 +++++++++++++++++++ 2 files changed, 73 insertions(+) create mode 100644 turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py diff --git a/turtlebot4_python_tutorials/setup.py b/turtlebot4_python_tutorials/setup.py index 7a81ace..2cb4382 100644 --- a/turtlebot4_python_tutorials/setup.py +++ b/turtlebot4_python_tutorials/setup.py @@ -27,6 +27,7 @@ 'follow_waypoints = turtlebot4_python_tutorials.follow_waypoints:main', 'create_path = turtlebot4_python_tutorials.create_path:main', 'patrol_loop = turtlebot4_python_tutorials.patrol_loop:main', + 'mail_delivery = turtlebot4_python_tutorials.mail_delivery:main', ], }, ) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py new file mode 100644 index 0000000..0f4d65c --- /dev/null +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py @@ -0,0 +1,72 @@ +#!/usr/bin/env python3 + +# Copyright 2023 Clearpath Robotics, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +# +# @author Hilary Luo (hluo@clearpathrobotics.com) + +import rclpy + +from operator import itemgetter +from pick import pick + +from turtlebot4_navigation.turtlebot4_navigator import TurtleBot4Directions, TurtleBot4Navigator + + +def main(args=None): + rclpy.init(args=args) + + navigator = TurtleBot4Navigator() + + # Start on dock + if not navigator.getDockedStatus(): + navigator.info('Docking before intialising pose') + navigator.dock() + + # Set initial pose + initial_pose = navigator.getPoseStamped([0.0, 0.0], TurtleBot4Directions.NORTH) + navigator.setInitialPose(initial_pose) + + # Wait for Nav2 + navigator.waitUntilNav2Active() + + # Undock + navigator.undock() + + # Prepare goal pose options + goal_options = [] + goal_options.append({'name': 'Home', 'pose': navigator.getPoseStamped([-1.0, 1.0], TurtleBot4Directions.EAST)}) + goal_options.append({'name': 'Position 1', 'pose': navigator.getPoseStamped([10.0, 6.0], TurtleBot4Directions.EAST)}) + goal_options.append({'name': 'Position 2', 'pose': navigator.getPoseStamped([-9.0, 9.0], TurtleBot4Directions.NORTH)}) + goal_options.append({'name': 'Position 3', 'pose': navigator.getPoseStamped([-12.0, 2.0], TurtleBot4Directions.NORTH_WEST)}) + goal_options.append({'name': 'Position 4', 'pose': navigator.getPoseStamped([3.0, -7.0], TurtleBot4Directions.WEST)}) + goal_options.append({'name': 'Exit', 'pose': None}) + + message= 'Welcome to the mail delivery service. Choose the destination (use arrow keys).' + + while True: + # Prompt the user for the goal location + selection, index = pick(list(map(itemgetter('name'), goal_options)), message) + + # Check for exit + if selection is 'Exit': + break + + #Navigate to requested position + navigator.startToPose(goal_options[index]['pose']) + + rclpy.shutdown() + +if __name__ == '__main__': + main() From 79af03a3a3d981fd7e7946c16285a0c193d5da06 Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Tue, 2 May 2023 14:10:36 -0400 Subject: [PATCH 4/9] Linting fixes --- .../mail_delivery.py | 42 ++++++++++++------- .../patrol_loop.py | 23 ++++++---- 2 files changed, 42 insertions(+), 23 deletions(-) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py index 0f4d65c..24f5bf8 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py @@ -16,11 +16,12 @@ # # @author Hilary Luo (hluo@clearpathrobotics.com) -import rclpy - from operator import itemgetter + from pick import pick +import rclpy + from turtlebot4_navigation.turtlebot4_navigator import TurtleBot4Directions, TurtleBot4Navigator @@ -45,28 +46,41 @@ def main(args=None): navigator.undock() # Prepare goal pose options - goal_options = [] - goal_options.append({'name': 'Home', 'pose': navigator.getPoseStamped([-1.0, 1.0], TurtleBot4Directions.EAST)}) - goal_options.append({'name': 'Position 1', 'pose': navigator.getPoseStamped([10.0, 6.0], TurtleBot4Directions.EAST)}) - goal_options.append({'name': 'Position 2', 'pose': navigator.getPoseStamped([-9.0, 9.0], TurtleBot4Directions.NORTH)}) - goal_options.append({'name': 'Position 3', 'pose': navigator.getPoseStamped([-12.0, 2.0], TurtleBot4Directions.NORTH_WEST)}) - goal_options.append({'name': 'Position 4', 'pose': navigator.getPoseStamped([3.0, -7.0], TurtleBot4Directions.WEST)}) - goal_options.append({'name': 'Exit', 'pose': None}) - - message= 'Welcome to the mail delivery service. Choose the destination (use arrow keys).' - + goal_options = [ + {'name': 'Home', + 'pose': navigator.getPoseStamped([-1.0, 1.0], TurtleBot4Directions.EAST)}, + + {'name': 'Position 1', + 'pose': navigator.getPoseStamped([10.0, 6.0], TurtleBot4Directions.EAST)}, + + {'name': 'Position 2', + 'pose': navigator.getPoseStamped([-9.0, 9.0], TurtleBot4Directions.NORTH)}, + + {'name': 'Position 3', + 'pose': navigator.getPoseStamped([-12.0, 2.0], TurtleBot4Directions.NORTH_WEST)}, + + {'name': 'Position 4', + 'pose': navigator.getPoseStamped([3.0, -7.0], TurtleBot4Directions.WEST)}, + + {'name': 'Exit', + 'pose': None} + ] + + message = 'Welcome to the mail delivery service. Choose the destination (use arrow keys).' + while True: # Prompt the user for the goal location selection, index = pick(list(map(itemgetter('name'), goal_options)), message) # Check for exit - if selection is 'Exit': + if selection == 'Exit': break - #Navigate to requested position + # Navigate to requested position navigator.startToPose(goal_options[index]['pose']) rclpy.shutdown() + if __name__ == '__main__': main() diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py index 9fe6def..79a2013 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py @@ -16,13 +16,14 @@ # # @author Hilary Luo (hluo@clearpathrobotics.com) +from threading import Lock, Thread +from time import sleep + import rclpy +from rclpy.executors import SingleThreadedExecutor from rclpy.node import Node from rclpy.qos import qos_profile_sensor_data -from rclpy.executors import SingleThreadedExecutor -from threading import Lock, Thread -from time import sleep from sensor_msgs.msg import BatteryState from turtlebot4_navigation.turtlebot4_navigator import TurtleBot4Directions, TurtleBot4Navigator @@ -31,6 +32,7 @@ BATTERY_LOW = 0.2 # when the robot will go charge BATTERY_CRITICAL = 0.1 # when the robot will shutdown + class BatteryMonitor(Node): def __init__(self, lock): @@ -55,6 +57,7 @@ def thread_function(self): executor.add_node(self) executor.spin() + def main(args=None): rclpy.init(args=args) @@ -89,7 +92,7 @@ def main(args=None): goal_pose.append(navigator.getPoseStamped([-5.0, -23.0], TurtleBot4Directions.NORTH)) goal_pose.append(navigator.getPoseStamped([9.0, -23.0], TurtleBot4Directions.NORTH_WEST)) goal_pose.append(navigator.getPoseStamped([10.0, 2.0], TurtleBot4Directions.WEST)) - + while True: with lock: battery_percent = battery_monitor.battery_percent @@ -99,16 +102,17 @@ def main(args=None): # Check battery charge level if (battery_percent < BATTERY_CRITICAL): - navigator.error("Battery critically low. Charge or power down") + navigator.error('Battery critically low. Charge or power down') break elif (battery_percent < BATTERY_LOW): # Go near the dock navigator.info('Docking for charge') - navigator.startToPose(navigator.getPoseStamped([-1.0, 1.0], TurtleBot4Directions.EAST)) + navigator.startToPose(navigator.getPoseStamped([-1.0, 1.0], + TurtleBot4Directions.EAST)) navigator.dock() if not navigator.getDockedStatus(): - navigator.error("Robot failed to dock") + navigator.error('Robot failed to dock') break # Wait until charged @@ -122,9 +126,9 @@ def main(args=None): # Undock navigator.undock() position_index = 0 - + else: - #Navigate to next position + # Navigate to next position navigator.startToPose(goal_pose[position_index]) position_index = position_index + 1 @@ -134,5 +138,6 @@ def main(args=None): battery_monitor.destroy_node() rclpy.shutdown() + if __name__ == '__main__': main() From a6208387114a07030099c50f55416c6285570a7f Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Thu, 4 May 2023 08:46:36 -0400 Subject: [PATCH 5/9] subscribe to local battery_state topic instead of global --- .../turtlebot4_python_tutorials/patrol_loop.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py index 79a2013..ff04211 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py @@ -43,7 +43,7 @@ def __init__(self, lock): # Subscribe to the /battery_state topic self.battery_state_subscriber = self.create_subscription( BatteryState, - '/battery_state', + 'battery_state', self.battery_state_callback, qos_profile_sensor_data) From cadcb6c6ffba5f34fb0fe124fe3bcf1288393b39 Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Thu, 4 May 2023 13:22:00 -0400 Subject: [PATCH 6/9] Updated user prompt to only rely on the default input() function --- .../mail_delivery.py | 31 ++++++++++++++----- 1 file changed, 24 insertions(+), 7 deletions(-) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py index 24f5bf8..c959840 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py @@ -18,8 +18,6 @@ from operator import itemgetter -from pick import pick - import rclpy from turtlebot4_navigation.turtlebot4_navigator import TurtleBot4Directions, TurtleBot4Navigator @@ -66,18 +64,37 @@ def main(args=None): 'pose': None} ] - message = 'Welcome to the mail delivery service. Choose the destination (use arrow keys).' + navigator.info('Welcome to the mail delivery service.') while True: + # Create a list of the goals for display + options_text = 'Please enter the number corresponding to the desired robot goal position:\n' + for i in range(len(goal_options)): + options_text += f' {i}. {goal_options[i]["name"]}\n' + # Prompt the user for the goal location - selection, index = pick(list(map(itemgetter('name'), goal_options)), message) + raw_input = input(f'{options_text}Selection: ') + + selected_index = 0 + + # Verify that the value input is a number + try: + selected_index = int(raw_input) + except ValueError: + navigator.error(f'Invalid goal selection: {raw_input}') + continue + + # Verify that the user input is within a valid range + if (selected_index < 0) or (selected_index >= len(goal_options)): + navigator.error(f'Goal selection out of bounds: {selected_index}') # Check for exit - if selection == 'Exit': + elif goal_options[selected_index]['name'] == 'Exit': break - # Navigate to requested position - navigator.startToPose(goal_options[index]['pose']) + else: + # Navigate to requested position + navigator.startToPose(goal_options[selected_index]['pose']) rclpy.shutdown() From 58bd41777ca8c024022f3025633744ffa9dd8d1e Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Thu, 4 May 2023 13:39:28 -0400 Subject: [PATCH 7/9] Switched battery charging print out to use navigator info and print once every percent increase --- .../turtlebot4_python_tutorials/patrol_loop.py | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py index ff04211..5df7e63 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/patrol_loop.py @@ -16,6 +16,7 @@ # # @author Hilary Luo (hluo@clearpathrobotics.com) +from math import floor from threading import Lock, Thread from time import sleep @@ -117,11 +118,16 @@ def main(args=None): # Wait until charged navigator.info('Charging...') + battery_percent_prev = 0 while (battery_percent < BATTERY_HIGH): sleep(15) + battery_percent_prev = floor(battery_percent*100)/100 with lock: battery_percent = battery_monitor.battery_percent - print(f'Battery is at {(battery_percent*100):.2f}% charge', end='\r') + + # Print charge level every time it increases a percent + if battery_percent > (battery_percent_prev + 0.01): + navigator.info(f'Battery is at {(battery_percent*100):.2f}% charge') # Undock navigator.undock() From 37475159db498cc52177525536d61326b201899a Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Thu, 4 May 2023 13:56:29 -0400 Subject: [PATCH 8/9] Unused import --- .../turtlebot4_python_tutorials/mail_delivery.py | 2 -- 1 file changed, 2 deletions(-) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py index c959840..a02e785 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py @@ -16,8 +16,6 @@ # # @author Hilary Luo (hluo@clearpathrobotics.com) -from operator import itemgetter - import rclpy from turtlebot4_navigation.turtlebot4_navigator import TurtleBot4Directions, TurtleBot4Navigator From a05a7f0794919a4dcb483993bd60dd93be0d89a3 Mon Sep 17 00:00:00 2001 From: Hilary Luo Date: Thu, 4 May 2023 13:59:32 -0400 Subject: [PATCH 9/9] Renamed variable --- .../turtlebot4_python_tutorials/mail_delivery.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py index a02e785..a8482bc 100644 --- a/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py +++ b/turtlebot4_python_tutorials/turtlebot4_python_tutorials/mail_delivery.py @@ -66,12 +66,12 @@ def main(args=None): while True: # Create a list of the goals for display - options_text = 'Please enter the number corresponding to the desired robot goal position:\n' + options_str = 'Please enter the number corresponding to the desired robot goal position:\n' for i in range(len(goal_options)): - options_text += f' {i}. {goal_options[i]["name"]}\n' + options_str += f' {i}. {goal_options[i]["name"]}\n' # Prompt the user for the goal location - raw_input = input(f'{options_text}Selection: ') + raw_input = input(f'{options_str}Selection: ') selected_index = 0