class AsyncActionClient: """ Async wrapper around the action client API. """ def __init__(self, name, action_spec): self._loop = asyncio.get_event_loop() self.name = name self.action_spec = action_spec self._exception_monitor = ExceptionMonitor() self._started_event = asyncio.Event() async def start(self): """ Start the action client. """ self._client = ActionClient(self.name, self.action_spec) try: self._started_event.set() await self._exception_monitor.start() finally: # TODO(pbovbel) depends on https://github.com/ros/actionlib/pull/142 self._started_event.clear() self._client.stop() self._client = None async def _started(self, log_period=None): await log_during(self._started_event.wait(), f"Waiting for {self.name} client to be started...", period=5.0) async def wait_for_server(self, log_period=None): """ Wait for the action server to connect to this client. """ await self._started(log_period=log_period) await log_during(self._wait_for_server(), f"Waiting for {self.name} server...", period=log_period) async def _wait_for_server(self): while True: # Use a small timeout so that the execution can be cancelled if necessary connected = await self._loop.run_in_executor( None, self._client.wait_for_server, rospy.Duration(0.1)) if connected: return connected async def send_goal(self, goal): """ Send a goal to an action server. As in rospy, if you have not made sure the server is up and listening to the client, the goal will be swallowed. """ await self._started(log_period=5.0) async_handle = _AsyncGoalHandle( name=self.name, exception_monitor=self._exception_monitor, loop=self._loop) sync_handle = self._client.send_goal( goal, transition_cb=async_handle._transition_cb, feedback_cb=async_handle._feedback_cb, ) async_handle.goal_id = sync_handle.comm_state_machine.action_goal.goal_id.id async_handle.cancel = sync_handle.cancel return async_handle async def ensure_goal(self, goal, resend_timeout): """ Send a goal to an action server. If the goal is not processed by the action server within resend_timeout, resend the goal. """ while True: await self.wait_for_server(log_period=5.0) handle = await self.send_goal(goal) try: await asyncio.wait_for(handle.reach_status(GoalStatus.PENDING), timeout=resend_timeout) except asyncio.TimeoutError: logger.warn( f"Action goal for {self.name} was not processed within timeout, resending" ) handle.cancel() continue except asyncio.CancelledError: handle.cancel() raise return handle