def _handle_establish_bond(self, req): rospy.loginfo("Request to establish a bond") bond_id = str(uuid.uuid1()) def on_formed(): rospy.loginfo("Bond formed with bond_id of '{0}'" .format(bond_id)) def on_broken(): # if bond_id in self.__bonds: rospy.loginfo("Bond with bond id '{0}' was broken, freeing associated capabilities" .format(bond_id)) self.__free_capabilities_by_bond_id(bond_id) del self.__bonds[bond_id] self.__bonds[bond_id] = Bond(self.__bond_topic, bond_id, on_broken=on_broken, on_formed=on_formed) self.__bonds[bond_id].start() return EstablishBondResponse(bond_id)
def establish_bond(self, timeout=None): """Establishes a bond using the ``~establish_bond`` service call The bond id which is returned by the service call is stored internally and used implicitly by the use/free capabilities functions. If :py:meth:`establish_bond` had previously been called, then the old bond will be broken, which will result in any capability uses under that bond to be implicitly freed. This function is called implicitly by :py:meth:`use_capability` if no bond exists. This function will block waiting for the service call to become available and to wait for the bond to be established. In both cases the timeout parameter is used. None is returned if the timeout occurs while waiting on the service to become available or while waiting for the bond to form. :param timeout: time in seconds to wait for the service to be available :type timeout: float :returns: the bond_id received from the server or :py:obj:`None` on failure :rtype: :py:obj:`str` """ if self.__wait_for_service(self.__establish_bond, timeout) is False: return None resp = self.__establish_bond() if not resp.bond_id: # pragma: no cover return None self._bond_id = resp.bond_id self._bond = Bond('{0}/bonds'.format(self._name), self._bond_id) self._bond.start() timeout_dur = None if timeout is None else rospy.Duration.from_sec( timeout) if self._bond.wait_until_formed( timeout_dur) is False: # pragma: no cover return None return self._bond_id