diff --git a/NaviGator/gnc/navigator_msg_multiplexer/nodes/ogrid_arbiter.py b/NaviGator/gnc/navigator_msg_multiplexer/nodes/ogrid_arbiter.py index ac8fffd4f..eb425ec7a 100755 --- a/NaviGator/gnc/navigator_msg_multiplexer/nodes/ogrid_arbiter.py +++ b/NaviGator/gnc/navigator_msg_multiplexer/nodes/ogrid_arbiter.py @@ -493,10 +493,7 @@ def publish(self, timer_event): ) print(e) fprint( - "w: {}, h: {}".format( - global_ogrid.info.width, - global_ogrid.info.height, - ), + f"w: {global_ogrid.info.width}, h: {global_ogrid.info.height}", msg_color="red", ) diff --git a/NaviGator/gnc/navigator_thrust_mapper/navigator_thrust_mapper/thruster_map.py b/NaviGator/gnc/navigator_thrust_mapper/navigator_thrust_mapper/thruster_map.py index 588679455..2fc19700a 100644 --- a/NaviGator/gnc/navigator_thrust_mapper/navigator_thrust_mapper/thruster_map.py +++ b/NaviGator/gnc/navigator_thrust_mapper/navigator_thrust_mapper/thruster_map.py @@ -166,15 +166,11 @@ def from_urdf( if find != -1 and find + len(transmission_suffix) == len(transmission.name): if len(transmission.joints) != 1: raise Exception( - "Transmission {} does not have 1 joint".format( - transmission.name, - ), + f"Transmission {transmission.name} does not have 1 joint", ) if len(transmission.actuators) != 1: raise Exception( - "Transmission {} does not have 1 actuator".format( - transmission.name, - ), + f"Transmission {transmission.name} does not have 1 actuator", ) t_ratio = transmission.actuators[0].mechanicalReduction @@ -195,9 +191,7 @@ def from_urdf( joint = t_joint if joint is None: rospy.logerr( - "Transmission joint {} not found".format( - transmission.joints[0].name, - ), + f"Transmission joint {transmission.joints[0].name} not found", ) try: trans = buff.lookup_transform( @@ -217,9 +211,7 @@ def from_urdf( joints.append(joint.name) if limit != -1 and joint.limit.effort != limit: raise Exception( - "Thruster {} had a different limit, cannot proceed".format( - joint.name, - ), + f"Thruster {joint.name} had a different limit, cannot proceed", ) limit = joint.limit.effort limit_tuple = (limit, -limit) diff --git a/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/kill.py b/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/kill.py index a3f7a612b..547c56fa8 100644 --- a/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/kill.py +++ b/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/kill.py @@ -28,10 +28,7 @@ def _online_bagger_cb(self, status, result): rospy.loginfo(f"KILL BAG WRITTEN TO {result.filename}") else: rospy.logwarn( - "KILL BAG {}, status: {}".format( - TerminalState.to_string(status), - result.status, - ), + f"KILL BAG {TerminalState.to_string(status)}, status: {result.status}", ) def _kill_task_cb(self, status, result): @@ -39,10 +36,7 @@ def _kill_task_cb(self, status, result): rospy.loginfo("Killed task success!") return rospy.logwarn( - "Killed task failed ({}): {}".format( - TerminalState.to_string(status), - result.result, - ), + f"Killed task failed ({TerminalState.to_string(status)}): {result.result}", ) def raised(self, alarm): diff --git a/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/thruster_fault.py b/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/thruster_fault.py index a89612632..ce89ac3a0 100644 --- a/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/thruster_fault.py +++ b/NaviGator/mission_control/navigator_alarm/navigator_alarm_handlers/thruster_fault.py @@ -65,9 +65,7 @@ def _check_faults(self, msg, topic): return self.broadcaster.raise_alarm( severity=5, - problem_description="{} thrusters have faults".format( - len(self._raised_alarms), - ), + problem_description=f"{len(self._raised_alarms)} thrusters have faults", parameters={ t: self._get_fault_codes(k) for t, k in self._raised_alarms.items() }, diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/detect_deliver_2016.py b/NaviGator/mission_control/navigator_missions/navigator_missions/detect_deliver_2016.py index bc95612b0..28c3ac4d9 100644 --- a/NaviGator/mission_control/navigator_missions/navigator_missions/detect_deliver_2016.py +++ b/NaviGator/mission_control/navigator_missions/navigator_missions/detect_deliver_2016.py @@ -240,10 +240,7 @@ async def search_sides(self, moves): self.shape_pose = found_pose return fprint( - "Saw (Shape={}, Color={}) on this side".format( - shape_color[0], - shape_color[1], - ), + f"Saw (Shape={shape_color[0]}, Color={shape_color[1]}) on this side", title="DETECT DELIVER", msg_color="green", ) @@ -287,10 +284,7 @@ def select_backup_shape(self): self.shape_pose = point_normal if self.Shape == shape or self.Color == color: fprint( - "Correct shape not found, resorting to shape={} color={}".format( - shape, - color, - ), + f"Correct shape not found, resorting to shape={shape} color={color}", title="DETECT DELIVER", msg_color="yellow", ) @@ -430,9 +424,7 @@ async def shoot_and_align_forest(self): move = await self.align_to_target() if move.failure_reason != "": fprint( - "Error Aligning with target = {}. Ending mission :(".format( - move.failure_reason, - ), + f"Error Aligning with target = {move.failure_reason}. Ending mission :(", title="DETECT DELIVER", msg_color="red", ) @@ -479,9 +471,7 @@ async def shoot_and_align(self): move = await self.align_to_target() if move.failure_reason != "": fprint( - "Error Aligning with target = {}. Ending mission :(".format( - move.failure_reason, - ), + f"Error Aligning with target = {move.failure_reason}. Ending mission :(", title="DETECT DELIVER", msg_color="red", ) diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/identify_dock.py b/NaviGator/mission_control/navigator_missions/navigator_missions/identify_dock.py index 28419f6b6..6d2203826 100644 --- a/NaviGator/mission_control/navigator_missions/navigator_missions/identify_dock.py +++ b/NaviGator/mission_control/navigator_missions/navigator_missions/identify_dock.py @@ -150,10 +150,7 @@ async def check_bays(self): def update_shape(self, shape_res, normal_res, tf): print_good( - "Found (Shape={}, Color={} in a bay".format( - shape_res.Shape, - shape_res.Color, - ), + f"Found (Shape={shape_res.Shape}, Color={shape_res.Color} in a bay", ) self.identified_shapes[(shape_res.Shape, shape_res.Color)] = self.get_shape_pos( normal_res, diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/move.py b/NaviGator/mission_control/navigator_missions/navigator_missions/move.py index 03017c09b..8ae428057 100755 --- a/NaviGator/mission_control/navigator_missions/navigator_missions/move.py +++ b/NaviGator/mission_control/navigator_missions/navigator_missions/move.py @@ -149,9 +149,7 @@ async def run(self, args): "yl": "yaw_left", "yr": "yaw_right", } - command = ( - command if command not in shorthand.keys() else shorthand[command] - ) + command = command if command not in shorthand else shorthand[command] movement = getattr(self.move, command) trans_move = command[:3] != "yaw" diff --git a/NaviGator/mission_control/navigator_missions/navigator_missions/navigation.py b/NaviGator/mission_control/navigator_missions/navigator_missions/navigation.py index 9b977b0bf..7812e5108 100644 --- a/NaviGator/mission_control/navigator_missions/navigator_missions/navigation.py +++ b/NaviGator/mission_control/navigator_missions/navigator_missions/navigation.py @@ -187,9 +187,7 @@ async def explore_closest_until(self, is_done, filter_and_sort): ) if classification_index != -1: self.send_feedback( - "{} identified. Canceling investigation".format( - move_id_tuple[1], - ), + f"{move_id_tuple[1]} identified. Canceling investigation", ) move_task.cancel() diff --git a/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_navigation.py b/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_navigation.py index 3086e39b5..7ef98c064 100644 --- a/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_navigation.py +++ b/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_navigation.py @@ -151,9 +151,7 @@ async def explore_closest_until(self, is_done, filter_and_sort): ) if classification_index != -1: self.send_feedback( - "{} identified. Canceling investigation".format( - move_id_tuple[1], - ), + f"{move_id_tuple[1]} identified. Canceling investigation", ) move_id_tuple[0].cancel() await self.nh.sleep(1.0) diff --git a/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_perception.py b/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_perception.py index f1483416f..2b1ef6d50 100644 --- a/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_perception.py +++ b/NaviGator/mission_control/navigator_missions/vrx_missions/vrx_perception.py @@ -79,11 +79,7 @@ async def run(self, parameters): ) elif objects[key] != new_objects[key]: self.send_feedback( - "{} changed from {} to {}".format( - key, - objects[key], - new_objects[key], - ), + f"{key} changed from {objects[key]} to {new_objects[key]}", ) await self.announce_object( key, diff --git a/NaviGator/simulation/navigator_gazebo/test/test_sim_integration.py b/NaviGator/simulation/navigator_gazebo/test/test_sim_integration.py index 3cb7ab8a7..46e20b856 100755 --- a/NaviGator/simulation/navigator_gazebo/test/test_sim_integration.py +++ b/NaviGator/simulation/navigator_gazebo/test/test_sim_integration.py @@ -71,10 +71,7 @@ def test_odom(self): rospy.sleep(0.1) self.assertTrue( len(self.odom_pos_msg) == 3 and len(self.odom_ori_msg) == 4, - msg="POS, ORI: {}, {}".format( - len(self.odom_pos_msg), - len(self.odom_ori_msg), - ), + msg=f"POS, ORI: {len(self.odom_pos_msg)}, {len(self.odom_ori_msg)}", ) initial_pos = [-1.2319, 0.0, 0.0] initial_ori = [0.0, 0.0, 0.0, 1.0] @@ -100,10 +97,7 @@ def test_absodom(self): rospy.sleep(0.1) self.assertTrue( len(self.absodom_pos_msg) == 3 and len(self.absodom_ori_msg) == 4, - msg="POS, ORI: {}, {}".format( - len(self.absodom_pos_msg), - len(self.absodom_ori_msg), - ), + msg=f"POS, ORI: {len(self.absodom_pos_msg)}, {len(self.absodom_ori_msg)}", ) initial_pos = [743789.637462, -5503821.36715, 3125622.10477] initial_ori = [0.0, 0.0, 0.0, 1.0] @@ -122,25 +116,13 @@ def verify_pos_ori(self, pos, initial_pos, ori, initial_ori, topic): actual, initial, places=0, - msg=( - "Error: {} position is: {} should be {}".format( - topic, - actual, - initial, - ) - ), + msg=(f"Error: {topic} position is: {actual} should be {initial}"), ) for actual, initial in zip(ori, initial_ori): self.assertEqual( actual, initial, - msg=( - "Error: {} orientation is: {} should be {}".format( - topic, - actual, - initial, - ) - ), + msg=(f"Error: {topic} orientation is: {actual} should be {initial}"), ) def cam_info_right_cb(self, msg): @@ -229,10 +211,7 @@ def verify_not_empty(self, data_lists, num_topics): self.assertEqual( len(data_lists), num_topics, - msg="Number of topics is {}, should be {}".format( - len(data_lists), - num_topics, - ), + msg=f"Number of topics is {len(data_lists)}, should be {num_topics}", ) for data_list in data_lists: self.assertNotEqual(len(data_list), 0, msg="data is empty") @@ -243,13 +222,7 @@ def verify_info(self, res_info, initial_info, topic): self.assertNotEqual( actual_dim, initial_dim, - msg=( - "Error: {} is: {} shouldn't be {}".format( - topic, - actual_dim, - initial_dim, - ) - ), + msg=(f"Error: {topic} is: {actual_dim} shouldn't be {initial_dim}"), ) diff --git a/NaviGator/utils/navigator_robotx_comms/nodes/robotx_comms_client.py b/NaviGator/utils/navigator_robotx_comms/nodes/robotx_comms_client.py index d8583f010..59e6139e3 100755 --- a/NaviGator/utils/navigator_robotx_comms/nodes/robotx_comms_client.py +++ b/NaviGator/utils/navigator_robotx_comms/nodes/robotx_comms_client.py @@ -559,10 +559,7 @@ def connect(self) -> None: """ if not self.connected: rospy.loginfo( - "Attempting Connection to TD Server at {}:{}".format( - self.tcp_ip, - self.tcp_port, - ), + f"Attempting Connection to TD Server at {self.tcp_ip}:{self.tcp_port}", ) while not self.connected and not rospy.is_shutdown(): # recreate socket diff --git a/NaviGator/utils/navigator_tools/navigator_tools/object_database_helper.py b/NaviGator/utils/navigator_tools/navigator_tools/object_database_helper.py index 0798c78e0..7d73fc1aa 100644 --- a/NaviGator/utils/navigator_tools/navigator_tools/object_database_helper.py +++ b/NaviGator/utils/navigator_tools/navigator_tools/object_database_helper.py @@ -50,7 +50,7 @@ async def get_object_by_id(self, my_id): req = ObjectDBQueryRequest() req.name = "all" resp = await self._database(req) - ans = [obj for obj in resp.objects if obj.id == my_id][0] + ans = next(obj for obj in resp.objects if obj.id == my_id) return ans async def begin_observing(self, cb): diff --git a/SubjuGator/command/subjugator_alarm/alarm_handlers/kill.py b/SubjuGator/command/subjugator_alarm/alarm_handlers/kill.py index 4781a760a..4055694d8 100644 --- a/SubjuGator/command/subjugator_alarm/alarm_handlers/kill.py +++ b/SubjuGator/command/subjugator_alarm/alarm_handlers/kill.py @@ -101,10 +101,7 @@ def _bag_done_cb(self, status, result): rospy.loginfo(f"KILL BAG WRITTEN TO {result.filename}") else: rospy.logwarn( - "KILL BAG {}, status: {}".format( - TerminalState.to_string(status), - result.status, - ), + f"KILL BAG {TerminalState.to_string(status)}, status: {result.status}", ) def bagger_dump(self): diff --git a/SubjuGator/command/subjugator_alarm/alarm_handlers/odom_kill.py b/SubjuGator/command/subjugator_alarm/alarm_handlers/odom_kill.py index 4a7638909..90a8e817b 100644 --- a/SubjuGator/command/subjugator_alarm/alarm_handlers/odom_kill.py +++ b/SubjuGator/command/subjugator_alarm/alarm_handlers/odom_kill.py @@ -101,9 +101,7 @@ def check_continuity(self, new_odom_msg: Odometry): # True if 'continuous' if jump > self.MAX_JUMP: rospy.logerr("ODOM DISCONTINUITY DETECTED") self.ab.raise_alarm( - problem_description="ODOM DISCONTINUITY DETECTED JUMPED {} METERS".format( - jump, - ), + problem_description=f"ODOM DISCONTINUITY DETECTED JUMPED {jump} METERS", severity=5, ) self.odom_discontinuity = True @@ -120,9 +118,7 @@ def need_kill(self): if odom_loss: rospy.logerr_throttle( 1, - "LOST ODOM FOR {} SECONDS".format( - (rospy.Time.now() - self.last_time).to_sec(), - ), + f"LOST ODOM FOR {(rospy.Time.now() - self.last_time).to_sec()} SECONDS", ) self.ab.raise_alarm( problem_description="LOST ODOM FOR {} SECONDS".format( diff --git a/SubjuGator/command/subjugator_keyboard_control/teleop_twist_keyboard.py b/SubjuGator/command/subjugator_keyboard_control/teleop_twist_keyboard.py index ea5c7bedb..870df6ac7 100755 --- a/SubjuGator/command/subjugator_keyboard_control/teleop_twist_keyboard.py +++ b/SubjuGator/command/subjugator_keyboard_control/teleop_twist_keyboard.py @@ -141,9 +141,7 @@ def wait_for_subscribers(self): while not rospy.is_shutdown() and self.publisher.get_num_connections() == 0: if i == 4: print( - "Waiting for subscriber to connect to {}".format( - self.publisher.name, - ), + f"Waiting for subscriber to connect to {self.publisher.name}", ) rospy.sleep(0.5) i += 1 diff --git a/SubjuGator/command/subjugator_missions/subjugator_missions/arm_torpedos.py b/SubjuGator/command/subjugator_missions/subjugator_missions/arm_torpedos.py index aad130049..7a88e8908 100644 --- a/SubjuGator/command/subjugator_missions/subjugator_missions/arm_torpedos.py +++ b/SubjuGator/command/subjugator_missions/subjugator_missions/arm_torpedos.py @@ -170,9 +170,7 @@ async def fire(self, target: str): ) self.print_good( - "{} locked. Firing torpedoes. Hit confirmed, good job Commander.".format( - target, - ), + f"{target} locked. Firing torpedoes. Hit confirmed, good job Commander.", ) sub_pos = await self.tx_pose() print("Current Sub Position: ", sub_pos) diff --git a/SubjuGator/command/subjugator_missions/subjugator_missions/start_gate.py b/SubjuGator/command/subjugator_missions/subjugator_missions/start_gate.py index f395bd1e0..0886298e1 100644 --- a/SubjuGator/command/subjugator_missions/subjugator_missions/start_gate.py +++ b/SubjuGator/command/subjugator_missions/subjugator_missions/start_gate.py @@ -160,9 +160,7 @@ def find_gate( p2 = rosmsg_to_numpy(o2.pose.position) if distance.euclidean(p, p2) > max_distance_away: fprint( - "Poles too far away. Distance {}".format( - distance.euclidean(p, p2), - ), + f"Poles too far away. Distance {distance.euclidean(p, p2)}", ) continue if distance.euclidean(p, p2) < min_distance_away: @@ -180,10 +178,7 @@ def find_gate( continue if abs(line[0]) < 1 and abs(line[1]) < 1: fprint( - "Objects on top of one another. x {}, y {}".format( - line[0], - line[1], - ), + f"Objects on top of one another. x {line[0]}, y {line[1]}", ) continue return (p, p2) diff --git a/SubjuGator/command/subjugator_missions/subjugator_missions/sub_singleton.py b/SubjuGator/command/subjugator_missions/subjugator_missions/sub_singleton.py index 693fc3bd7..8e498fc4d 100644 --- a/SubjuGator/command/subjugator_missions/subjugator_missions/sub_singleton.py +++ b/SubjuGator/command/subjugator_missions/subjugator_missions/sub_singleton.py @@ -599,7 +599,7 @@ async def start_search_in_cone( distance_tol: float = 10, speed: float = 0.5, clear: bool = False, - c_func: Callable = None, + c_func: Callable | None = None, ): if clear: print("SONAR_OBJECTS: clearing pointcloud") diff --git a/SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts/generate_config b/SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts/generate_config index 5d12dad06..f818bd613 100755 --- a/SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts/generate_config +++ b/SubjuGator/drivers/magnetic_compensation/sub8_magnetic_hardsoft_compensation/scripts/generate_config @@ -110,9 +110,7 @@ def test(): assert numpy.allclose( shift2, shift, - ), "Magnetic Hardsoft Compenstion self-test failed, shifts: {}".format( - (shift2, shift), - ) + ), f"Magnetic Hardsoft Compenstion self-test failed, shifts: {(shift2, shift)}" assert ( error < 1e-5 ), f"Magnetic Hardsoft Compenstion self-test failed, error: {error}" diff --git a/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/handle.py b/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/handle.py index c62f5732b..19df02c33 100644 --- a/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/handle.py +++ b/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/handle.py @@ -109,9 +109,7 @@ def on_command(self, msg: Thrust) -> None: # If we don't have a mapping for this thruster, ignore it if cmd.name not in self.thrusters: rospy.logwarn( - "Command received for {}, but this is not a thruster.".format( - cmd.name, - ), + f"Command received for {cmd.name}, but this is not a thruster.", ) continue # Map commanded thrust (in newetons) to effort value (-1 to 1) diff --git a/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/packets.py b/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/packets.py index 8cc3a0f27..dcd1aaa0b 100644 --- a/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/packets.py +++ b/SubjuGator/drivers/sub8_thrust_and_kill_board/sub8_thrust_and_kill_board/packets.py @@ -287,7 +287,4 @@ def command(self) -> float: return struct.unpack("f", self.payload[1:])[0] def __str__(self): - return "ThrustPacket(thruster_id={}, command={})".format( - self.thruster_id, - self.command, - ) + return f"ThrustPacket(thruster_id={self.thruster_id}, command={self.command})" diff --git a/SubjuGator/perception/subjugator_perception/ml_classifiers/path_marker/path_localizer.py b/SubjuGator/perception/subjugator_perception/ml_classifiers/path_marker/path_localizer.py index 29665f12a..c70e5e258 100755 --- a/SubjuGator/perception/subjugator_perception/ml_classifiers/path_marker/path_localizer.py +++ b/SubjuGator/perception/subjugator_perception/ml_classifiers/path_marker/path_localizer.py @@ -17,7 +17,7 @@ rospack.get_path("subjugator_perception") + "/ml_classifiers/path_marker/utils", ) -from utils import detector_utils # noqa: manually appending sys.path +from utils import detector_utils # noqa class classifier: diff --git a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/sub8_driver.py b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/sub8_driver.py index 8236940ac..c03b318d2 100755 --- a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/sub8_driver.py +++ b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/sub8_driver.py @@ -85,9 +85,7 @@ def read_packet(self) -> bool: self.handles[packet.device].on_data(packet.data) else: rospy.logwarn( - "Message received for device {}, but no handle registered".format( - packet.device, - ), + f"Message received for device {packet.device}, but no handle registered", ) return True diff --git a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/utils.py b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/utils.py index 2d2558f57..0ef0cf9a1 100644 --- a/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/utils.py +++ b/mil_common/drivers/mil_usb_to_can/mil_usb_to_can/sub8/utils.py @@ -26,10 +26,7 @@ class ChecksumException(USB2CANException): def __init__(self, calculated, expected): super().__init__( - "Checksum was calculated as {} but reported as {}".format( - calculated, - expected, - ), + f"Checksum was calculated as {calculated} but reported as {expected}", ) diff --git a/mil_common/mil_missions/mil_missions_gui/dashboard.py b/mil_common/mil_missions/mil_missions_gui/dashboard.py index f3f224243..440dc85b9 100755 --- a/mil_common/mil_missions/mil_missions_gui/dashboard.py +++ b/mil_common/mil_missions/mil_missions_gui/dashboard.py @@ -195,11 +195,10 @@ def ui_log(self, string): """ self.lock.acquire() date_time = datetime.datetime.fromtimestamp(rospy.Time.now().to_time()) - time_str = "{}:{}:{}".format( - date_time.hour, - date_time.minute, - date_time.second, - ).ljust(12, " ") + time_str = f"{date_time.hour}:{date_time.minute}:{date_time.second}".ljust( + 12, + " ", + ) formatted = time_str + string self.feedback_list.addItem(formatted) self.lock.release() @@ -242,9 +241,7 @@ def transition_cb(self, goal, handler): self.current_mission_status = terminal_state self.current_mission_status_label.setText(self.current_mission_status) self.ui_log( - "FINISHED: mission finished ({})".format( - self.current_mission_status, - ), + f"FINISHED: mission finished ({self.current_mission_status})", ) def reload_available_missions(self, _): diff --git a/mil_common/mil_missions/nodes/mission_client b/mil_common/mil_missions/nodes/mission_client index 2ff81d944..230547f8e 100755 --- a/mil_common/mil_missions/nodes/mission_client +++ b/mil_common/mil_missions/nodes/mission_client @@ -30,9 +30,7 @@ class MissionClientCli: missions = MissionClient.available_missions() if not missions: print( - "{} param not set. Is mission runner running?".format( - MissionClient.LIST_PARAM, - ), + f"{MissionClient.LIST_PARAM} param not set. Is mission runner running?", ) return print("Available Missions:") diff --git a/mil_common/mil_missions/test/test_import_missions.py b/mil_common/mil_missions/test/test_import_missions.py index e03fb7e82..c09c8f13b 100755 --- a/mil_common/mil_missions/test/test_import_missions.py +++ b/mil_common/mil_missions/test/test_import_missions.py @@ -21,10 +21,7 @@ def test_import_missions(self): if not hasattr(mission_module, self.base_class): self.fail( - msg="{} doesn't have base mission {}".format( - self.module, - self.base_class, - ), + msg=f"{self.module} doesn't have base mission {self.base_class}", ) base_mission = getattr(mission_module, self.base_class) diff --git a/mil_common/perception/mil_vision/mil_vision_tools/cv_tools.py b/mil_common/perception/mil_vision/mil_vision_tools/cv_tools.py index dcfb694a1..42b6112b2 100644 --- a/mil_common/perception/mil_vision/mil_vision_tools/cv_tools.py +++ b/mil_common/perception/mil_vision/mil_vision_tools/cv_tools.py @@ -79,7 +79,7 @@ def __init__( self.conversion_code = conversion_code @classmethod - def from_dict(cls, d, in_space: str = "BGR", thresh_space: str = None): + def from_dict(cls, d, in_space: str = "BGR", thresh_space: Optional[str] = None): """ Loads thresholds from a dictionary. See examples for valid dictionaries. @@ -114,9 +114,7 @@ def from_dict(cls, d, in_space: str = "BGR", thresh_space: str = None): d.keys(), ), ) - assert thresh_space in d, "{} color space not in dictionary".format( - thresh_space, - ) + assert thresh_space in d, f"{thresh_space} color space not in dictionary" inner = d[thresh_space] if "low" in inner and "high" in inner: return cls( diff --git a/mil_common/utils/mil_tools/mil_ros_tools/extract_bag_images.py b/mil_common/utils/mil_tools/mil_ros_tools/extract_bag_images.py index c243ae950..22e52987c 100755 --- a/mil_common/utils/mil_tools/mil_ros_tools/extract_bag_images.py +++ b/mil_common/utils/mil_tools/mil_ros_tools/extract_bag_images.py @@ -150,17 +150,11 @@ def get_camera_model(bag: str, topic: str): _, msg, _ = next(bag.read_messages(topics=camera_info_topic)) except StopIteration: raise Exception( - "no camera info messages found on topic {} in {}".format( - camera_info_topic, - bag, - ), + f"no camera info messages found on topic {camera_info_topic} in {bag}", ) if msg._type != "sensor_msgs/CameraInfo": raise Exception( - "msg on topic {} are not camera info in bag {}".format( - camera_info_topic, - bag, - ), + f"msg on topic {camera_info_topic} are not camera info in bag {bag}", ) model = PinholeCameraModel() model.fromCameraInfo(msg) @@ -218,10 +212,7 @@ def extract_images(self, source_dir=".", image_dir=".", verbose=False): """ if verbose: print( - "\tExtracting images from topic {} in {}".format( - self.topic, - self.filename, - ), + f"\tExtracting images from topic {self.topic} in {self.filename}", ) filename = os.path.join(source_dir, self.filename) b = rosbag.Bag(filename) diff --git a/mil_common/utils/mil_tools/mil_ros_tools/label_me_bag.py b/mil_common/utils/mil_tools/mil_ros_tools/label_me_bag.py index d3a98fa67..4e6c7231c 100755 --- a/mil_common/utils/mil_tools/mil_ros_tools/label_me_bag.py +++ b/mil_common/utils/mil_tools/mil_ros_tools/label_me_bag.py @@ -263,10 +263,7 @@ def completion_report(self): total_img_count += i if total_img_count == 0: print( - "{}/{} TOTAL images labeled (0%)".format( - total_xml_count, - total_img_count, - ), + f"{total_xml_count}/{total_img_count} TOTAL images labeled (0%)", ) else: print( diff --git a/mil_common/utils/mil_tools/mil_ros_tools/msg_helpers.py b/mil_common/utils/mil_tools/mil_ros_tools/msg_helpers.py index 9ffa9b2d9..8ab315818 100644 --- a/mil_common/utils/mil_tools/mil_ros_tools/msg_helpers.py +++ b/mil_common/utils/mil_tools/mil_ros_tools/msg_helpers.py @@ -58,10 +58,7 @@ def rosmsg_to_numpy(rosmsg, keys=None): break assert ( len(output_array) != 0 - ), "Input type {} has none of these attributes {}.".format( - type(rosmsg).__name__, - keys, - ) + ), f"Input type {type(rosmsg).__name__} has none of these attributes {keys}." return np.array(output_array).astype(np.float32) else: diff --git a/mil_common/utils/mil_tools/nodes/online_bagger.py b/mil_common/utils/mil_tools/nodes/online_bagger.py index 2580f5cf2..5a0c6bb32 100755 --- a/mil_common/utils/mil_tools/nodes/online_bagger.py +++ b/mil_common/utils/mil_tools/nodes/online_bagger.py @@ -71,10 +71,7 @@ def get_subscriber_list(self, status): sub_list = "" for topic in self.subscriber_list: if self.subscriber_list[topic][1] == status: - sub_list = sub_list + "\n{:13}, {}".format( - self.subscriber_list[topic], - topic, - ) + sub_list = sub_list + f"\n{self.subscriber_list[topic]:13}, {topic}" return sub_list def get_params(self): diff --git a/mil_common/utils/mil_tools/nodes/tf_fudger.py b/mil_common/utils/mil_tools/nodes/tf_fudger.py index 58a647757..0ae508c98 100755 --- a/mil_common/utils/mil_tools/nodes/tf_fudger.py +++ b/mil_common/utils/mil_tools/nodes/tf_fudger.py @@ -45,10 +45,7 @@ ang_res = ang_range / ang_max print( - "Distance resolution: {} meters\nAngular resolution: {} radians".format( - x_res, - ang_res, - ), + f"Distance resolution: {x_res} meters\nAngular resolution: {ang_res} radians", ) cv2.createTrackbar("x", "tf", 0, x_max, lambda x: x) diff --git a/mil_common/utils/mil_tools/nodes/tf_to_gazebo.py b/mil_common/utils/mil_tools/nodes/tf_to_gazebo.py index b587dfb88..9363d3c4f 100755 --- a/mil_common/utils/mil_tools/nodes/tf_to_gazebo.py +++ b/mil_common/utils/mil_tools/nodes/tf_to_gazebo.py @@ -25,12 +25,7 @@ def main(): if do_cam_fix: rot = tf.transformations.quaternion_multiply(rot, cam_fix_quat) print( - "(qx={}, qy={} , qz={}, qw={})".format( - rot[0], - rot[1], - rot[2], - rot[3], - ), + f"(qx={rot[0]}, qy={rot[1]} , qz={rot[2]}, qw={rot[3]})", ) print(f"(x={trans[0]}, y={trans[1]}, z={trans[2]})") euler = tf.transformations.euler_from_quaternion(rot) diff --git a/ruff.toml b/ruff.toml index 69b8787be..0ec9c21f1 100644 --- a/ruff.toml +++ b/ruff.toml @@ -35,6 +35,7 @@ ignore = [ "D212", # we use second line! "D200", # one line docstrings are not shortened! "SIM115", # too many for now... + "RUF012", # too many for now, adds obvious ClassVar statements ] [per-file-ignores]