Skip to content

Commit

Permalink
Adding requester and request time for dispatch scripts (#240)
Browse files Browse the repository at this point in the history
Signed-off-by: Aaron Chong <[email protected]>
  • Loading branch information
aaronchongth authored Jun 19, 2024
1 parent 7c642aa commit 58ec578
Show file tree
Hide file tree
Showing 6 changed files with 57 additions and 5 deletions.
11 changes: 10 additions & 1 deletion rmf_demos_tasks/rmf_demos_tasks/dispatch_action.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,12 @@ def __init__(self, argv=sys.argv):
help='Use tool sink during perform action, \
default: false',
)
parser.add_argument(
'--requester',
help='Entity that is requesting this task',
type=str,
default='rmf_demos_tasks'
)

self.args = parser.parse_args(argv[1:])
self.response = asyncio.Future()
Expand Down Expand Up @@ -129,13 +135,16 @@ def __init__(self, argv=sys.argv):
payload['type'] = 'dispatch_task_request'
request = {}

# Set task request start time
# Set task request request time and start time
now = self.get_clock().now().to_msg()
now.sec = now.sec + self.args.start_time
start_time = now.sec * 1000 + round(now.nanosec / 10**6)
request['unix_millis_request_time'] = start_time
request['unix_millis_earliest_start_time'] = start_time
# todo(YV): Fill priority after schema is added

request['requester'] = self.args.requester

# Define task request category
request['category'] = 'compose'

Expand Down
11 changes: 10 additions & 1 deletion rmf_demos_tasks/rmf_demos_tasks/dispatch_clean.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,12 @@ def __init__(self, argv=sys.argv):
action='store_true',
help='Use sim time, default: false',
)
parser.add_argument(
'--requester',
help='Entity that is requesting this task',
type=str,
default='rmf_demos_tasks'
)

self.args = parser.parse_args(argv[1:])
self.response = asyncio.Future()
Expand Down Expand Up @@ -111,12 +117,15 @@ def __init__(self, argv=sys.argv):
payload['type'] = 'dispatch_task_request'
request = {}

# Set task request start time
# Set task request request time and start time
now = self.get_clock().now().to_msg()
now.sec = now.sec + self.args.start_time
start_time = now.sec * 1000 + round(now.nanosec / 10**6)
request['unix_millis_request_time'] = start_time
request['unix_millis_earliest_start_time'] = start_time

request['requester'] = self.args.requester

# Define task request category
request['category'] = 'compose'

Expand Down
10 changes: 9 additions & 1 deletion rmf_demos_tasks/rmf_demos_tasks/dispatch_delivery.py
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,12 @@ def __init__(self, argv=sys.argv):
action='store_true',
help='Use sim time, default: false',
)
parser.add_argument(
'--requester',
help='Entity that is requesting this task',
type=str,
default='rmf_demos_tasks'
)

self.args = parser.parse_args(argv[1:])
self.response = asyncio.Future()
Expand Down Expand Up @@ -166,11 +172,13 @@ def __init__(self, argv=sys.argv):
payload['type'] = 'dispatch_task_request'
request = {}

# Set task request start time
# Set task request request time, start time and requester
now = self.get_clock().now().to_msg()
now.sec = now.sec + self.args.start_time
start_time = now.sec * 1000 + round(now.nanosec / 10**6)
request['unix_millis_request_time'] = start_time
request['unix_millis_earliest_start_time'] = start_time
request['requester'] = self.args.requester

if self.args.fleet:
request['fleet_name'] = self.args.fleet
Expand Down
8 changes: 8 additions & 0 deletions rmf_demos_tasks/rmf_demos_tasks/dispatch_go_to_place.py
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,12 @@ def __init__(self, argv=sys.argv):
action='store_true',
help='Use sim time, default: false',
)
parser.add_argument(
'--requester',
help='Entity that is requesting this task',
type=str,
default='rmf_demos_tasks'
)

self.args = parser.parse_args(argv[1:])
self.response = asyncio.Future()
Expand Down Expand Up @@ -154,7 +160,9 @@ def __init__(self, argv=sys.argv):
'category': 'go_to_place',
'phases': [{'activity': go_to_activity}],
},
'unix_millis_request_time': start_time,
'unix_millis_earliest_start_time': start_time,
'requester': self.args.requester,
}

if self.args.fleet:
Expand Down
11 changes: 10 additions & 1 deletion rmf_demos_tasks/rmf_demos_tasks/dispatch_patrol.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,6 +84,12 @@ def __init__(self, argv=sys.argv):
action='store_true',
help='Use sim time, default: false',
)
parser.add_argument(
'--requester',
help='Entity that is requesting this task',
type=str,
default='rmf_demos_tasks'
)

self.args = parser.parse_args(argv[1:])
self.response = asyncio.Future()
Expand Down Expand Up @@ -120,13 +126,16 @@ def __init__(self, argv=sys.argv):

request = {}

# Set task request start time
# Set task request request time and start time
now = self.get_clock().now().to_msg()
now.sec = now.sec + self.args.start_time
start_time = now.sec * 1000 + round(now.nanosec / 10**6)
request['unix_millis_request_time'] = start_time
request['unix_millis_earliest_start_time'] = start_time
# todo(YV): Fill priority after schema is added

request['requester'] = self.args.requester

# Define task request category
request['category'] = 'patrol'

Expand Down
11 changes: 10 additions & 1 deletion rmf_demos_tasks/rmf_demos_tasks/dispatch_teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,12 @@ def __init__(self, argv=sys.argv):
action='store_true',
help='Use sim time, default: false',
)
parser.add_argument(
'--requester',
help='Entity that is requesting this task',
type=str,
default='rmf_demos_tasks'
)

self.args = parser.parse_args(argv[1:])
self.response = asyncio.Future()
Expand Down Expand Up @@ -99,13 +105,16 @@ def __init__(self, argv=sys.argv):
payload['type'] = 'dispatch_task_request'
request = {}

# Set task request start time
# Set task request request time and start time
now = self.get_clock().now().to_msg()
now.sec = now.sec + self.args.start_time
start_time = now.sec * 1000 + round(now.nanosec / 10**6)
request['unix_millis_request_time'] = start_time
request['unix_millis_earliest_start_time'] = start_time
# todo(YV): Fill priority after schema is added

request['requester'] = self.args.requester

# Define task request category
request['category'] = 'compose'

Expand Down

0 comments on commit 58ec578

Please sign in to comment.