Python interface for ROCON services making scheduler requests.
This class is used by a ROCON service to handle its resource requests. When an instance of Requester is created, it creates its own scheduler feedback topic and connects to the ROCON scheduler topic.
Parameters: |
|
---|
As long as the Requester object remains, it will periodically send request messages to the scheduler, even when no requests are outstanding. The scheduler will provide feedback for them if anything has changed. The caller-provided feedback function will be invoked each time a feedback message arrives, like this:
Param rset: | The current set of requests including any updates from the scheduler. |
---|---|
Type rset: | RequestSet |
The feedback function is called when new feedback is received from the scheduler, already holding the Big Requester Lock. It is expected to iterate over its RequestSet, checking the status of every ResourceRequest it contains, modifying them appropriately, then return without waiting. If any changes occur, the scheduler will be notified after this callback returns.
Usage example:
#!/usr/bin/env python
""" Requester usage example. """
import rospy
from scheduler_msgs.msg import Request, Resource
from concert_scheduler_requests import Requester
class ExampleRequester:
def __init__(self):
rospy.init_node("example_requester")
self.rqr = Requester(self.feedback)
self.request_turtlebot()
self.timer = rospy.Timer(rospy.Duration(2.0), self.periodic_update)
rospy.spin()
def feedback(self, rset):
""" Scheduler feedback function. """
for rq in rset.values():
if rq.msg.status == Request.WAITING:
rospy.loginfo('Request queued: ' + str(rq.uuid))
elif rq.msg.status == Request.GRANTED:
rospy.loginfo('Request granted: ' + str(rq.uuid))
elif rq.msg.status == Request.CLOSED:
rospy.loginfo('Request closed: ' + str(rq.uuid))
elif rq.msg.status == Request.PREEMPTING:
rospy.loginfo('Request preempted (reason='
+ str(rq.msg.reason) + '): ' + str(rq.uuid))
rq.cancel() # release preempted resource immediately
def periodic_update(self, event):
""" Timer event handler for periodic request updates. """
try:
# cancel the previous request, holding the Big Requester Lock
with self.rqr.lock:
self.rqr.rset[self.request_id].cancel()
except KeyError:
# previous request is gone, request another similar robot
self.request_turtlebot()
def request_turtlebot(self):
""" Request any tutlebot able to run *example_rapp*. """
bot = Resource(rapp='example_rapp', uri='rocon:/turtlebot')
self.request_id = self.rqr.new_request([bot])
self.rqr.send_requests()
if __name__ == '__main__':
node = ExampleRequester()
Big Requester Lock.
This recursive Python threading lock serializes access to requester data. The requester feedback function is always invoked holding it. All Requester methods acquire it automatically, whenever needed.
In any other thread, acquire it when updating shared request set objects. Never hold it when sleeping or waiting for I/O.
RequestSet containing the current status of every ResourceRequest made by this requester. All requester operations are done using this object and its contents.
Default for new requests’ priorities if none specified.
Cancel all current requests to the scheduler.
After calling this method to cancel all your requests, invoke send_requests() to notify the scheduler immediately.
Add a new scheduler request.
Call this method for each desired new request, then invoke send_requests() to notify the scheduler.
Parameters: |
|
---|---|
Returns: | UUID (uuid.UUID) assigned. |
Raises : | WrongRequestError if request already exists. |
Send all current requests to the scheduler.
Use this method after updating rset or calling new_request() one or more times. It will send them to the scheduler immediately. Otherwise, they would not go out until the next heartbeat timer event.
Note
A recent heartbeat may already have sent some recent requests. This method just ensures they are all sent without further delay.