Skip to content

Commit 5c61644

Browse files
authored
Python string format (#2466)
* Convert to python format strings for readability * Merge concatenated strings * Revert converting generated files * Single quotes for consistency * Just print the exception
1 parent a800b89 commit 5c61644

File tree

12 files changed

+89
-92
lines changed

12 files changed

+89
-92
lines changed

‎nav2_bringup/bringup/launch/multi_tb3_simulation_launch.py‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -123,7 +123,7 @@ def generate_launch_description():
123123
# Define commands for launching the navigation instances
124124
nav_instances_cmds = []
125125
for robot in robots:
126-
params_file = LaunchConfiguration(robot['name'] + '_params_file')
126+
params_file = LaunchConfiguration(f"{robot['name']}_params_file")
127127

128128
group = GroupAction([
129129
IncludeLaunchDescription(

‎nav2_bringup/nav2_gazebo_spawner/nav2_gazebo_spawner/nav2_gazebo_spawner.py‎

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ def main():
6767
if args.turtlebot_type is not None:
6868
sdf_file_path = os.path.join(
6969
get_package_share_directory('turtlebot3_gazebo'), 'models',
70-
'turtlebot3_{}'.format(args.turtlebot_type), 'model.sdf')
70+
f'turtlebot3_{args.turtlebot_type}', 'model.sdf')
7171
else:
7272
sdf_file_path = args.sdf
7373

@@ -86,7 +86,7 @@ def main():
8686
if args.robot_namespace:
8787
ros_params = plugin.find('ros')
8888
ros_tf_remap = ET.SubElement(ros_params, 'remapping')
89-
ros_tf_remap.text = '/tf:=/' + args.robot_namespace + '/tf'
89+
ros_tf_remap.text = f'/tf:=/{args.robot_namespace}/tf'
9090

9191
# Set data for request
9292
request = SpawnEntity.Request()
@@ -101,10 +101,10 @@ def main():
101101
future = client.call_async(request)
102102
rclpy.spin_until_future_complete(node, future, timeout_sec=args.timeout)
103103
if future.result() is not None:
104-
print('response: %r' % future.result())
104+
print(f'response: {future.result()!r}')
105105
else:
106106
raise RuntimeError(
107-
'exception while calling service: %r' % future.exception())
107+
f'exception while calling service: {future.exception()!r}')
108108

109109
node.get_logger().info('Done! Shutting down node.')
110110
node.destroy_node()

‎nav2_map_server/test/test_launch_files/map_saver_node.launch.py‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222

2323

2424
def generate_launch_description():
25-
map_publisher = os.path.dirname(os.getenv('TEST_EXECUTABLE')) + '/test_map_saver_publisher'
25+
map_publisher = f"{os.path.dirname(os.getenv('TEST_EXECUTABLE'))}/test_map_saver_publisher"
2626

2727
ld = LaunchDescription()
2828

‎nav2_simple_commander/nav2_simple_commander/demo_picking.py‎

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -75,7 +75,7 @@ def main():
7575
shelf_item_pose.pose.position.y = shelf_positions[request_item_location][1]
7676
shelf_item_pose.pose.orientation.z = 1.0
7777
shelf_item_pose.pose.orientation.w = 0.0
78-
print('Received request for item picking at ' + request_item_location + '.')
78+
print(f'Received request for item picking at {request_item_location}.')
7979
navigator.goToPose(shelf_item_pose)
8080

8181
# Do something during our route
@@ -105,12 +105,12 @@ def main():
105105
navigator.goToPose(shipping_destination)
106106

107107
elif result == NavigationResult.CANCELED:
108-
print('Task at ' + request_item_location + ' was canceled. Returning to staging point...')
108+
print(f'Task at {request_item_location} was canceled. Returning to staging point...')
109109
initial_pose.header.stamp = navigator.get_clock().now().to_msg()
110110
navigator.goToPose(initial_pose)
111111

112112
elif result == NavigationResult.FAILED:
113-
print('Task at ' + request_item_location + ' failed!')
113+
print(f'Task at {request_item_location} failed!')
114114
exit(-1)
115115

116116
while not navigator.isNavComplete():

‎nav2_simple_commander/nav2_simple_commander/robot_navigator.py‎

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -96,14 +96,14 @@ def goThroughPoses(self, poses):
9696
goal_msg = NavigateThroughPoses.Goal()
9797
goal_msg.poses = poses
9898

99-
self.info('Navigating with ' + str(len(goal_msg.poses)) + ' goals.' + '...')
99+
self.info(f'Navigating with {len(goal_msg.poses)} goals....')
100100
send_goal_future = self.nav_through_poses_client.send_goal_async(goal_msg,
101101
self._feedbackCallback)
102102
rclpy.spin_until_future_complete(self, send_goal_future)
103103
self.goal_handle = send_goal_future.result()
104104

105105
if not self.goal_handle.accepted:
106-
self.error('Goal with ' + str(len(poses)) + ' poses was rejected!')
106+
self.error(f'Goal with {len(poses)} poses was rejected!')
107107
return False
108108

109109
self.result_future = self.goal_handle.get_result_async()
@@ -142,14 +142,14 @@ def followWaypoints(self, poses):
142142
goal_msg = FollowWaypoints.Goal()
143143
goal_msg.poses = poses
144144

145-
self.info('Following ' + str(len(goal_msg.poses)) + ' goals.' + '...')
145+
self.info(f'Following {len(goal_msg.poses)} goals....')
146146
send_goal_future = self.follow_waypoints_client.send_goal_async(goal_msg,
147147
self._feedbackCallback)
148148
rclpy.spin_until_future_complete(self, send_goal_future)
149149
self.goal_handle = send_goal_future.result()
150150

151151
if not self.goal_handle.accepted:
152-
self.error('Following ' + str(len(poses)) + ' waypoints request was rejected!')
152+
self.error(f'Following {len(poses)} waypoints request was rejected!')
153153
return False
154154

155155
self.result_future = self.goal_handle.get_result_async()
@@ -172,7 +172,7 @@ def isNavComplete(self):
172172
if self.result_future.result():
173173
self.status = self.result_future.result().status
174174
if self.status != GoalStatus.STATUS_SUCCEEDED:
175-
self.debug('Goal with failed with status code: {0}'.format(self.status))
175+
self.debug(f'Goal with failed with status code: {self.status}')
176176
return True
177177
else:
178178
# Timed out, still processing, not complete yet
@@ -227,7 +227,7 @@ def getPath(self, start, goal):
227227
rclpy.spin_until_future_complete(self, self.result_future)
228228
self.status = self.result_future.result().status
229229
if self.status != GoalStatus.STATUS_SUCCEEDED:
230-
self.warn('Getting path failed with status code: {0}'.format(self.status))
230+
self.warn(f'Getting path failed with status code: {self.status}')
231231
return None
232232

233233
return self.result_future.result().result.path
@@ -255,7 +255,7 @@ def getPathThroughPoses(self, start, goals):
255255
rclpy.spin_until_future_complete(self, self.result_future)
256256
self.status = self.result_future.result().status
257257
if self.status != GoalStatus.STATUS_SUCCEEDED:
258-
self.warn('Getting path failed with status code: {0}'.format(self.status))
258+
self.warn(f'Getting path failed with status code: {self.status}')
259259
return None
260260

261261
return self.result_future.result().result.path
@@ -322,10 +322,10 @@ def lifecycleStartup(self):
322322
self.info('Starting up lifecycle nodes based on lifecycle_manager.')
323323
for srv_name, srv_type in self.get_service_names_and_types():
324324
if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
325-
self.info('Starting up ' + srv_name)
325+
self.info(f'Starting up {srv_name}')
326326
mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
327327
while not mgr_client.wait_for_service(timeout_sec=1.0):
328-
self.info(srv_name + ' service not available, waiting...')
328+
self.info(f'{srv_name} service not available, waiting...')
329329
req = ManageLifecycleNodes.Request()
330330
req.command = ManageLifecycleNodes.Request().STARTUP
331331
future = mgr_client.call_async(req)
@@ -346,10 +346,10 @@ def lifecycleShutdown(self):
346346
self.info('Shutting down lifecycle nodes based on lifecycle_manager.')
347347
for srv_name, srv_type in self.get_service_names_and_types():
348348
if srv_type[0] == 'nav2_msgs/srv/ManageLifecycleNodes':
349-
self.info('Shutting down ' + srv_name)
349+
self.info(f'Shutting down {srv_name}')
350350
mgr_client = self.create_client(ManageLifecycleNodes, srv_name)
351351
while not mgr_client.wait_for_service(timeout_sec=1.0):
352-
self.info(srv_name + ' service not available, waiting...')
352+
self.info(f'{srv_name} service not available, waiting...')
353353
req = ManageLifecycleNodes.Request()
354354
req.command = ManageLifecycleNodes.Request().SHUTDOWN
355355
future = mgr_client.call_async(req)
@@ -359,21 +359,21 @@ def lifecycleShutdown(self):
359359

360360
def _waitForNodeToActivate(self, node_name):
361361
# Waits for the node within the tester namespace to become active
362-
self.debug('Waiting for ' + node_name + ' to become active..')
363-
node_service = node_name + '/get_state'
362+
self.debug(f'Waiting for {node_name} to become active..')
363+
node_service = f'{node_name}/get_state'
364364
state_client = self.create_client(GetState, node_service)
365365
while not state_client.wait_for_service(timeout_sec=1.0):
366-
self.info(node_service + ' service not available, waiting...')
366+
self.info(f'{node_service} service not available, waiting...')
367367

368368
req = GetState.Request()
369369
state = 'unknown'
370370
while state != 'active':
371-
self.debug('Getting ' + node_name + ' state...')
371+
self.debug(f'Getting {node_name} state...')
372372
future = state_client.call_async(req)
373373
rclpy.spin_until_future_complete(self, future)
374374
if future.result() is not None:
375375
state = future.result().current_state.label
376-
self.debug('Result of get_state: %s' % state)
376+
self.debug(f'Result of get_state: {state}')
377377
time.sleep(2)
378378
return
379379

‎nav2_system_tests/src/costmap_filters/tester_node.py‎

Lines changed: 13 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -210,7 +210,7 @@ def runNavigateAction(self, goal_pose: Optional[Pose] = None):
210210
rclpy.spin_until_future_complete(self, get_result_future)
211211
status = get_result_future.result().status
212212
if status != GoalStatus.STATUS_SUCCEEDED:
213-
self.info_msg('Goal failed with status code: {0}'.format(status))
213+
self.info_msg(f'Goal failed with status code: {status}')
214214
return False
215215

216216
self.info_msg('Goal succeeded!')
@@ -230,8 +230,7 @@ def checkKeepout(self, x, y):
230230
self.warn_msg('Filter mask was not received')
231231
elif self.isInKeepout(x, y):
232232
self.filter_test_result = False
233-
self.error_msg('Pose (' + str(x) + ', ' +
234-
str(y) + ') belongs to keepout zone')
233+
self.error_msg(f'Pose ({x}, {y}) belongs to keepout zone')
235234
return False
236235
return True
237236

@@ -286,7 +285,7 @@ def dwbCostCloudCallback(self, msg):
286285
self.cost_cloud_received = True
287286

288287
def speedLimitCallback(self, msg):
289-
self.info_msg('Received speed limit: ' + str(msg.speed_limit))
288+
self.info_msg(f'Received speed limit: {msg.speed_limit}')
290289
self.checkSpeed(self.speed_it, msg.speed_limit)
291290
self.speed_it += 1
292291

@@ -340,25 +339,25 @@ def distanceFromGoal(self):
340339
d_x = self.current_pose.position.x - self.goal_pose.position.x
341340
d_y = self.current_pose.position.y - self.goal_pose.position.y
342341
distance = math.sqrt(d_x * d_x + d_y * d_y)
343-
self.info_msg('Distance from goal is: ' + str(distance))
342+
self.info_msg(f'Distance from goal is: {distance}')
344343
return distance
345344

346345
def wait_for_node_active(self, node_name: str):
347346
# Waits for the node within the tester namespace to become active
348-
self.info_msg('Waiting for ' + node_name + ' to become active')
349-
node_service = node_name + '/get_state'
347+
self.info_msg(f'Waiting for {node_name} to become active')
348+
node_service = f'{node_name}/get_state'
350349
state_client = self.create_client(GetState, node_service)
351350
while not state_client.wait_for_service(timeout_sec=1.0):
352-
self.info_msg(node_service + ' service not available, waiting...')
351+
self.info_msg(f'{node_service} service not available, waiting...')
353352
req = GetState.Request() # empty request
354353
state = 'UNKNOWN'
355354
while (state != 'active'):
356-
self.info_msg('Getting ' + node_name + ' state...')
355+
self.info_msg(f'Getting {node_name} state...')
357356
future = state_client.call_async(req)
358357
rclpy.spin_until_future_complete(self, future)
359358
if future.result() is not None:
360359
state = future.result().current_state.label
361-
self.info_msg('Result of get_state: %s' % state)
360+
self.info_msg(f'Result of get_state: {state}')
362361
else:
363362
self.error_msg('Exception while calling service: %r' %
364363
future.exception())
@@ -372,8 +371,7 @@ def shutdown(self):
372371
mgr_client = self.create_client(
373372
ManageLifecycleNodes, transition_service)
374373
while not mgr_client.wait_for_service(timeout_sec=1.0):
375-
self.info_msg(transition_service +
376-
' service not available, waiting...')
374+
self.info_msg(f'{transition_service} service not available, waiting...')
377375

378376
req = ManageLifecycleNodes.Request()
379377
req.command = ManageLifecycleNodes.Request().SHUTDOWN
@@ -385,13 +383,12 @@ def shutdown(self):
385383
self.info_msg(
386384
'Shutting down navigation lifecycle manager complete.')
387385
except Exception as e: # noqa: B902
388-
self.error_msg('Service call failed %r' % (e,))
386+
self.error_msg(f'Service call failed {e!r}')
389387
transition_service = 'lifecycle_manager_localization/manage_nodes'
390388
mgr_client = self.create_client(
391389
ManageLifecycleNodes, transition_service)
392390
while not mgr_client.wait_for_service(timeout_sec=1.0):
393-
self.info_msg(transition_service +
394-
' service not available, waiting...')
391+
self.info_msg(f'{transition_service} service not available, waiting...')
395392

396393
req = ManageLifecycleNodes.Request()
397394
req.command = ManageLifecycleNodes.Request().SHUTDOWN
@@ -403,7 +400,7 @@ def shutdown(self):
403400
self.info_msg(
404401
'Shutting down localization lifecycle manager complete')
405402
except Exception as e: # noqa: B902
406-
self.error_msg('Service call failed %r' % (e,))
403+
self.error_msg(f'Service call failed {e!r}')
407404

408405
def wait_for_initial_pose(self):
409406
self.initial_pose_received = False

‎nav2_system_tests/src/system/nav_through_poses_tester_node.py‎

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -111,7 +111,7 @@ def runNavigateAction(self, goal_pose: Optional[Pose] = None):
111111
rclpy.spin_until_future_complete(self, get_result_future)
112112
status = get_result_future.result().status
113113
if status != GoalStatus.STATUS_SUCCEEDED:
114-
self.info_msg('Goal failed with status code: {0}'.format(status))
114+
self.info_msg(f'Goal failed with status code: {status}')
115115
return False
116116

117117
self.info_msg('Goal succeeded!')
@@ -124,22 +124,22 @@ def poseCallback(self, msg):
124124

125125
def wait_for_node_active(self, node_name: str):
126126
# Waits for the node within the tester namespace to become active
127-
self.info_msg('Waiting for ' + node_name + ' to become active')
128-
node_service = node_name + '/get_state'
127+
self.info_msg(f'Waiting for {node_name} to become active')
128+
node_service = f'{node_name}/get_state'
129129
state_client = self.create_client(GetState, node_service)
130130
while not state_client.wait_for_service(timeout_sec=1.0):
131-
self.info_msg(node_service + ' service not available, waiting...')
131+
self.info_msg(f'{node_service} service not available, waiting...')
132132
req = GetState.Request() # empty request
133133
state = 'UNKNOWN'
134134
while (state != 'active'):
135-
self.info_msg('Getting ' + node_name + ' state...')
135+
self.info_msg(f'Getting {node_name} state...')
136136
future = state_client.call_async(req)
137137
rclpy.spin_until_future_complete(self, future)
138138
if future.result() is not None:
139139
state = future.result().current_state.label
140-
self.info_msg('Result of get_state: %s' % state)
140+
self.info_msg(f'Result of get_state: {state}')
141141
else:
142-
self.error_msg('Exception while calling service: %r' % future.exception())
142+
self.error_msg(f'Exception while calling service: {future.exception()!r}')
143143
time.sleep(5)
144144

145145
def shutdown(self):
@@ -149,7 +149,7 @@ def shutdown(self):
149149
transition_service = 'lifecycle_manager_navigation/manage_nodes'
150150
mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
151151
while not mgr_client.wait_for_service(timeout_sec=1.0):
152-
self.info_msg(transition_service + ' service not available, waiting...')
152+
self.info_msg(f'{transition_service} service not available, waiting...')
153153

154154
req = ManageLifecycleNodes.Request()
155155
req.command = ManageLifecycleNodes.Request().SHUTDOWN
@@ -160,11 +160,11 @@ def shutdown(self):
160160
future.result()
161161
self.info_msg('Shutting down navigation lifecycle manager complete.')
162162
except Exception as e: # noqa: B902
163-
self.error_msg('Service call failed %r' % (e,))
163+
self.error_msg(f'Service call failed {e!r}')
164164
transition_service = 'lifecycle_manager_localization/manage_nodes'
165165
mgr_client = self.create_client(ManageLifecycleNodes, transition_service)
166166
while not mgr_client.wait_for_service(timeout_sec=1.0):
167-
self.info_msg(transition_service + ' service not available, waiting...')
167+
self.info_msg(f'{transition_service} service not available, waiting...')
168168

169169
req = ManageLifecycleNodes.Request()
170170
req.command = ManageLifecycleNodes.Request().SHUTDOWN
@@ -175,7 +175,7 @@ def shutdown(self):
175175
future.result()
176176
self.info_msg('Shutting down localization lifecycle manager complete')
177177
except Exception as e: # noqa: B902
178-
self.error_msg('Service call failed %r' % (e,))
178+
self.error_msg(f'Service call failed {e!r}')
179179

180180
def wait_for_initial_pose(self):
181181
self.initial_pose_received = False

0 commit comments

Comments
 (0)