Update master with local changes

ken910606 1 month ago
parent 989d3ad2d2
commit f2bb4679c2

@ -37,6 +37,7 @@ def arm_disarm(
param1: 1.0 to arm, 0.0 to disarm. param1: 1.0 to arm, 0.0 to disarm.
param2: usually 0. Some stacks use 21196 for force-arm (ArduPilot); pass via param2 if needed. param2: usually 0. Some stacks use 21196 for force-arm (ArduPilot); pass via param2 if needed.
""" """
if not rclpy.ok():
rclpy.init(args=None) rclpy.init(args=None)
node: Optional[Node] = None node: Optional[Node] = None
try: try:
@ -82,7 +83,6 @@ def arm_disarm(
finally: finally:
if node is not None: if node is not None:
node.destroy_node() node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__": if __name__ == "__main__":

@ -42,6 +42,7 @@ def change_mode(
) -> ChangeModeResult: ) -> ChangeModeResult:
"""One-shot helper for collaborators who want minimal code.""" """One-shot helper for collaborators who want minimal code."""
if not rclpy.ok():
rclpy.init(args=None) rclpy.init(args=None)
node: Optional[Node] = None node: Optional[Node] = None
try: try:
@ -87,7 +88,6 @@ def change_mode(
finally: finally:
if node is not None: if node is not None:
node.destroy_node() node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__": if __name__ == "__main__":

@ -35,6 +35,7 @@ def takeoff(
service_name: str = DEFAULT_SERVICE_NAME, service_name: str = DEFAULT_SERVICE_NAME,
) -> TakeoffResult: ) -> TakeoffResult:
"""One-shot MAV_CMD_NAV_TAKEOFF wrapper.""" """One-shot MAV_CMD_NAV_TAKEOFF wrapper."""
if not rclpy.ok():
rclpy.init(args=None) rclpy.init(args=None)
node: Optional[Node] = None node: Optional[Node] = None
try: try:
@ -80,7 +81,6 @@ def takeoff(
finally: finally:
if node is not None: if node is not None:
node.destroy_node() node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__": if __name__ == "__main__":

Loading…
Cancel
Save