Revision 465c7ad7 client/python/hlrc_client/MiddlewareROS.py
client/python/hlrc_client/MiddlewareROS.py | ||
---|---|---|
28 | 28 |
from Middleware import * |
29 | 29 |
import errno |
30 | 30 |
|
31 |
import roslib; |
|
32 | 31 |
import rospy |
33 | 32 |
import actionlib |
34 | 33 |
from hlrc_server.msg import * |
34 |
from geometry_msgs.msg import Point |
|
35 | 35 |
from actionlib_msgs.msg import GoalStatus |
36 | 36 |
|
37 | 37 |
class MiddlewareROS(Middleware): |
... | ... | |
86 | 86 |
self.gazetarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/gaze", gazetargetAction) |
87 | 87 |
self.gazetarget_client.wait_for_server() |
88 | 88 |
|
89 |
self.logger.debug("creating lookattarget action client") |
|
90 |
self.lookattarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/lookat", lookattargetAction) |
|
91 |
self.lookattarget_client.wait_for_server() |
|
92 |
|
|
89 | 93 |
self.logger.debug("creating mouthtarget action client") |
90 | 94 |
self.mouthtarget_client = actionlib.SimpleActionClient(self.base_scope + "/set/mouth", mouthtargetAction) |
91 | 95 |
self.mouthtarget_client.wait_for_server() |
... | ... | |
196 | 200 |
|
197 | 201 |
self.logger.debug("gaze rpc done") |
198 | 202 |
|
203 |
def publish_lookat_target(self, x, y, z, blocking, frame_id='', roll=0.0): |
|
204 |
"""publish a gaze target via mw |
|
205 |
:param x,y,z: position to look at (in eyes frame or frame_id) |
|
206 |
:param roll: side-ways motion of head |
|
207 |
:param blocking: True if this call should block until execution finished on robot |
|
208 |
""" |
|
209 |
self.logger.debug("calling the gaze rpc (%s)..." % ("BLOCKING" if blocking else "NON-BLOCKING")) |
|
210 |
|
|
211 |
# create a goal to send to the action server. |
|
212 |
goal = lookattargetGoal() |
|
213 |
goal.header.frame_id = frame_id |
|
214 |
goal.header.stamp = rospy.Time.now() |
|
215 |
|
|
216 |
p = Point() |
|
217 |
p.x = float(x) |
|
218 |
p.y = float(y) |
|
219 |
p.z = float(z) |
|
220 |
goal.point = p |
|
221 |
goal.roll = roll |
|
222 |
|
|
223 |
# send the goal to the server |
|
224 |
if blocking: |
|
225 |
# send and wait: |
|
226 |
state = self.lookattarget_client.send_goal_and_wait(goal, execute_timeout=rospy.Duration.from_sec(MiddlewareROS.ROS_ACTION_CALL_TIMEOUT)) |
|
227 |
if state != GoalStatus.SUCCEEDED: |
|
228 |
self.logger.error("%s timed out waiting for result or soemthing else went wrong" % (sys._getframe().f_code.co_name)) |
|
229 |
else: |
|
230 |
# non blocking, fire & forget |
|
231 |
self.lookattarget_client.send_goal(goal) |
|
232 |
|
|
233 |
self.logger.debug("lookat rpc done") |
|
234 |
|
|
199 | 235 |
def publish_mouth_target(self, mouth, blocking): |
200 | 236 |
"""publish a mouth target via mw |
201 | 237 |
:param mouth: mouth value to set |
Also available in: Unified diff