Skip to content

Commit

Permalink
decorator should not be callable. (#1050) (#1051)
Browse files Browse the repository at this point in the history
#1047

Signed-off-by: Tomoya Fujita <[email protected]>

Signed-off-by: Tomoya Fujita <[email protected]>
(cherry picked from commit 2da35a4)

Co-authored-by: Tomoya Fujita <[email protected]>
  • Loading branch information
mergify[bot] and fujitatomoya authored Dec 22, 2022
1 parent d7346f5 commit 6b6617a
Show file tree
Hide file tree
Showing 2 changed files with 37 additions and 1 deletion.
2 changes: 1 addition & 1 deletion rclpy/rclpy/qos_overriding_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ def _get_qos_policy_parameter(qos: QoSProfile, policy: QoSPolicyKind) -> Union[s
if policy in (
QoSPolicyKind.LIFESPAN, QoSPolicyKind.DEADLINE, QoSPolicyKind.LIVELINESS_LEASE_DURATION
):
value = value.nanoseconds()
value = value.nanoseconds
return value


Expand Down
36 changes: 36 additions & 0 deletions rclpy/test/test_qos_overriding_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,21 @@
import pytest

import rclpy
from rclpy.duration import Duration
from rclpy.node import Node
from rclpy.parameter import Parameter
from rclpy.publisher import Publisher
from rclpy.qos import QoSDurabilityPolicy
from rclpy.qos import QoSHistoryPolicy
from rclpy.qos import QoSLivelinessPolicy
from rclpy.qos import QoSProfile
from rclpy.qos import QoSReliabilityPolicy
from rclpy.qos_overriding_options import _declare_qos_parameters
from rclpy.qos_overriding_options import _get_qos_policy_parameter
from rclpy.qos_overriding_options import InvalidQosOverridesError
from rclpy.qos_overriding_options import QosCallbackResult
from rclpy.qos_overriding_options import QoSOverridingOptions
from rclpy.qos_overriding_options import QoSPolicyKind


@pytest.fixture(autouse=True)
Expand All @@ -32,6 +39,35 @@ def init_shutdown():
rclpy.shutdown()


def test_get_qos_policy_parameter():
qos = QoSProfile(
history=QoSHistoryPolicy.KEEP_LAST,
depth=10,
reliability=QoSReliabilityPolicy.RELIABLE,
durability=QoSDurabilityPolicy.VOLATILE,
lifespan=Duration(nanoseconds=1e3),
deadline=Duration(nanoseconds=1e6),
liveliness=QoSLivelinessPolicy.SYSTEM_DEFAULT,
liveliness_lease_duration=Duration(nanoseconds=1e9)
)
value = _get_qos_policy_parameter(qos, QoSPolicyKind.HISTORY)
assert value == 'keep_last'
value = _get_qos_policy_parameter(qos, QoSPolicyKind.DEPTH)
assert value == qos.depth
value = _get_qos_policy_parameter(qos, QoSPolicyKind.RELIABILITY)
assert value == 'reliable'
value = _get_qos_policy_parameter(qos, QoSPolicyKind.DURABILITY)
assert value == 'volatile'
value = _get_qos_policy_parameter(qos, QoSPolicyKind.LIFESPAN)
assert value == qos.lifespan.nanoseconds
value = _get_qos_policy_parameter(qos, QoSPolicyKind.DEADLINE)
assert value == qos.deadline.nanoseconds
value = _get_qos_policy_parameter(qos, QoSPolicyKind.LIVELINESS)
assert value == 'system_default'
value = _get_qos_policy_parameter(qos, QoSPolicyKind.LIVELINESS_LEASE_DURATION)
assert value == qos.liveliness_lease_duration.nanoseconds


def test_declare_qos_parameters():
node = Node('my_node')
_declare_qos_parameters(
Expand Down

0 comments on commit 6b6617a

Please sign in to comment.