Tools: ros2: Run ament_black on all files

* This commit is files changed automatically by the black linter

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
Ryan Friedman 2023-11-21 19:13:18 -07:00 committed by Tom Pittenger
parent b5e2f9aa0a
commit 85172b5646
8 changed files with 22 additions and 62 deletions

View File

@ -40,9 +40,7 @@ class TimeListener(Node):
def cb(self, msg):
"""Process a Time message."""
if msg.sec:
self.get_logger().info(
"From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec)
)
self.get_logger().info("From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec))
else:
self.get_logger().info("From AP : False")

View File

@ -9,15 +9,11 @@ setup(
version='0.0.0',
packages=[package_name],
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/ament_index/resource_index/packages', ['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
(os.path.join("share", package_name, "launch"),
glob("launch/*.launch.py")),
(os.path.join("share", package_name, "config"),
glob("config/*.parm")),
(os.path.join("share", package_name, "config"),
glob("config/*.yaml")),
(os.path.join("share", package_name, "launch"), glob("launch/*.launch.py")),
(os.path.join("share", package_name, "config"), glob("config/*.parm")),
(os.path.join("share", package_name, "config"), glob("config/*.yaml")),
],
install_requires=['setuptools'],
zip_safe=True,

View File

@ -51,14 +51,10 @@ class NavSatFixListener(rclpy.node.Node):
depth=1,
)
self.subscription = self.create_subscription(
NavSatFix, self.topic, self.subscriber_callback, qos_profile
)
self.subscription = self.create_subscription(NavSatFix, self.topic, self.subscriber_callback, qos_profile)
# Add a spin thread.
self.ros_spin_thread = threading.Thread(
target=lambda node: rclpy.spin(node), args=(self,)
)
self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,))
self.ros_spin_thread.start()
def subscriber_callback(self, msg):
@ -66,9 +62,7 @@ class NavSatFixListener(rclpy.node.Node):
self.msg_event_object.set()
if msg.latitude:
self.get_logger().info(
"From AP : True [lat:{}, lon: {}]".format(msg.latitude, msg.longitude)
)
self.get_logger().info("From AP : True [lat:{}, lon: {}]".format(msg.latitude, msg.longitude))
else:
self.get_logger().info("From AP : False")

View File

@ -41,14 +41,10 @@ class TimeListener(rclpy.node.Node):
def start_subscriber(self):
"""Start the subscriber."""
self.subscription = self.create_subscription(
Time, self.topic, self.subscriber_callback, 1
)
self.subscription = self.create_subscription(Time, self.topic, self.subscriber_callback, 1)
# Add a spin thread.
self.ros_spin_thread = threading.Thread(
target=lambda node: rclpy.spin(node), args=(self,)
)
self.ros_spin_thread = threading.Thread(target=lambda node: rclpy.spin(node), args=(self,))
self.ros_spin_thread.start()
def subscriber_callback(self, msg):
@ -56,9 +52,7 @@ class TimeListener(rclpy.node.Node):
self.msg_event_object.set()
if msg.sec:
self.get_logger().info(
"From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec)
)
self.get_logger().info("From AP : True [sec:{}, nsec: {}]".format(msg.sec, msg.nanosec))
else:
self.get_logger().info("From AP : False")

View File

@ -50,7 +50,5 @@ def test_virtual_ports(launch_context, launch_description):
def validate_output(output):
assert "N starting data transfer loop" in output, "Test process had no output."
process_tools.assert_stderr_sync(
launch_context, virtual_ports, validate_output, timeout=5
)
process_tools.assert_stderr_sync(launch_context, virtual_ports, validate_output, timeout=5)
yield

View File

@ -74,14 +74,8 @@ class ExecuteFunction(Action):
"""Create an ExecuteFunction action."""
super().__init__(**left_over_kwargs)
if not callable(function):
raise TypeError(
"ExecuteFunction expected a callable for 'function', got '{}'".format(
type(function)
)
)
ensure_argument_type(
args, (collections.abc.Iterable, type(None)), "args", "ExecuteFunction"
)
raise TypeError("ExecuteFunction expected a callable for 'function', got '{}'".format(type(function)))
ensure_argument_type(args, (collections.abc.Iterable, type(None)), "args", "ExecuteFunction")
ensure_argument_type(kwargs, (dict, type(None)), "kwargs", "ExecuteFunction")
self.__function = function
self.__args = [] # type: Iterable
@ -98,9 +92,7 @@ class ExecuteFunction(Action):
"""Return the Action obtained by executing the function."""
return self.__action
def execute(
self, context: LaunchContext
) -> Optional[List[LaunchDescriptionEntity]]:
def execute(self, context: LaunchContext) -> Optional[List[LaunchDescriptionEntity]]:
"""Execute the function."""
action = self.__function(context, *self.__args, **self.__kwargs)
self.__action = action

View File

@ -68,9 +68,7 @@ class VirtualPortsLaunch:
return action
@staticmethod
def generate_launch_description_with_actions() -> (
Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]
):
def generate_launch_description_with_actions() -> Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]:
"""Generate a launch description with actions."""
launch_arguments = VirtualPortsLaunch.generate_launch_arguments()
@ -186,9 +184,7 @@ class MicroRosAgentLaunch:
return node
@staticmethod
def generate_launch_description_with_actions() -> (
Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]
):
def generate_launch_description_with_actions() -> Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]:
"""Generate a launch description with actions."""
launch_arguments = MicroRosAgentLaunch.generate_launch_arguments()
@ -315,9 +311,7 @@ class MAVProxyLaunch:
return mavproxy_process
@staticmethod
def generate_launch_description_with_actions() -> (
Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]
):
def generate_launch_description_with_actions() -> Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]:
"""Generate a launch description for MAVProxy."""
launch_arguments = MAVProxyLaunch.generate_launch_arguments()
@ -486,9 +480,7 @@ class SITLLaunch:
return sitl_process
@staticmethod
def generate_launch_description_with_actions() -> (
Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]
):
def generate_launch_description_with_actions() -> Tuple[LaunchDescription, Dict[Text, ExecuteFunction]]:
"""Generate a launch description for SITL."""
launch_arguments = SITLLaunch.generate_launch_arguments()
@ -553,8 +545,7 @@ class SITLLaunch:
DeclareLaunchArgument(
"instance",
default_value="0",
description="Set instance of SITL "
"(adds 10*instance to all port numbers).",
description="Set instance of SITL " "(adds 10*instance to all port numbers).",
),
DeclareLaunchArgument(
"defaults",
@ -599,8 +590,7 @@ class SITLLaunch:
DeclareLaunchArgument(
"base_port",
default_value="",
description="Set port num for base port(default 5670) "
"must be before -I option.",
description="Set port num for base port(default 5670) " "must be before -I option.",
),
DeclareLaunchArgument(
"rc_in_port",

View File

@ -29,9 +29,7 @@ def listify(fn) -> List[LaunchDescriptionEntity]:
"""Wrap a functions's return value in a list."""
@wraps(fn)
def listify_helper(
context: LaunchContext, *args, **kwargs
) -> List[LaunchDescriptionEntity]:
def listify_helper(context: LaunchContext, *args, **kwargs) -> List[LaunchDescriptionEntity]:
return [fn(context, args, kwargs)]
return listify_helper