Skip to content

Commit 481abbe

Browse files
committed
Finish in-code documentation for API
1 parent c16a062 commit 481abbe

2 files changed

Lines changed: 111 additions & 61 deletions

File tree

README.md

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -115,11 +115,11 @@ The `action_result` is an enumerated value denoting the result of the action (us
115115

116116
### Standard Communication Channels
117117

118-
Tasks and robot definition files declare actions and observations, and these files are include through [BenchBot Add-ons](https://github.com/roboticvisionorg/benchbot_addons). The add-on creator is free to add and declare channels as they please, but it is a better experience for all if channel definitions are as consistent as possible across the BenchBot ecosystem.
118+
Tasks and robot definition files declare actions and observations, and these files are include through [BenchBot add-ons](https://github.com/roboticvisionorg/benchbot_addons). The add-on creator is free to add and declare channels as they please, but it is a better experience for all if channel definitions are as consistent as possible across the BenchBot ecosystem.
119119

120120
So if you're adding a robot that move between a set of poses, declare a channel called `'move_next` with no arguments. Likewise, a robot that receives image observations should use a channel named `'image_rgb'` with the same format as described below. Feel free to implement the channels however you please for your robot, but consistent interfaces should always be preferred.
121121

122-
If you encounter a task using non-standard channel configurations, the API has all the functionality you need as a user to handle them (`actions` & `config` properties, plus observation dict returned by `step()` & `reset()`). On the other hand, maybe the non-standard channel should be a new standard. New standard communication channels are always welcome; please open a pull request with the details!
122+
If you encounter a task using non-standard channel configurations, the API has all the functionality you need as a user to handle them (`actions`, `config`, & `observations` properties). On the other hand, maybe the non-standard channel should be a new standard. New standard communication channels are always welcome; please open a pull request with the details!
123123

124124
#### Standard action channels:
125125

@@ -164,6 +164,7 @@ The API handles communication for all parts of the BenchBot system, including co
164164
| API method or property | Description |
165165
| ----------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
166166
| `actions` | Returns the list of actions currently available to the agent. This will update as actions are performed in the environment (for example if the agent has collided with an obstacle this list will be empty). |
167+
| `observations` | Returns the lists of observations available to the agent. |
167168
| `step(action, **action_args)` | Performs the requested action with the provided named action arguments. See [Using the API to communicate with a robot](#using-the-api-to-communicate-with-a-robot) above for further details. |
168169

169170
### Creating results

benchbot_api/benchbot.py

Lines changed: 108 additions & 59 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222

2323

2424
class _UnexpectedResponseError(requests.RequestException):
25-
""" """
25+
"""Consistent error messaging for when the Supervisor rejects a query"""
2626
def __init__(self, http_status_code, *args, **kwargs):
2727
super(_UnexpectedResponseError, self).__init__(
2828
"Received an unexpected response from BenchBot supervisor "
@@ -32,34 +32,45 @@ def __init__(self, http_status_code, *args, **kwargs):
3232
@unique
3333
class ActionResult(Enum):
3434
"""Result of an action that an agent has taken
35-
SUCCESS : Action has finished successfully and the robot is ready for a new action
36-
FINISHED : Action has finished successfully and the robot has finished all its goals
37-
COLLISION : Action has not finished successfully and the robot has collided with an obstacle
35+
36+
Values
37+
------
38+
SUCCESS :
39+
Action succeeded, and the robot is ready for a new action
40+
FINISHED :
41+
Action succeeded, and the robot is finished in the current scene
42+
COLLISION :
43+
Action failed, and the robot has colliding with an obstacle
3844
"""
3945
SUCCESS = 0,
4046
FINISHED = 1,
4147
COLLISION = 2
4248

4349

4450
class BenchBot(object):
45-
"""BenchBot handles communication between the client and server systems, and abstracts away hardware and simulation, such that code written to be run by BenchBot will run with either a real or simulated robot"""
46-
47-
SUPPORTED_ACTIONS = {
48-
'_debug_move': [],
49-
'move_next': [],
50-
'move_distance': ['distance'],
51-
'move_angle': ['angle']
52-
}
53-
51+
"""BenchBot handles communication between the client and server systems,
52+
and abstracts away hardware and simulation, such that code written to be
53+
run by BenchBot will run with either a real or simulated robot
54+
"""
5455
@unique
5556
class RouteType(Enum):
56-
""" """
57+
"""Enum denoting type of route (used in building routes when talking
58+
with a Supervisor)
59+
"""
5760
CONNECTION = 0,
5861
CONFIG = 1,
5962
ROBOT = 2,
6063
RESULTS = 3,
6164
EXPLICIT = 4
6265

66+
ROUTE_MAP = {
67+
RouteType.CONNECTION: 'connections',
68+
RouteType.CONFIG: 'config',
69+
RouteType.ROBOT: 'robot',
70+
RouteType.RESULTS: 'results_functions',
71+
RouteType.EXPLICIT: ''
72+
}
73+
6374
def __init__(self,
6475
agent=None,
6576
supervisor_address='http://' + DEFAULT_ADDRESS + ':' +
@@ -77,42 +88,61 @@ def __init__(self,
7788
self.start()
7889

7990
def _build_address(self, route_name, route_type=RouteType.CONNECTION):
80-
"""
91+
"""Builds an address for communication with a running instance of
92+
BenchBot Supervisor
8193
8294
Parameters
8395
----------
8496
route_name :
97+
The name of the route within the subdirectory (e.g. 'is_finished')
8598
8699
route_type :
87-
Default value = RouteType.CONNECTION
100+
The type of route which maps to the URL's subdirectory (e.g.
101+
RouteType.ROBOT = 'robot')
88102
89103
Returns
90104
-------
91-
92-
105+
string
106+
A full URL string describing the route (e.g.
107+
'http://localhost:10000/robot/is_finished')
93108
"""
94109
base = self.supervisor_address + (
95110
'' if self.supervisor_address.endswith('/') else '/')
96-
if route_type == BenchBot.RouteType.CONNECTION:
97-
return base + 'connections/' + route_name
98-
elif route_type == BenchBot.RouteType.CONFIG:
99-
return base + 'config/' + route_name
100-
elif route_type == BenchBot.RouteType.ROBOT:
101-
return base + 'robot/' + route_name
102-
elif route_type == BenchBot.RouteType.RESULTS:
103-
return base + 'results_functions/' + route_name
104-
elif route_type == BenchBot.RouteType.EXPLICIT:
105-
return base + route_name
106-
else:
111+
if route_type not in BenchBot.ROUTE_MAP:
107112
raise ValueError(
108113
"Cannot build address from invalid route type: %s" %
109114
route_type)
115+
return (base + BenchBot.ROUTE_MAP[route_type] +
116+
('/' if BenchBot.ROUTE_MAP[route_type] else '') + route_name)
110117

111118
def _query(self,
112119
route_name=None,
113120
route_type=RouteType.CONNECTION,
114121
data=None,
115122
method=requests.get):
123+
"""Sends a request to a running BenchBot Supervisor, and returns the
124+
response
125+
126+
Parameters
127+
----------
128+
route_name:
129+
The name of the route within the subdirectory (e.g. 'is_finished')
130+
131+
route_type :
132+
The type of route which maps to the URL's subdirectory (e.g.
133+
RouteType.ROBOT = 'robot')
134+
135+
data :
136+
A dict of data to attach to the request
137+
138+
method :
139+
HTTP method to use for the request (should generally always be GET)
140+
141+
Returns
142+
-------
143+
dict
144+
The JSON data returned by the request's response
145+
"""
116146
data = {} if data is None else data
117147
addr = self._build_address(route_name, route_type)
118148
try:
@@ -127,16 +157,17 @@ def _query(self,
127157

128158
@staticmethod
129159
def _attempt_connection_imports(connection_data):
130-
"""
160+
"""Attempts to dynamically import any API-side connection callbacks
161+
(this method should never need to be called manually)
131162
132163
Parameters
133164
----------
134165
connection_data :
135-
166+
A dict containing the data defining the connection
136167
137168
Returns
138169
-------
139-
170+
None
140171
141172
"""
142173
if 'callback_api' in connection_data:
@@ -152,7 +183,8 @@ def actions(self):
152183
Returns
153184
-------
154185
list
155-
A list of actions the robot can take. If the robot has collided with an obstacle or finished its task, this list will be empty.
186+
A list of actions the robot can take. If the robot has collided
187+
with an obstacle or finished its task, this list will be empty.
156188
"""
157189
return ([] if self._query('is_collided',
158190
BenchBot.RouteType.ROBOT)['is_collided']
@@ -167,13 +199,14 @@ def config(self):
167199
Returns
168200
-------
169201
dict
170-
A dict of all configuration parameters as retrieved from the running BenchBot supervisor
202+
A dict of all configuration parameters as retrieved from the
203+
running BenchBot supervisor
171204
"""
172205
return self._query('', BenchBot.RouteType.CONFIG)
173206

174207
@property
175208
def observations(self):
176-
"""The list of observations the robot can see.
209+
"""The list of observations the robot is currently providing
177210
178211
Returns
179212
-------
@@ -184,7 +217,8 @@ def observations(self):
184217

185218
@property
186219
def result_filename(self):
187-
"""The result filename. If the path doesn't exist, it makes it.
220+
"""The location where results should be written. If the path doesn't
221+
exist, it makes it.
188222
189223
Returns
190224
-------
@@ -196,6 +230,16 @@ def result_filename(self):
196230
return os.path.join(RESULT_LOCATION)
197231

198232
def empty_results(self):
233+
"""Helper method for getting an empty results dict, pre-populated with
234+
metadata from the currently running configuration. See the
235+
'results_functions()' method for help filling in the empty results.
236+
237+
Returns
238+
-------
239+
dict
240+
A dict with the fields 'task_details' (populated),
241+
'environment_details' (populated), and 'results' (empty)
242+
"""
199243
return {
200244
'task_details':
201245
self._query('task', BenchBot.RouteType.CONFIG),
@@ -206,6 +250,14 @@ def empty_results(self):
206250
}
207251

208252
def next_scene(self):
253+
"""Moves the robot to the next scene, declaring failure if there is no
254+
next scene defined
255+
256+
Returns
257+
-------
258+
bool
259+
Denotes whether moving to the next scene succeeded or failed
260+
"""
209261
# Bail if next is not a valid operation
210262
if (self._query('is_collided',
211263
BenchBot.RouteType.ROBOT)['is_collided']):
@@ -223,12 +275,15 @@ def next_scene(self):
223275
return resp['next_success']
224276

225277
def reset(self):
226-
"""Resets the robot state, and restarts the supervisor if necessary.
278+
"""Resets the robot state, starting again at the first scene with a
279+
fresh environment. Resetting is skipped if the environment is still in
280+
a fresh state.
227281
228282
Returns
229283
-------
230284
tuple
231-
Observations and action result at the start of the task.
285+
Observations and action result at the start of the task (should
286+
always be SUCCESS).
232287
"""
233288
# Only restart the supervisor if it is in a dirty state
234289
if self._query('is_dirty', BenchBot.RouteType.ROBOT)['is_dirty']:
@@ -251,8 +306,8 @@ def results_functions(self):
251306

252307
def run(self):
253308
"""Helper function that runs the robot according to the agent given.
254-
Use this function as the basis for implementing a custom AI loop.
255-
309+
Generally, you should use this function and implement your object in
310+
your own custom agent class.
256311
"""
257312
if self.agent is None:
258313
raise RuntimeError(
@@ -278,12 +333,9 @@ def scene_fn():
278333
self.results_functions())
279334

280335
def start(self):
281-
"""Connects to the supervisor and initialises the connection callbacks.
282-
283-
Raises
284-
------
285-
requests.ConnectionError
286-
If the BenchBot supervisor cannot be found.
336+
"""Establishes a connect to the Supervisor, and then uses this to
337+
establish a connection with a running robot. It then initialises all
338+
connections, ensuring API-side callbacks are accessible.
287339
"""
288340
# Establish a connection to the supervisor (throw an error on failure)
289341
print("Waiting to establish connection to a running supervisor ... ",
@@ -334,17 +386,20 @@ def start(self):
334386
self.reset()
335387

336388
def step(self, action, **action_kwargs):
337-
"""Performs 'action' with 'action_kwargs' as its arguments and returns the observations after 'action' has completed, regardless of the result.
389+
"""Performs 'action' with 'action_kwargs' as its arguments, and returns
390+
the observations after 'action' has completed, regardless of the
391+
result.
338392
339393
Parameters
340394
----------
341-
action : {'move_next', 'move_distance', 'move_angle'}
342-
Action to be performed, must be one of 'move_next', 'move_distance', or 'move_angle'.
395+
action :
396+
Name of action to be performed. The 'actions' property is available
397+
to list available actions if you are unsure what is available.
398+
343399
**action_kwargs
344-
Arguments to be used by the action.
345-
Must be empty if action is 'move_next'.
346-
Must be 'distance' if action is 'move_distance'. Distance is in metres.
347-
Must be 'angle' if action is 'move_angle'. Angle is in degrees.
400+
Arguments to be used by the action. See the connection's callbacks
401+
by using the 'config' property if you are unsure of an action's
402+
supported arguments.
348403
349404
Returns
350405
-------
@@ -359,12 +414,6 @@ def step(self, action, **action_kwargs):
359414
raise ValueError(
360415
"Action '%s' is not a valid action (valid actions are: %s)."
361416
% (action, ', '.join(BenchBot.SUPPORTED_ACTIONS.keys())))
362-
# elif len(action_kwargs) != len(BenchBot.SUPPORTED_ACTIONS[action]):
363-
# raise ValueError(
364-
# "Action '%s' requires %d args (%s); you provided %d." %
365-
# (action, len(BenchBot.SUPPORTED_ACTIONS[action]),
366-
# ', '.join(BenchBot.SUPPORTED_ACTIONS[action]),
367-
# len(action_kwargs)))
368417
else:
369418
missing_keys = (set(BenchBot.SUPPORTED_ACTIONS[action]) -
370419
set(action_kwargs.keys()))

0 commit comments

Comments
 (0)