def test_qos_profile_only_constructor(self): test_qos_profile = QoSProfile( **_rclpy.rclpy_get_rmw_qos_profile('qos_profile_default')) info_for_ref = TopicEndpointInfo() info_for_ref.qos_profile = test_qos_profile info_from_ctor = TopicEndpointInfo(qos_profile=test_qos_profile) self.assertEqual(info_for_ref, info_from_ctor) self.assertEqual(test_qos_profile, info_from_ctor.qos_profile)
RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT = 0 RMW_QOS_POLICY_RELIABILITY_RELIABLE = 1 RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT = 2 class QoSDurabilityPolicy(IntEnum): """ Enum for QoS Durability settings. This enum matches the one defined in rmw/types.h """ RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT = 0 RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL = 1 RMW_QOS_POLICY_DURABILITY_VOLATILE = 2 qos_profile_default = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_default') qos_profile_system_default = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_system_default') qos_profile_sensor_data = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_sensor_data') qos_profile_services_default = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_services_default') qos_profile_parameters = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_parameters') qos_profile_parameter_events = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_parameter_events')
class QoSProfile: """Define Quality of Service policies.""" # default QoS profile not exposed to the user to encourage them to think about QoS settings __qos_profile_default_dict = _rclpy.rclpy_get_rmw_qos_profile( 'qos_profile_default') __slots__ = [ '_history', '_depth', '_reliability', '_durability', '_lifespan', '_deadline', '_liveliness', '_liveliness_lease_duration', '_avoid_ros_namespace_conventions', ] def __init__(self, **kwargs): assert all('_' + key in self.__slots__ for key in kwargs.keys()), \ 'Invalid arguments passed to constructor: %r' % kwargs.keys() if 'history' not in kwargs: if 'depth' not in kwargs: raise InvalidQoSProfileException( 'History and/or depth settings are required.') kwargs[ 'history'] = QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST self.history = kwargs.get('history') if (QoSHistoryPolicy.RMW_QOS_POLICY_HISTORY_KEEP_LAST == self.history and 'depth' not in kwargs): raise InvalidQoSProfileException( 'History set to KEEP_LAST without a depth setting.') self.depth = kwargs.get('depth', QoSProfile.__qos_profile_default_dict['depth']) self.reliability = kwargs.get( 'reliability', QoSProfile.__qos_profile_default_dict['reliability']) self.durability = kwargs.get( 'durability', QoSProfile.__qos_profile_default_dict['durability']) self.lifespan = kwargs.get( 'lifespan', QoSProfile.__qos_profile_default_dict['lifespan']) self.deadline = kwargs.get( 'deadline', QoSProfile.__qos_profile_default_dict['deadline']) self.liveliness = kwargs.get( 'liveliness', QoSProfile.__qos_profile_default_dict['liveliness']) self.liveliness_lease_duration = kwargs.get( 'liveliness_lease_duration', QoSProfile.__qos_profile_default_dict['liveliness_lease_duration']) self.avoid_ros_namespace_conventions = kwargs.get( 'avoid_ros_namespace_conventions', QoSProfile. __qos_profile_default_dict['avoid_ros_namespace_conventions']) @property def history(self): """ Get field 'history'. :returns: history attribute :rtype: QoSHistoryPolicy """ return self._history @history.setter def history(self, value): assert isinstance(value, QoSHistoryPolicy) or isinstance(value, int) self._history = QoSHistoryPolicy(value) @property def reliability(self): """ Get field 'reliability'. :returns: reliability attribute :rtype: QoSReliabilityPolicy """ return self._reliability @reliability.setter def reliability(self, value): assert isinstance(value, QoSReliabilityPolicy) or isinstance( value, int) self._reliability = QoSReliabilityPolicy(value) @property def durability(self): """ Get field 'durability'. :returns: durability attribute :rtype: QoSDurabilityPolicy """ return self._durability @durability.setter def durability(self, value): assert isinstance(value, QoSDurabilityPolicy) or isinstance(value, int) self._durability = QoSDurabilityPolicy(value) @property def depth(self): """ Get field 'depth'. :returns: depth attribute :rtype: int """ return self._depth @depth.setter def depth(self, value): assert isinstance(value, int) self._depth = value @property def lifespan(self): """ Get field 'lifespan'. :returns: lifespan attribute :rtype: Duration """ return self._lifespan @lifespan.setter def lifespan(self, value): assert isinstance(value, Duration) self._lifespan = value @property def deadline(self): """ Get field 'deadline'. :returns: deadline attribute. :rtype: Duration """ return self._deadline @deadline.setter def deadline(self, value): assert isinstance(value, Duration) self._deadline = value @property def liveliness(self): """ Get field 'liveliness'. :returns: liveliness attribute :rtype: QoSLivelinessPolicy """ return self._liveliness @liveliness.setter def liveliness(self, value): assert isinstance(value, (QoSLivelinessPolicy, int)) self._liveliness = QoSLivelinessPolicy(value) @property def liveliness_lease_duration(self): """ Get field 'liveliness_lease_duration'. :returns: liveliness_lease_duration attribute. :rtype: Duration """ return self._liveliness_lease_duration @liveliness_lease_duration.setter def liveliness_lease_duration(self, value): assert isinstance(value, Duration) self._liveliness_lease_duration = value @property def avoid_ros_namespace_conventions(self): """ Get field 'avoid_ros_namespace_conventions'. :returns: avoid_ros_namespace_conventions attribute :rtype: bool """ return self._avoid_ros_namespace_conventions @avoid_ros_namespace_conventions.setter def avoid_ros_namespace_conventions(self, value): assert isinstance(value, bool) self._avoid_ros_namespace_conventions = value def get_c_qos_profile(self): return _rclpy.rclpy_convert_from_py_qos_policy( self.history, self.depth, self.reliability, self.durability, self.lifespan.get_c_duration(), self.deadline.get_c_duration(), self.liveliness, self.liveliness_lease_duration.get_c_duration(), self.avoid_ros_namespace_conventions, ) def __eq__(self, other): if not isinstance(other, QoSProfile): return False return all( self.__getattribute__(slot) == other.__getattribute__(slot) for slot in self.__slots__)
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT = 0 SYSTEM_DEFAULT = RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT RMW_QOS_POLICY_LIVELINESS_AUTOMATIC = 1 AUTOMATIC = RMW_QOS_POLICY_LIVELINESS_AUTOMATIC RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC = 3 MANUAL_BY_TOPIC = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC RMW_QOS_POLICY_LIVELINESS_UNKNOWN = 4 UNKNOWN = RMW_QOS_POLICY_LIVELINESS_UNKNOWN # Alias with the old name, for retrocompatibility QoSLivelinessPolicy = LivelinessPolicy qos_profile_unknown = QoSProfile( **_rclpy.rclpy_get_rmw_qos_profile('qos_profile_unknown')) qos_profile_system_default = QoSProfile( **_rclpy.rclpy_get_rmw_qos_profile('qos_profile_system_default')) qos_profile_sensor_data = QoSProfile( **_rclpy.rclpy_get_rmw_qos_profile('qos_profile_sensor_data')) qos_profile_services_default = QoSProfile( **_rclpy.rclpy_get_rmw_qos_profile('qos_profile_services_default')) qos_profile_parameters = QoSProfile( **_rclpy.rclpy_get_rmw_qos_profile('qos_profile_parameters')) qos_profile_parameter_events = QoSProfile( **_rclpy.rclpy_get_rmw_qos_profile('qos_profile_parameter_events')) qos_profile_action_status_default = QoSProfile( **_rclpy_action.rclpy_action_get_rmw_qos_profile( 'rcl_action_qos_profile_status_default'))