Skip to content

Commit 00a0019

Browse files
committed
new: implements service client primitive
* moves AtomicVar into utils * added additional checks in action client to capture common misstakes
1 parent 37d44d8 commit 00a0019

File tree

3 files changed

+160
-25
lines changed

3 files changed

+160
-25
lines changed

skiros2_std_skills/skiros2_std_skills/action_client_primitive.py

Lines changed: 16 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -10,24 +10,7 @@
1010
from threading import Lock
1111
from typing import Optional
1212
from action_msgs.msg import GoalStatus
13-
14-
class AtomicVar:
15-
def __init__(self, initialValue: Optional[any]=None, sharedLock: Optional[Lock] = None) -> None:
16-
self.lock = sharedLock
17-
self.var = initialValue
18-
if self.lock is None:
19-
self.lock = Lock()
20-
21-
def get_and_reset(self):
22-
with self.lock:
23-
var = self.var
24-
if var is not None:
25-
self.var = None
26-
return var
27-
28-
def set(self, var):
29-
with self.lock:
30-
self.var = var
13+
from skiros2_std_skills.utils import AtomicVar
3114

3215
class PrimitiveActionClient(PrimitiveBase):
3316
"""
@@ -37,6 +20,10 @@ class PrimitiveActionClient(PrimitiveBase):
3720
3821
build_client_onstart defines if the client will be built every time the skill it is called or not
3922
(save up to 0.3 seconds). Default is True
23+
24+
feedback_timeout_sec defines a timeout in seconds for not reciving action
25+
feedback in a timely manner. Could be used to detect if the action server
26+
has gone down or experiences issues. Default is no timeout.
4027
"""
4128
build_client_onstart = True
4229
feedback_timeout_sec = None # set to second if you want reliability
@@ -68,12 +55,20 @@ def onStart(self):
6855

6956
if self.build_client_onstart or self.client is None:
7057
self.client = self.buildClient()
71-
58+
59+
if self.client is None:
60+
return self.startError("Action client returned by buildClient() is None.", -105)
61+
7262
if not self.client.wait_for_server(0.5):
7363
return self.startError("Action server is not available: {}".format(self.client), -101)
7464

7565
self._goal_handle = None
76-
self._goal_future = self.client.send_goal_async(self.buildGoal(), feedback_callback = self._feedback_callback)
66+
67+
goal = self.buildGoal()
68+
if goal is None:
69+
return self.startError("Action goal is None", -106)
70+
71+
self._goal_future = self.client.send_goal_async(goal, feedback_callback = self._feedback_callback)
7772
self._goal_future.add_done_callback(self._goal_request_callback)
7873

7974
self._get_result_future = None
@@ -89,8 +84,7 @@ def onStart(self):
8984
def execute(self):
9085
res = self._goal_msg.get_and_reset()
9186
if res is not None:
92-
if not res:
93-
# Rejected
87+
if res == False:
9488
return self.fail("Rejected.", -102)
9589

9690
fb = self._feedback_msg.get_and_reset()
@@ -115,9 +109,6 @@ def execute(self):
115109
return self.fail("Action feedback did not arrive within timeout of %d sec" % self.feedback_timeout_sec, -104)
116110

117111
return State.Running
118-
119-
def get_result_msg(self):
120-
return self.client.get_result()
121112

