Skip to content

Commit

Permalink
Temporary Patch to fix rclpy:1123
Browse files Browse the repository at this point in the history
  • Loading branch information
jmblixt3 committed Jun 20, 2024
1 parent 7942ccb commit 6ab52a3
Showing 1 changed file with 28 additions and 1 deletion.
29 changes: 28 additions & 1 deletion src/rovr_control/rovr_control/calibrate_field_coordinates.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,33 @@
from rovr_interfaces.action import CalibrateFieldCoordinates
from rovr_interfaces.srv import ResetOdom

from typing import Any
from threading import RLock

class PatchRclpyIssue1123(ActionClient):
_lock: RLock = None # type: ignore

@property
def _cpp_client_handle_lock(self) -> RLock:
if self._lock is None:
self._lock = RLock()
return self._lock

async def execute(self, *args: Any, **kwargs: Any) -> None:
with self._cpp_client_handle_lock:
return await super().execute(*args, **kwargs) # type: ignore

def send_goal_async(self, *args: Any, **kwargs: Any) -> Future:
with self._cpp_client_handle_lock:
return super().send_goal_async(*args, **kwargs)

def _cancel_goal_async(self, *args: Any, **kwargs: Any) -> Future:
with self._cpp_client_handle_lock:
return super()._cancel_goal_async(*args, **kwargs)

def _get_result_async(self, *args: Any, **kwargs: Any) -> Future:
with self._cpp_client_handle_lock:
return super()._get_result_async(*args, **kwargs)

class CalibrateFieldCoordinateServer(Node):
def __init__(self):
Expand All @@ -26,7 +53,7 @@ def __init__(self):
self.cli_set_apriltag_odometry = self.create_client(ResetOdom, "resetOdom")
self.future_odom = Future()

self.cli_spin = ActionClient(self, Spin, "spin")
self.cli_spin = PatchRclpyIssue1123(self, Spin, "spin")
self.future_spin = Future()

def execute_callback(self, goal_handle: ServerGoalHandle):
Expand Down

0 comments on commit 6ab52a3

Please sign in to comment.