Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[ros2param] Provide tests for ros2param verbs #389

Open
wants to merge 7 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions ros2param/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<test_depend>ament_pep257</test_depend>
<test_depend>ament_xmllint</test_depend>
<test_depend>python3-pytest</test_depend>
<test_depend>ros_testing</test_depend>

<export>
<build_type>ament_python</build_type>
Expand Down
56 changes: 56 additions & 0 deletions ros2param/test/fixtures/param_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
# Copyright 2019 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

import sys

from rcl_interfaces.msg import ParameterDescriptor
import rclpy
from rclpy.node import Node


class ParamNode(Node):

def __init__(self):
super().__init__('param_node')
self.declare_parameter('bool_param', True, ParameterDescriptor())
self.declare_parameter('int_param', 42, ParameterDescriptor())
self.declare_parameter('double_param', 1.23, ParameterDescriptor())
self.declare_parameter('str_param', 'Hello World', ParameterDescriptor())
self.declare_parameter('int_array', [1, 2, 3], ParameterDescriptor())
self.declare_parameter('double_array', [1.0, 2.0, 3.0], ParameterDescriptor())
self.declare_parameter('bool_array', [True, False, True], ParameterDescriptor())
self.declare_parameter('str_array', ['Hello', 'World'], ParameterDescriptor())
self.declare_parameter('byte_array', [b'p', b'v'], ParameterDescriptor())
self.declare_parameter('parameter_with_no_value', None, ParameterDescriptor())
BMarchi marked this conversation as resolved.
Show resolved Hide resolved


def main(args=None):
rclpy.init(args=args)

node = ParamNode()

try:
rclpy.spin(node)
except KeyboardInterrupt:
print('node stopped cleanly')
except BaseException:
print('exception in node:', file=sys.stderr)
raise
finally:
node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()
Loading