naoqi_node.py
Go to the documentation of this file.
1 # Copyright 2009-2011 Armin Hornung, University of Freiburg
2 # http://www.ros.org/wiki/nao
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions are met:
6 #
7 # # Redistributions of source code must retain the above copyright
8 # notice, this list of conditions and the following disclaimer.
9 # # Redistributions in binary form must reproduce the above copyright
10 # notice, this list of conditions and the following disclaimer in the
11 # documentation and/or other materials provided with the distribution.
12 # # Neither the name of the University of Freiburg nor the names of its
13 # contributors may be used to endorse or promote products derived from
14 # this software without specific prior written permission.
15 #
16 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 # POSSIBILITY OF SUCH DAMAGE.
27 #
28 
29 from threading import Thread
30 
31 import rospy
32 
33 # import Aldebaran API (must be in PYTHONPATH):
34 try:
35  from naoqi import ALProxy
36 except ImportError:
37  raise RuntimeError("Error importing NaoQI. Please make sure that Aldebaran's NaoQI API is in your PYTHONPATH.")
38 
39 class NaoqiNode(Thread):
40  """
41  A ROS Node wrapper that can help you connect to NAOqi and deal with ROS shutdown
42  To start your node, just call:
43  my_node = MyNode('my_node')
44  my_node.start() # that will spawn your node in a thread (and run whatever is in the run() function
45  rospy.spin()
46  # when killing ROS, the node will automatically stop its main loop, exit, and then unsubscribe from ALMemory events
47  # and call whatever you have in unsubscribe()
48  Then, if your node needs to process data, you just needs to have a run function:
49 
50  def run(Self):
51  #do some initialization
52  while self.is_looping():
53  # do something
54  # do some post processing
55  """
56  def __init__(self, name):
57  """
58  :param name: the name of the ROS node
59  """
60  super(NaoqiNode, self).__init__()
61 
62  # A distutils.version.LooseVersion that contains the current verssion of NAOqi we're connected to
63  self.__naoqi_version = None
64  self.__name = name
65 
66  ## NAOqi stuff
67  # dict from a modulename to a proxy
68  self.__proxies = {}
69 
70  # Initialize ros, before getting parameters.
71  rospy.init_node(self.__name)
72 
73  # If user has set parameters for ip and port use them as default
74  default_ip = rospy.get_param("~pip", "127.0.0.1")
75  default_port = rospy.get_param("~pport", 9559)
76 
77  # get connection from command line:
78  from argparse import ArgumentParser
79  parser = ArgumentParser()
80  parser.add_argument("--pip", dest="pip", default=default_ip,
81  help="IP/hostname of parent broker. Default is 127.0.0.1.", metavar="IP")
82  parser.add_argument("--pport", dest="pport", default=default_port, type=int,
83  help="port of parent broker. Default is 9559.", metavar="PORT")
84 
85  import sys
86  args, unknown = parser.parse_known_args(args=rospy.myargv(argv=sys.argv)[1:])
87  self.pip = args.pip
88  self.pport = args.pport
89 
90  ## ROS stuff
91  self.__stop_thread = False
92  # make sure that we unregister from everything when the module dies
93  rospy.on_shutdown(self.__on_ros_shutdown)
94 
95  def __on_ros_shutdown(self):
96  """
97  Callback function called whenever rospy.spin() stops
98  """
99  rospy.loginfo('Stopping ' + self.__name)
100 
101  self.__stop_thread = True
102  # wait for the thread to be done
103  if self.is_alive():
104  self.join()
105 
106  rospy.loginfo(self.__name + ' stopped')
107 
108  def run(self):
109  """
110  This is a virtual method that corresponds to the code of the Node that runs continuously
111  It should have a while loop calling the self.is_looping() function
112  """
113  """
114  # code example
115  #do some initialization
116  while self.is_looping():
117  # do something
118  # do some post processing
119  """
120  raise NotImplementedError('Implement the run function of your NaoNode !')
121 
122  def is_looping(self):
123  """
124  :return: whether the thread is supposed to be running
125  """
126  return not self.__stop_thread
127 
128  def get_proxy(self, name, warn=True):
129  """
130  Returns a proxy to a specific module. If it has not been created yet, it is created
131  :param name: the name of the module to create a proxy for
132  :return: a proxy to the corresponding module
133  """
134  if name in self.__proxies and self.__proxies[name] is not None:
135  return self.__proxies[name]
136 
137  proxy = None
138  try:
139  proxy = ALProxy(name,self.pip,self.pport)
140  except RuntimeError,e:
141  if warn:
142  rospy.logerr("Could not create Proxy to \"%s\". \nException message:\n%s",name, e)
143 
144  self.__proxies[name] = proxy
145  return proxy
146 
147  def get_version(self):
148  """
149  Returns the NAOqi version.
150  A proxy for ALMemory is automatically created if needed as self.memProxy.
151  You can then simply have code that runs or not depending on the NAOqi version.
152  E.g. if distutils.version.LooseVersion('1.6') < get_version() ....
153  :return: a distutils.version.LooseVersion object with the NAOqi version
154  """
155  if self.__naoqi_version is None:
156  proxy = self.get_proxy('ALMemory')
157  if proxy is None:
158  # exiting is bad but it should not happen
159  # except maybe with NAOqi versions < 1.6 or future ones
160  # in which case we will adapt that code to call the proper
161  # version function
162  exit(1)
163 
164  from distutils.version import LooseVersion
165  self.__naoqi_version = LooseVersion(proxy.version())
166 
167  return self.__naoqi_version
__proxies
NAOqi stuff dict from a modulename to a proxy.
Definition: naoqi_node.py:68
def get_proxy(self, name, warn=True)
Definition: naoqi_node.py:128


naoqi_driver_py
Author(s): Armin Hornung, Armin Hornung, Stefan Osswald, Daniel Maier, Miguel Sarabia, Severin Lemaignan
autogenerated on Thu Jul 16 2020 03:18:30