isar 1.15.0__py3-none-any.whl → 1.34.9__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- isar/__init__.py +2 -5
- isar/apis/api.py +159 -66
- isar/apis/models/__init__.py +0 -1
- isar/apis/models/models.py +22 -12
- isar/apis/models/start_mission_definition.py +128 -123
- isar/apis/robot_control/robot_controller.py +41 -0
- isar/apis/schedule/scheduling_controller.py +135 -121
- isar/apis/security/authentication.py +5 -5
- isar/config/certs/ca-cert.pem +32 -32
- isar/config/keyvault/keyvault_service.py +1 -2
- isar/config/log.py +47 -39
- isar/config/logging.conf +16 -31
- isar/config/open_telemetry.py +102 -0
- isar/config/predefined_mission_definition/default_exr.json +49 -0
- isar/config/predefined_mission_definition/default_mission.json +1 -5
- isar/config/predefined_mission_definition/default_turtlebot.json +4 -11
- isar/config/predefined_missions/default.json +67 -87
- isar/config/predefined_missions/default_extra_capabilities.json +107 -0
- isar/config/settings.py +119 -142
- isar/eventhandlers/eventhandler.py +123 -0
- isar/mission_planner/local_planner.py +6 -20
- isar/mission_planner/mission_planner_interface.py +1 -1
- isar/models/events.py +184 -0
- isar/models/status.py +18 -0
- isar/modules.py +118 -205
- isar/robot/robot.py +377 -0
- isar/robot/robot_battery.py +60 -0
- isar/robot/robot_monitor_mission.py +357 -0
- isar/robot/robot_pause_mission.py +74 -0
- isar/robot/robot_resume_mission.py +67 -0
- isar/robot/robot_start_mission.py +66 -0
- isar/robot/robot_status.py +61 -0
- isar/robot/robot_stop_mission.py +68 -0
- isar/robot/robot_upload_inspection.py +75 -0
- isar/script.py +171 -0
- isar/services/service_connections/mqtt/mqtt_client.py +47 -11
- isar/services/service_connections/mqtt/robot_heartbeat_publisher.py +32 -0
- isar/services/service_connections/mqtt/robot_info_publisher.py +4 -3
- isar/services/service_connections/persistent_memory.py +69 -0
- isar/services/utilities/mqtt_utilities.py +93 -0
- isar/services/utilities/robot_utilities.py +20 -0
- isar/services/utilities/scheduling_utilities.py +393 -65
- isar/state_machine/state_machine.py +227 -486
- isar/state_machine/states/__init__.py +0 -7
- isar/state_machine/states/await_next_mission.py +114 -0
- isar/state_machine/states/blocked_protective_stop.py +60 -0
- isar/state_machine/states/going_to_lockdown.py +95 -0
- isar/state_machine/states/going_to_recharging.py +92 -0
- isar/state_machine/states/home.py +115 -0
- isar/state_machine/states/intervention_needed.py +77 -0
- isar/state_machine/states/lockdown.py +38 -0
- isar/state_machine/states/maintenance.py +36 -0
- isar/state_machine/states/monitor.py +137 -166
- isar/state_machine/states/offline.py +60 -0
- isar/state_machine/states/paused.py +92 -23
- isar/state_machine/states/pausing.py +48 -0
- isar/state_machine/states/pausing_return_home.py +48 -0
- isar/state_machine/states/recharging.py +80 -0
- isar/state_machine/states/resuming.py +57 -0
- isar/state_machine/states/resuming_return_home.py +64 -0
- isar/state_machine/states/return_home_paused.py +109 -0
- isar/state_machine/states/returning_home.py +217 -0
- isar/state_machine/states/stopping.py +61 -0
- isar/state_machine/states/stopping_due_to_maintenance.py +61 -0
- isar/state_machine/states/stopping_go_to_lockdown.py +60 -0
- isar/state_machine/states/stopping_go_to_recharge.py +51 -0
- isar/state_machine/states/stopping_return_home.py +77 -0
- isar/state_machine/states/unknown_status.py +72 -0
- isar/state_machine/states_enum.py +22 -5
- isar/state_machine/transitions/mission.py +192 -0
- isar/state_machine/transitions/return_home.py +106 -0
- isar/state_machine/transitions/robot_status.py +80 -0
- isar/state_machine/utils/common_event_handlers.py +73 -0
- isar/storage/blob_storage.py +71 -45
- isar/storage/local_storage.py +28 -14
- isar/storage/storage_interface.py +28 -6
- isar/storage/uploader.py +184 -55
- isar/storage/utilities.py +35 -27
- isar-1.34.9.dist-info/METADATA +496 -0
- isar-1.34.9.dist-info/RECORD +135 -0
- {isar-1.15.0.dist-info → isar-1.34.9.dist-info}/WHEEL +1 -1
- isar-1.34.9.dist-info/entry_points.txt +3 -0
- robot_interface/models/exceptions/__init__.py +0 -7
- robot_interface/models/exceptions/robot_exceptions.py +274 -4
- robot_interface/models/initialize/__init__.py +0 -1
- robot_interface/models/inspection/__init__.py +0 -13
- robot_interface/models/inspection/inspection.py +43 -34
- robot_interface/models/mission/mission.py +18 -14
- robot_interface/models/mission/status.py +20 -25
- robot_interface/models/mission/task.py +156 -92
- robot_interface/models/robots/battery_state.py +6 -0
- robot_interface/models/robots/media.py +13 -0
- robot_interface/models/robots/robot_model.py +7 -7
- robot_interface/robot_interface.py +135 -66
- robot_interface/telemetry/mqtt_client.py +84 -12
- robot_interface/telemetry/payloads.py +111 -12
- robot_interface/utilities/json_service.py +7 -1
- isar/config/predefined_missions/default_turtlebot.json +0 -110
- isar/config/predefined_poses/__init__.py +0 -0
- isar/config/predefined_poses/predefined_poses.py +0 -616
- isar/config/settings.env +0 -26
- isar/mission_planner/sequential_task_selector.py +0 -23
- isar/mission_planner/task_selector_interface.py +0 -31
- isar/models/communication/__init__.py +0 -0
- isar/models/communication/message.py +0 -12
- isar/models/communication/queues/__init__.py +0 -4
- isar/models/communication/queues/queue_io.py +0 -12
- isar/models/communication/queues/queue_timeout_error.py +0 -2
- isar/models/communication/queues/queues.py +0 -19
- isar/models/communication/queues/status_queue.py +0 -20
- isar/models/mission_metadata/__init__.py +0 -0
- isar/services/readers/__init__.py +0 -0
- isar/services/readers/base_reader.py +0 -37
- isar/services/service_connections/mqtt/robot_status_publisher.py +0 -93
- isar/services/service_connections/stid/__init__.py +0 -0
- isar/services/service_connections/stid/stid_service.py +0 -45
- isar/services/utilities/queue_utilities.py +0 -39
- isar/state_machine/states/idle.py +0 -40
- isar/state_machine/states/initialize.py +0 -60
- isar/state_machine/states/initiate.py +0 -129
- isar/state_machine/states/off.py +0 -18
- isar/state_machine/states/stop.py +0 -78
- isar/storage/slimm_storage.py +0 -181
- isar-1.15.0.dist-info/METADATA +0 -417
- isar-1.15.0.dist-info/RECORD +0 -113
- robot_interface/models/initialize/initialize_params.py +0 -9
- robot_interface/models/mission/step.py +0 -211
- {isar-1.15.0.dist-info → isar-1.34.9.dist-info/licenses}/LICENSE +0 -0
- {isar-1.15.0.dist-info → isar-1.34.9.dist-info}/top_level.txt +0 -0
isar/robot/robot.py
ADDED
|
@@ -0,0 +1,377 @@
|
|
|
1
|
+
import logging
|
|
2
|
+
from queue import Queue
|
|
3
|
+
from threading import Event as ThreadEvent
|
|
4
|
+
from threading import Thread
|
|
5
|
+
from typing import Callable, List, Optional, Tuple
|
|
6
|
+
|
|
7
|
+
from isar.config.settings import settings
|
|
8
|
+
from isar.models.events import (
|
|
9
|
+
Event,
|
|
10
|
+
Events,
|
|
11
|
+
RobotServiceEvents,
|
|
12
|
+
SharedState,
|
|
13
|
+
StateMachineEvents,
|
|
14
|
+
)
|
|
15
|
+
from isar.robot.robot_battery import RobotBatteryThread
|
|
16
|
+
from isar.robot.robot_monitor_mission import RobotMonitorMissionThread
|
|
17
|
+
from isar.robot.robot_pause_mission import RobotPauseMissionThread
|
|
18
|
+
from isar.robot.robot_resume_mission import RobotResumeMissionThread
|
|
19
|
+
from isar.robot.robot_start_mission import RobotStartMissionThread
|
|
20
|
+
from isar.robot.robot_status import RobotStatusThread
|
|
21
|
+
from isar.robot.robot_stop_mission import RobotStopMissionThread
|
|
22
|
+
from isar.robot.robot_upload_inspection import RobotUploadInspectionThread
|
|
23
|
+
from isar.services.utilities.mqtt_utilities import publish_mission_status
|
|
24
|
+
from robot_interface.models.exceptions.robot_exceptions import ErrorMessage, ErrorReason
|
|
25
|
+
from robot_interface.models.mission.mission import Mission
|
|
26
|
+
from robot_interface.models.mission.status import MissionStatus
|
|
27
|
+
from robot_interface.models.mission.task import TASKS
|
|
28
|
+
from robot_interface.robot_interface import RobotInterface
|
|
29
|
+
from robot_interface.telemetry.mqtt_client import MqttClientInterface
|
|
30
|
+
|
|
31
|
+
|
|
32
|
+
class Robot(object):
|
|
33
|
+
def __init__(
|
|
34
|
+
self,
|
|
35
|
+
events: Events,
|
|
36
|
+
robot: RobotInterface,
|
|
37
|
+
shared_state: SharedState,
|
|
38
|
+
mqtt_publisher: MqttClientInterface,
|
|
39
|
+
) -> None:
|
|
40
|
+
self.logger = logging.getLogger("robot")
|
|
41
|
+
self.state_machine_events: StateMachineEvents = events.state_machine_events
|
|
42
|
+
self.robot_service_events: RobotServiceEvents = events.robot_service_events
|
|
43
|
+
self.mqtt_publisher: MqttClientInterface = mqtt_publisher
|
|
44
|
+
self.upload_queue: Queue = events.upload_queue
|
|
45
|
+
self.shared_state: SharedState = shared_state
|
|
46
|
+
self.robot: RobotInterface = robot
|
|
47
|
+
self.start_mission_thread: Optional[RobotStartMissionThread] = None
|
|
48
|
+
self.robot_battery_thread: Optional[RobotBatteryThread] = None
|
|
49
|
+
self.robot_status_thread: Optional[RobotStatusThread] = None
|
|
50
|
+
self.monitor_mission_thread: Optional[RobotMonitorMissionThread] = None
|
|
51
|
+
self.stop_mission_thread: Optional[RobotStopMissionThread] = None
|
|
52
|
+
self.pause_mission_thread: Optional[RobotPauseMissionThread] = None
|
|
53
|
+
self.resume_mission_thread: Optional[RobotResumeMissionThread] = None
|
|
54
|
+
self.upload_inspection_threads: List[RobotUploadInspectionThread] = []
|
|
55
|
+
self.signal_thread_quitting: ThreadEvent = ThreadEvent()
|
|
56
|
+
self.signal_mission_stopped: ThreadEvent = ThreadEvent()
|
|
57
|
+
self.inspection_callback_thread: Optional[Thread] = None
|
|
58
|
+
|
|
59
|
+
def stop(self) -> None:
|
|
60
|
+
self.signal_thread_quitting.set()
|
|
61
|
+
if self.robot_status_thread is not None and self.robot_status_thread.is_alive():
|
|
62
|
+
self.robot_status_thread.join()
|
|
63
|
+
if (
|
|
64
|
+
self.robot_battery_thread is not None
|
|
65
|
+
and self.robot_battery_thread.is_alive()
|
|
66
|
+
):
|
|
67
|
+
self.robot_battery_thread.join()
|
|
68
|
+
if (
|
|
69
|
+
self.monitor_mission_thread is not None
|
|
70
|
+
and self.monitor_mission_thread.is_alive()
|
|
71
|
+
):
|
|
72
|
+
self.monitor_mission_thread.join()
|
|
73
|
+
if (
|
|
74
|
+
self.start_mission_thread is not None
|
|
75
|
+
and self.start_mission_thread.is_alive()
|
|
76
|
+
):
|
|
77
|
+
self.start_mission_thread.join()
|
|
78
|
+
if self.stop_mission_thread is not None and self.stop_mission_thread.is_alive():
|
|
79
|
+
self.stop_mission_thread.join()
|
|
80
|
+
for thread in self.upload_inspection_threads:
|
|
81
|
+
if thread.is_alive():
|
|
82
|
+
thread.join()
|
|
83
|
+
self.upload_inspection_threads = []
|
|
84
|
+
self.robot_status_thread = None
|
|
85
|
+
self.robot_battery_thread = None
|
|
86
|
+
self.start_mission_thread = None
|
|
87
|
+
self.monitor_mission_thread = None
|
|
88
|
+
|
|
89
|
+
def _start_mission_done_handler(self) -> None:
|
|
90
|
+
if (
|
|
91
|
+
self.start_mission_thread is not None
|
|
92
|
+
and not self.start_mission_thread.is_alive()
|
|
93
|
+
):
|
|
94
|
+
self.start_mission_thread.join()
|
|
95
|
+
mission = self.start_mission_thread.mission
|
|
96
|
+
error_message = self.start_mission_thread.error_message
|
|
97
|
+
self.start_mission_thread = None
|
|
98
|
+
|
|
99
|
+
if (
|
|
100
|
+
error_message
|
|
101
|
+
and error_message.error_reason == ErrorReason.RobotAlreadyHomeException
|
|
102
|
+
):
|
|
103
|
+
self.robot_service_events.robot_already_home.trigger_event(True)
|
|
104
|
+
return
|
|
105
|
+
elif error_message:
|
|
106
|
+
mission.status = MissionStatus.Failed
|
|
107
|
+
error_message.error_description = (
|
|
108
|
+
f"Failed to initiate due to: {error_message.error_description}"
|
|
109
|
+
)
|
|
110
|
+
mission.error_message = error_message
|
|
111
|
+
publish_mission_status(self.mqtt_publisher, mission)
|
|
112
|
+
self.robot_service_events.mission_failed.trigger_event(error_message)
|
|
113
|
+
return
|
|
114
|
+
else:
|
|
115
|
+
self.robot_service_events.mission_started.trigger_event(True)
|
|
116
|
+
|
|
117
|
+
if (
|
|
118
|
+
self.monitor_mission_thread is not None
|
|
119
|
+
and self.monitor_mission_thread.is_alive()
|
|
120
|
+
):
|
|
121
|
+
self.logger.warning(
|
|
122
|
+
"Attempted to start mission while monitoring an old mission."
|
|
123
|
+
)
|
|
124
|
+
self.monitor_mission_thread.join()
|
|
125
|
+
|
|
126
|
+
self.signal_mission_stopped.clear()
|
|
127
|
+
self.monitor_mission_thread = RobotMonitorMissionThread(
|
|
128
|
+
self.robot_service_events,
|
|
129
|
+
self.shared_state,
|
|
130
|
+
self.robot,
|
|
131
|
+
self.mqtt_publisher,
|
|
132
|
+
self.signal_thread_quitting,
|
|
133
|
+
self.signal_mission_stopped,
|
|
134
|
+
mission,
|
|
135
|
+
)
|
|
136
|
+
self.monitor_mission_thread.start()
|
|
137
|
+
|
|
138
|
+
def _stop_mission_done_handler(self) -> None:
|
|
139
|
+
if (
|
|
140
|
+
self.stop_mission_thread is not None
|
|
141
|
+
and not self.stop_mission_thread.is_alive()
|
|
142
|
+
):
|
|
143
|
+
self.stop_mission_thread.join()
|
|
144
|
+
error_message = self.stop_mission_thread.error_message
|
|
145
|
+
self.stop_mission_thread = None
|
|
146
|
+
|
|
147
|
+
if error_message:
|
|
148
|
+
self.robot_service_events.mission_failed_to_stop.trigger_event(
|
|
149
|
+
error_message
|
|
150
|
+
)
|
|
151
|
+
else:
|
|
152
|
+
self.signal_mission_stopped.set()
|
|
153
|
+
if self.monitor_mission_thread is not None:
|
|
154
|
+
self.monitor_mission_thread.join()
|
|
155
|
+
self.monitor_mission_thread = None
|
|
156
|
+
self.robot_service_events.mission_successfully_stopped.trigger_event(
|
|
157
|
+
True
|
|
158
|
+
)
|
|
159
|
+
|
|
160
|
+
def _pause_mission_done_handler(self) -> None:
|
|
161
|
+
if (
|
|
162
|
+
self.pause_mission_thread is not None
|
|
163
|
+
and not self.pause_mission_thread.is_alive()
|
|
164
|
+
):
|
|
165
|
+
self.pause_mission_thread.join()
|
|
166
|
+
error_message = self.pause_mission_thread.error_message
|
|
167
|
+
self.pause_mission_thread = None
|
|
168
|
+
|
|
169
|
+
if error_message:
|
|
170
|
+
self.robot_service_events.mission_failed_to_pause.trigger_event(
|
|
171
|
+
error_message
|
|
172
|
+
)
|
|
173
|
+
else:
|
|
174
|
+
self.robot_service_events.mission_successfully_paused.trigger_event(
|
|
175
|
+
True
|
|
176
|
+
)
|
|
177
|
+
|
|
178
|
+
def _start_mission_event_handler(self, event: Event[Mission]) -> None:
|
|
179
|
+
start_mission = event.consume_event()
|
|
180
|
+
if start_mission is not None:
|
|
181
|
+
if (
|
|
182
|
+
self.start_mission_thread is not None
|
|
183
|
+
and self.start_mission_thread.is_alive()
|
|
184
|
+
):
|
|
185
|
+
self.logger.warning(
|
|
186
|
+
"Attempted to start mission while another mission was starting."
|
|
187
|
+
)
|
|
188
|
+
self.start_mission_thread.join()
|
|
189
|
+
|
|
190
|
+
self.start_mission_thread = RobotStartMissionThread(
|
|
191
|
+
self.robot,
|
|
192
|
+
self.signal_thread_quitting,
|
|
193
|
+
start_mission,
|
|
194
|
+
)
|
|
195
|
+
self.start_mission_thread.start()
|
|
196
|
+
|
|
197
|
+
def _stop_mission_request_handler(self, event: Event[bool]) -> None:
|
|
198
|
+
if event.has_event():
|
|
199
|
+
if (
|
|
200
|
+
self.stop_mission_thread is not None
|
|
201
|
+
and self.stop_mission_thread.is_alive()
|
|
202
|
+
):
|
|
203
|
+
self.logger.warning(
|
|
204
|
+
"Received stop mission event while trying to stop a mission. Aborting stop attempt."
|
|
205
|
+
)
|
|
206
|
+
return
|
|
207
|
+
if (
|
|
208
|
+
self.start_mission_thread is not None
|
|
209
|
+
and self.start_mission_thread.is_alive()
|
|
210
|
+
):
|
|
211
|
+
return
|
|
212
|
+
event.consume_event()
|
|
213
|
+
self.stop_mission_thread = RobotStopMissionThread(
|
|
214
|
+
self.robot, self.signal_thread_quitting
|
|
215
|
+
)
|
|
216
|
+
self.stop_mission_thread.start()
|
|
217
|
+
|
|
218
|
+
def _pause_mission_request_handler(self, event: Event[bool]) -> None:
|
|
219
|
+
if event.has_event():
|
|
220
|
+
if (
|
|
221
|
+
self.pause_mission_thread is not None
|
|
222
|
+
and self.pause_mission_thread.is_alive()
|
|
223
|
+
):
|
|
224
|
+
self.logger.warning(
|
|
225
|
+
"Received pause mission event while trying to pause a mission. Aborting pause attempt."
|
|
226
|
+
)
|
|
227
|
+
return
|
|
228
|
+
if (
|
|
229
|
+
self.start_mission_thread is not None
|
|
230
|
+
and self.start_mission_thread.is_alive()
|
|
231
|
+
):
|
|
232
|
+
return
|
|
233
|
+
event.consume_event()
|
|
234
|
+
self.pause_mission_thread = RobotPauseMissionThread(
|
|
235
|
+
self.robot, self.signal_thread_quitting
|
|
236
|
+
)
|
|
237
|
+
self.pause_mission_thread.start()
|
|
238
|
+
|
|
239
|
+
def _resume_mission_request_handler(self, event: Event[bool]) -> None:
|
|
240
|
+
if event.consume_event():
|
|
241
|
+
if (
|
|
242
|
+
self.resume_mission_thread is not None
|
|
243
|
+
and self.resume_mission_thread.is_alive()
|
|
244
|
+
):
|
|
245
|
+
self.logger.warning(
|
|
246
|
+
"Received resume mission event while trying to resume a mission. Aborting resume attempt."
|
|
247
|
+
)
|
|
248
|
+
return
|
|
249
|
+
if (
|
|
250
|
+
self.start_mission_thread is not None
|
|
251
|
+
and self.start_mission_thread.is_alive()
|
|
252
|
+
):
|
|
253
|
+
error_description = "Received resume mission event while trying to start a mission. Aborting resume attempt."
|
|
254
|
+
error_message = ErrorMessage(
|
|
255
|
+
error_reason=ErrorReason.RobotStillStartingMissionException,
|
|
256
|
+
error_description=error_description,
|
|
257
|
+
)
|
|
258
|
+
self.robot_service_events.mission_failed_to_resume.trigger_event(
|
|
259
|
+
error_message
|
|
260
|
+
)
|
|
261
|
+
return
|
|
262
|
+
self.resume_mission_thread = RobotResumeMissionThread(
|
|
263
|
+
self.robot, self.signal_thread_quitting
|
|
264
|
+
)
|
|
265
|
+
self.resume_mission_thread.start()
|
|
266
|
+
|
|
267
|
+
def _resume_mission_done_handler(self) -> None:
|
|
268
|
+
if (
|
|
269
|
+
self.resume_mission_thread is not None
|
|
270
|
+
and not self.resume_mission_thread.is_alive()
|
|
271
|
+
):
|
|
272
|
+
self.resume_mission_thread.join()
|
|
273
|
+
error_message = self.resume_mission_thread.error_message
|
|
274
|
+
self.resume_mission_thread = None
|
|
275
|
+
|
|
276
|
+
if error_message:
|
|
277
|
+
self.robot_service_events.mission_failed_to_resume.trigger_event(
|
|
278
|
+
error_message
|
|
279
|
+
)
|
|
280
|
+
else:
|
|
281
|
+
self.robot_service_events.mission_successfully_resumed.trigger_event(
|
|
282
|
+
True
|
|
283
|
+
)
|
|
284
|
+
|
|
285
|
+
def _upload_inspection_event_handler(
|
|
286
|
+
self, event: Event[Tuple[TASKS, Mission]]
|
|
287
|
+
) -> None:
|
|
288
|
+
upload_request = event.consume_event()
|
|
289
|
+
if upload_request:
|
|
290
|
+
|
|
291
|
+
upload_inspection_thread = RobotUploadInspectionThread(
|
|
292
|
+
self.upload_queue, self.robot, upload_request[0], upload_request[1]
|
|
293
|
+
)
|
|
294
|
+
self.upload_inspection_threads.append(upload_inspection_thread)
|
|
295
|
+
upload_inspection_thread.start()
|
|
296
|
+
|
|
297
|
+
def _upload_inspection_done_handler(self):
|
|
298
|
+
if len(self.upload_inspection_threads) > 0:
|
|
299
|
+
|
|
300
|
+
def _join_threads(thread: RobotUploadInspectionThread) -> bool:
|
|
301
|
+
if not thread.is_alive():
|
|
302
|
+
thread.join()
|
|
303
|
+
return True
|
|
304
|
+
return False
|
|
305
|
+
|
|
306
|
+
self.upload_inspection_threads[:] = [
|
|
307
|
+
thread
|
|
308
|
+
for thread in self.upload_inspection_threads
|
|
309
|
+
if _join_threads(thread)
|
|
310
|
+
]
|
|
311
|
+
|
|
312
|
+
def register_and_monitor_inspection_callback(
|
|
313
|
+
self,
|
|
314
|
+
callback_function: Callable,
|
|
315
|
+
) -> None:
|
|
316
|
+
self.inspection_callback_function = callback_function
|
|
317
|
+
|
|
318
|
+
self.inspection_callback_thread = self.robot.register_inspection_callback(
|
|
319
|
+
callback_function
|
|
320
|
+
)
|
|
321
|
+
if self.inspection_callback_thread is not None:
|
|
322
|
+
self.inspection_callback_thread.start()
|
|
323
|
+
self.logger.info("Inspection callback thread started and will be monitored")
|
|
324
|
+
|
|
325
|
+
def _monitor_inspection_callback_thread(self) -> None:
|
|
326
|
+
if (
|
|
327
|
+
self.inspection_callback_thread is not None
|
|
328
|
+
and not self.inspection_callback_thread.is_alive()
|
|
329
|
+
):
|
|
330
|
+
self.logger.warning("Inspection callback thread died - restarting")
|
|
331
|
+
self.inspection_callback_thread.join()
|
|
332
|
+
self.inspection_callback_thread.start()
|
|
333
|
+
|
|
334
|
+
def run(self) -> None:
|
|
335
|
+
self.robot_status_thread = RobotStatusThread(
|
|
336
|
+
robot=self.robot,
|
|
337
|
+
signal_thread_quitting=self.signal_thread_quitting,
|
|
338
|
+
shared_state=self.shared_state,
|
|
339
|
+
state_machine_events=self.state_machine_events,
|
|
340
|
+
robot_service_events=self.robot_service_events,
|
|
341
|
+
)
|
|
342
|
+
self.robot_status_thread.start()
|
|
343
|
+
|
|
344
|
+
self.robot_battery_thread = RobotBatteryThread(
|
|
345
|
+
self.robot, self.signal_thread_quitting, self.shared_state
|
|
346
|
+
)
|
|
347
|
+
self.robot_battery_thread.start()
|
|
348
|
+
|
|
349
|
+
while not self.signal_thread_quitting.wait(0):
|
|
350
|
+
self._start_mission_event_handler(self.state_machine_events.start_mission)
|
|
351
|
+
|
|
352
|
+
self._pause_mission_request_handler(self.state_machine_events.pause_mission)
|
|
353
|
+
|
|
354
|
+
self._resume_mission_request_handler(
|
|
355
|
+
self.state_machine_events.resume_mission
|
|
356
|
+
)
|
|
357
|
+
|
|
358
|
+
self._stop_mission_request_handler(self.state_machine_events.stop_mission)
|
|
359
|
+
|
|
360
|
+
self._upload_inspection_event_handler(
|
|
361
|
+
self.robot_service_events.request_inspection_upload
|
|
362
|
+
)
|
|
363
|
+
|
|
364
|
+
self._start_mission_done_handler()
|
|
365
|
+
|
|
366
|
+
self._stop_mission_done_handler()
|
|
367
|
+
|
|
368
|
+
self._pause_mission_done_handler()
|
|
369
|
+
|
|
370
|
+
self._upload_inspection_done_handler()
|
|
371
|
+
|
|
372
|
+
self._resume_mission_done_handler()
|
|
373
|
+
|
|
374
|
+
if settings.UPLOAD_INSPECTIONS_ASYNC:
|
|
375
|
+
self._monitor_inspection_callback_thread()
|
|
376
|
+
|
|
377
|
+
self.logger.info("Exiting robot service main thread")
|
|
@@ -0,0 +1,60 @@
|
|
|
1
|
+
import logging
|
|
2
|
+
import time
|
|
3
|
+
from threading import Event, Thread
|
|
4
|
+
|
|
5
|
+
from isar.config.settings import settings
|
|
6
|
+
from isar.models.events import SharedState
|
|
7
|
+
from robot_interface.models.exceptions.robot_exceptions import RobotException
|
|
8
|
+
from robot_interface.robot_interface import RobotInterface
|
|
9
|
+
|
|
10
|
+
|
|
11
|
+
class RobotBatteryThread(Thread):
|
|
12
|
+
def __init__(
|
|
13
|
+
self,
|
|
14
|
+
robot: RobotInterface,
|
|
15
|
+
signal_thread_quitting: Event,
|
|
16
|
+
shared_state: SharedState,
|
|
17
|
+
):
|
|
18
|
+
self.logger = logging.getLogger("robot")
|
|
19
|
+
self.shared_state: SharedState = shared_state
|
|
20
|
+
self.robot: RobotInterface = robot
|
|
21
|
+
self.signal_thread_quitting: Event = signal_thread_quitting
|
|
22
|
+
self.last_robot_battery_poll_time: float = time.time()
|
|
23
|
+
self.force_battery_poll_next_iteration: bool = True
|
|
24
|
+
Thread.__init__(self, name="Robot battery thread")
|
|
25
|
+
|
|
26
|
+
def stop(self) -> None:
|
|
27
|
+
return
|
|
28
|
+
|
|
29
|
+
def _is_ready_to_poll_for_battery(self) -> bool:
|
|
30
|
+
if self.force_battery_poll_next_iteration:
|
|
31
|
+
self.force_battery_poll_next_iteration = False
|
|
32
|
+
return True
|
|
33
|
+
|
|
34
|
+
time_since_last_robot_battery_poll = (
|
|
35
|
+
time.time() - self.last_robot_battery_poll_time
|
|
36
|
+
)
|
|
37
|
+
return (
|
|
38
|
+
time_since_last_robot_battery_poll
|
|
39
|
+
> settings.ROBOT_API_BATTERY_POLL_INTERVAL
|
|
40
|
+
)
|
|
41
|
+
|
|
42
|
+
def run(self):
|
|
43
|
+
if self.signal_thread_quitting.is_set():
|
|
44
|
+
return
|
|
45
|
+
|
|
46
|
+
thread_check_interval = settings.THREAD_CHECK_INTERVAL
|
|
47
|
+
|
|
48
|
+
while not self.signal_thread_quitting.wait(thread_check_interval):
|
|
49
|
+
if not self._is_ready_to_poll_for_battery():
|
|
50
|
+
continue
|
|
51
|
+
try:
|
|
52
|
+
self.last_robot_battery_poll_time = time.time()
|
|
53
|
+
|
|
54
|
+
robot_battery_level = self.robot.get_battery_level()
|
|
55
|
+
|
|
56
|
+
self.shared_state.robot_battery_level.update(robot_battery_level)
|
|
57
|
+
except RobotException as e:
|
|
58
|
+
self.logger.error(f"Failed to retrieve robot battery level: {e}")
|
|
59
|
+
continue
|
|
60
|
+
self.logger.info("Exiting robot battery thread")
|