mycroft_skills.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 import rospy
3 import actionlib
4 from std_msgs.msg import String, Bool
5 from mycroft_ros.msg import Mycroft, IntentResponse, IntentResponseEntity as Entity, GetResponseAction, GetResponseResult
6 from mycroft_ros.srv import MycroftSkill as MycroftService, MycroftSkillResponse, MycroftSkillRequest
7 
8 import time
9 import re
10 from threading import Timer
11 import mycroft.lock
12 import pathlib
13 from os.path import basename
14 from mycroft import dialog
15 from mycroft.api import is_paired, BackendDown
16 from mycroft.enclosure.api import EnclosureAPI
17 from mycroft.configuration import Configuration
18 from mycroft.messagebus.client.ws import WebsocketClient
19 from mycroft.messagebus.message import Message
20 from mycroft.util import (
21  connected, wait_while_speaking, reset_sigint_handler,
22  create_echo_function, create_daemon, wait_for_exit_signal
23 )
24 from mycroft.util.log import LOG
25 from mycroft.util.lang import set_active_lang
26 from mycroft.skills.skill_manager import SkillManager, MsmException
27 from mycroft.skills.core import FallbackSkill, MycroftSkill
28 from mycroft.skills.event_scheduler import EventScheduler
29 from mycroft.skills.intent_service import IntentService
30 from mycroft.skills.padatious_service import PadatiousService
31 from adapt.intent import Intent, IntentBuilder
32 
33 bus = None # Mycroft messagebus reference, see "mycroft.messagebus"
34 event_scheduler = None
35 skill_manager = None
36 topic_name = "checking"
37 connect_to_mycroft_backend = True
38 get_response_server = None
39 ask_yesno_server = None
40 
41 # Remember "now" at startup. Used to detect clock changes.
42 start_ticks = time.monotonic()
43 start_clock = time.time()
44 
46  bus = None
47  manager = None
48  result = GetResponseResult()
49 
50  def __init__(self, manager):
51  self.manager = manager
52  self.server = actionlib.SimpleActionServer('get_response', GetResponseAction, self.execute, False)
53  self.server.start()
54 
55  def execute(self, goal):
56  global skill_manager
57  skill_path = goal.skill_path
58  #skill = skill_manager.loaded_skills.get(skill_path, {})
59  skill = self.manager.loaded_skills.get(skill_path, {})
60  self.result.response = skill["instance"].get_response(dialog=goal.dialog)
61  self.server.set_succeeded(self.result)
62 
64  bus = None
65  manager = None
66  result = GetResponseResult()
67 
68  def __init__(self, manager):
69  self.manager = manager
70  self.server = actionlib.SimpleActionServer('ask_yesno', GetResponseAction, self.execute, False)
71  self.server.start()
72 
73  def execute(self, goal):
74  skill_path = goal.skill_path
75  skill = self.manager.loaded_skills.get(skill_path, {})
76  self.result.response = skill["instance"].ask_yesno(prompt=goal.dialog)
77  self.server.set_succeeded(self.result)
78 
80  global bus, skill_manager
81  skill_path = data.skill_path
82  skill = skill_manager.loaded_skills.get(skill_path, {})
83  print(data.dialog)
84  if skill["instance"] is not None:
85  text = skill["instance"].get_response(dialog=data.dialog)
86  if text is not None:
87  print(text)
88  else:
89  print("was none")
90 
91 def connect():
92  global bus
93  bus.run_forever()
94 
96  """
97  Start loading skills.
98  Starts
99  - SkillManager to load/reloading of skills when needed
100  - a timer to check for internet connection
101  - adapt intent service
102  - padatious intent service
103  """
104  global bus, skill_manager, event_scheduler, connect_to_mycroft_backend
105 
106  bus.on('intent_failure', FallbackSkill.make_intent_failure_handler(bus))
107 
108  # Create the Intent manager, which converts utterances to intents
109  # This is the heart of the voice invoked skill system
110  service = IntentService(bus)
111  try:
112  PadatiousService(bus, service)
113  except Exception as e:
114  LOG.exception('Failed to create padatious handlers '
115  '({})'.format(repr(e)))
116  event_scheduler = EventScheduler(bus)
117 
118  # Create a thread that monitors the loaded skills, looking for updates
119  try:
120  skill_manager = SkillManager(bus)
121  except MsmException:
122  # skill manager couldn't be created, wait for network connection and
123  # retry
124  LOG.info('Msm is uninitialized and requires network connection',
125  'to fetch skill information\n'
126  'Waiting for network connection...')
127  while not connected():
128  time.sleep(30)
129  skill_manager = SkillManager(bus)
130 
131  skill_manager.daemon = True
132  # Wait until priority skills have been loaded before checking
133  # network connection
134  # print(skill_manager.msm.repo.get_default_skill_names())
135  skill_manager.load_priority()
136  skill_manager.start()
137  bus.emit(Message('skill.manager.initialised'))
138  if connect_to_mycroft_backend:
140  else:
142 
143 def shutdown():
144  if event_scheduler:
145  event_scheduler.shutdown()
146 
147  # Terminate all running threads that update skills
148  if skill_manager:
149  skill_manager.stop()
150  skill_manager.join()
151 
152 def try_update_system(platform):
153  bus.emit(Message('system.update'))
154  msg = Message('system.update', {
155  'paired': is_paired(),
156  'platform': platform
157  })
158  resp = bus.wait_for_response(msg, 'system.update.processing')
159 
160  if resp and (resp.data or {}).get('processing', True):
161  bus.wait_for_response(Message('system.update.waiting'),
162  'system.update.complete', 1000)
163 
165  if connected():
166  bus.emit(Message('mycroft.internet.connected'))
167 
169  global bus
170  bus.emit(Message("recognizer_loop:utterance", {'utterances': [data.data], 'lang': "en-us"}))
171 
172 def register_intents(instance, skill_topic, intent_files=None, entities=None, intents=None):
173  pub = rospy.Publisher(skill_topic, IntentResponse, queue_size=10)
174  if intent_files:
175  for intent_file in intent_files:
176  instance.register_intent_file(intent_file, lambda m : pub.publish(IntentResponse(m.type, m.data['utterance'], [Entity(entity, value) for entity, value in m.data.items() if entity != 'utterance'])))
177  if intents:
178  for intent in intents:
179  instance.register_intent(Intent(name=intent.name, requires=[(req.entity, req.attribute_name) if req.attribute_name != '' else (req.entity, req.entity) for req in intent.requires], at_least_one=intent.at_least_one, optional=[(opt.entity, opt.attribute_name) if opt.attribute_name != '' else (opt.entity, opt.entity) for opt in intent.optional]), lambda m : pub.publish(IntentResponse(m.data['intent_type'], m.data['utterance'], [Entity(entity, value) for entity, value in m.data.items() if entity not in ('intent_type', 'target', 'confidence', '__tags__', 'utterance')])))
180  if entities:
181  for entity in entities:
182  instance.register_entity_file(entity)
183 
185  """
186  Removes the skill using its path.
187  Arguements:
188  data (String): Skill directory path
189  """
190  global bus, skill_manager
191  skill_path = data.data
192  skill = skill_manager.loaded_skills.get(skill_path, {})
193  # set is_ros_node to False to let the SkillManager handle skill removal
194  skill["is_ros_node"] = False
195 
197  """ Create new MycroftSkill for ROS node and load into SkillManager
198 
199  Arguements:
200  data: mycroft/register_skill service payload containing MycroftSkill srv
201 
202  """
203  global bus, skill_manager
204  mycroft_skill = data.skill
205  skill_path = mycroft_skill.path.rstrip('/')
206  skill_id = basename(skill_path)
207  skill = skill_manager.loaded_skills.setdefault(skill_path, {})
208  skill.update({"id": skill_id, "path": skill_path})
209  skill["loaded"] = True
210  skill["is_ros_node"] = True
211  instance = MycroftSkill(name=skill_id)
212  instance.skill_id = skill_id
213  instance.bind(bus)
214  try:
215  instance.load_data_files(skill_path)
216  skill_topic = 'mycroft/' + skill_id
217  register_intents(instance=instance, intents=mycroft_skill.intents, skill_topic=skill_topic, intent_files=mycroft_skill.intent_files, entities=mycroft_skill.entities)
218  instance.initialize()
219  except Exception as e:
220  instance.default_shutdown()
221  raise e
222  skill["instance"] = instance
223  modified = 0
224  if skill['instance'] is not None:
225  bus.emit(Message('mycroft.skills.loaded', {'path': skill_path, 'id': skill['id'], 'name': skill['instance'].name, 'modified': modified}))
226  return MycroftSkillResponse(True)
227  else:
228  bus.emit(Message('mycroft.skills.loading_failure', {'path': skill_path, 'id': skill['id']}))
229  return MycroftSkillResponse(False)
230 
232  """
233  Check for network connection. If not paired trigger pairing.
234  Runs as a Timer every second until connection is detected.
235  """
236  if connected():
237  enclosure = EnclosureAPI(bus)
238 
239  if is_paired():
240  # Skip the sync message when unpaired because the prompt to go to
241  # home.mycrof.ai will be displayed by the pairing skill
242  enclosure.mouth_text(dialog.get("message_synching.clock"))
243 
244  # Force a sync of the local clock with the internet
245  config = Configuration.get()
246  platform = config['enclosure'].get("platform", "unknown")
247  if platform in ['mycroft_mark_1', 'picroft']:
248  bus.wait_for_response(Message('system.ntp.sync'),
249  'system.ntp.sync.complete', 15)
250 
251  if not is_paired():
252  try_update_system(platform)
253 
254  # Check if the time skewed significantly. If so, reboot
255  skew = abs((time.monotonic() - start_ticks) -
256  (time.time() - start_clock))
257  if skew > 60 * 60:
258  # Time moved by over an hour in the NTP sync. Force a reboot to
259  # prevent weird things from occcurring due to the 'time warp'.
260  #
261  data = {'utterance': dialog.get("time.changed.reboot")}
262  bus.emit(Message("speak", data))
264 
265  # provide visual indicators of the reboot
266  enclosure.mouth_text(dialog.get("message_rebooting"))
267  enclosure.eyes_color(70, 65, 69) # soft gray
268  enclosure.eyes_spin()
269 
270  # give the system time to finish processing enclosure messages
271  time.sleep(1.0)
272 
273  # reboot
274  bus.emit(Message("system.reboot"))
275  return
276  else:
277  bus.emit(Message("enclosure.mouth.reset"))
278  time.sleep(0.5)
279 
280  enclosure.eyes_color(189, 183, 107) # dark khaki
281  enclosure.mouth_text(dialog.get("message_loading.skills"))
282 
283  bus.emit(Message('mycroft.internet.connected'))
284  # check for pairing, if not automatically start pairing
285  try:
286  if not is_paired(ignore_errors=False):
287  payload = {
288  'utterances': ["pair my device"],
289  'lang': "en-us"
290  }
291  bus.emit(Message("recognizer_loop:utterance", payload))
292  else:
293  from mycroft.api import DeviceApi
294  api = DeviceApi()
295  api.update_version()
296  except BackendDown:
297  data = {'utterance': dialog.get("backend.down")}
298  bus.emit(Message("speak", data))
299  bus.emit(Message("backend.down"))
300 
301  else:
302  thread = Timer(1, check_connection)
303  thread.daemon = True
304  thread.start()
305 
306 def check_working(message):
307  if message is not None:
308  print('do somethingggg')
309  print(message.data)
310  else:
311  print('do something else')
312 
314  global skill_manager
315  get_response_server = GetResponseServer(manager=skill_manager)
316  ask_yesno_server = AskYesNoServer(manager=skill_manager)
317 
318 def listener():
319  rospy.init_node('mycroft_skills')
320  rospy.loginfo(rospy.get_caller_id() + " started")
321  rospy.Subscriber("mycroft/utterance", String, handle_utterance)
322  rospy.Subscriber("mycroft/remove_skill", String, handle_remove_skill)
323  s = rospy.Service('mycroft/register_skill', MycroftService, handle_register_skill)
324 
325  global bus
327  # Create PID file, prevent multiple instancesof this service
328  mycroft.lock.Lock('skills')
329  # Connect this Skill management process to the Mycroft Messagebus
330  bus = WebsocketClient()
331  Configuration.init(bus)
332  config = Configuration.get()
333  # Set the active lang to match the configured one
334  set_active_lang(config.get('lang', 'en-us'))
335 
336  bus.on('skill.manager.initialised', initialise_response_server)
337  bus.on('message', create_echo_function('SKILLS'))
338  # Startup will be called after the connection with the Messagebus is done
339  bus.once('open', _starting_up)
340  bus.on('skill.converse.request', check_working)
341 
342  create_daemon(bus.run_forever)
344  shutdown()
345 
346  rospy.spin()
347 
348 if __name__ == '__main__':
349  listener()
def create_daemon(target, args=(), kwargs=None)
def register_intents(instance, skill_topic, intent_files=None, entities=None, intents=None)
def check_working(message)
def is_paired(ignore_errors=True)
def handle_register_skill(data)
def handle_utterance(data)
def create_echo_function(name, whitelist=None)
def check_connection_without_backend()
def try_update_system(platform)
def handle_remove_skill(data)
def initialise_response_server(message)
def get_response(skill_path, dialog, client=None)
Definition: helpers.py:86
def __init__(self, manager)
def get(phrase, lang=None, context=None)
MycroftSkill base class.
Definition: core.py:483
def ask_yesno(skill_path, dialog, client=None)
Definition: helpers.py:97
def handle_get_response(data)


mycroft_ros
Author(s):
autogenerated on Mon Apr 26 2021 02:35:40