Compare commits

...

1 Commits

Author SHA1 Message Date
ken910606 f2bb4679c2 Update master with local changes 1 month ago

@ -37,6 +37,7 @@ def arm_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.
"""
if not rclpy.ok():
rclpy.init(args=None)
node: Optional[Node] = None
try:
@ -82,7 +83,6 @@ def arm_disarm(
finally:
if node is not None:
node.destroy_node()
rclpy.shutdown()
if __name__ == "__main__":

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

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

Loading…
Cancel
Save