122113
def _cancel_callback(self, future):
123114
cancel_response = future.result()
Lines changed: 119 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,119 @@
1+
from skiros2_common.core.abstract_skill import State
2+
from skiros2_common.core.primitive import PrimitiveBase
3+
from skiros2_common.core.params import ParamTypes
4+
import skiros2_common.tools.logger as log
5+
import rclpy
6+
from rclpy import action, task, client, Future
7+
from rclpy.time import Duration
8+
from actionlib_msgs.msg import GoalStatus
9+
import queue
10+
from threading import Lock
11+
from typing import Optional
12+
from action_msgs.msg import GoalStatus
13+
from skiros2_std_skills.utils import AtomicVar
14+
15+
class PrimitiveServiceClient(PrimitiveBase):
16+
"""
17+
@brief Base class for skills based on a service client.
18+
19+
See test_service_skill for a practical example
20+
"""
21+
22+
build_client_onstart = False
23+
call_timeout_sec = None
24+
25+
def onPreempt(self):
26+
"""
27+
@brief Cancel service call
28+
"""
29+
log.debug("Cancel requested")
30+
if self._future is not None:
31+
self._future.cancel()
32+
self._future = None
33+
self.client.destroy()
34+
self.client = None
35+
log.debug("Service call canceled")
36+
return self.success("Service call canceled.")
37+
else:
38+
return self.fail("Goal has not been accepted or rejected, cannot cancel.")
39+
40+
def onStart(self):
41+
self._response = AtomicVar()
42+
43+
# 1. Build client
44+
if self.build_client_onstart or self.client is None:
45+
self.client = self.buildClient()
46+
47+
if self.client is None:
48+
return self.startError("Action client returned by buildClient() is None.", -101)
49+
50+
# 2. Wait for server
51+
if not self.client.wait_for_service(0.5):
52+
return self.startError("Service server is not available: {}".format(self.client), -101)
53+
54+
# 3. Build message and call service
55+
service_request = self.buildRequest()
56+
if service_request is None:
57+
return self.startError("Service request is None", -106)
58+
59+
self._future = self.client.call_async(service_request)
60+
self._future.add_done_callback(self._response_callback)
61+
self._last_call_timestamp = self.node.get_clock().now()
62+
63+
return True
64+
65+
def _response_callback(self, future: Future):
66+
self._response.set(future.result())
67+
68+
def execute(self):
69+
res = self._response.get_and_reset()
70+
if res is not None:
71+
return self.onDone(res)
72+
73+
time_since_start_sec = (self.node.get_clock().now()-self._last_call_timestamp).nanoseconds/1.0e9
74+
if self.call_timeout_sec is not None:
75+
if time_since_start_sec > self.call_timeout_sec:
76+
self.client.destroy()
77+
self.client = None
78+
return self.fail("Service call did not finish within timeout of %d sec" % self.call_timeout_sec, -104)
79+
80+
return self.step("Service called, been waiting for %.1f sec" % time_since_start_sec)
81+
82+
def onInit(self):
83+
"""
84+
@brief Optional to override. Called once when loading the primitive. If return False, the primitive is not loaded
85+
@return True if loaded correctly. False on error
86+
"""
87+
self.client = None
88+
if not self.build_client_onstart:
89+
self.client = self.buildClient()
90+
91+
return True
92+
93+
def onEnd(self):
94+
"""
95+
@brief Optional to override. Routine called just after skill execution end
96+
"""
97+
return True
98+
99+
def buildClient(self)->client.Client:
100+
"""
101+
@brief To override. Called when starting the skill
102+
@return an service client created by self.node.create_client(...)
103+
"""
104+
pass
105+
106+
def buildRequest(self):
107+
"""
108+
@brief To override. Called when starting the skill
109+
@return an action msg initialized
110+
"""
111+
pass
112+
113+
def onDone(self, response):
114+
"""
115+
@brief To override. Called when response has arrived.
116+
@return self.success or self.fail
117+
"""
118+
#Do something with result msg
119+
return self.success("Finished. Result: {}".format(response))
Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
import queue
2+
from threading import Lock
3+
from typing import Optional
4+
5+
class AtomicVar:
6+
def __init__(self, initialValue: Optional[any]=None, sharedLock: Optional[Lock] = None) -> None:
7+
self.lock = sharedLock
8+
self.var = initialValue
9+
if self.lock is None:
10+
self.lock = Lock()
11+
12+
def get_and_reset(self):
13+
with self.lock:
14+
var = self.var
15+
if var is not None:
16+
self.var = None
17+
return var
18+
19+
def get(self):
20+
with self.lock:
21+
return self.var
22+
23+
def set(self, var):
24+
with self.lock:
25+
self.var = var

0 commit comments

Comments
 (0)