rosros 0.2.5
Simple unified interface to ROS1 / ROS2 Python API
Loading...
Searching...
No Matches
rclify.py
Go to the documentation of this file.
1"""
2Stand-in for `rclpy` in ROS1.
3
4Heavily modified copy from ROS2 `rclpy`,
5at https://github.com/ros2/rclpy (`rclpy/rclpy/__init__.py`),
6released under the Apache 2.0 License.
7
8------------------------------------------------------------------------------
9This file is part of rosros - simple unified interface to ROS1 / ROS2.
10Released under the BSD License.
11
12@author Erki Suurjaak
13@created 16.02.2022
14@modified 28.02.2023
15------------------------------------------------------------------------------
16"""
17## @namespace rosros.rclify.rclify
18
19# Original file copyright notice:
20#
21# Copyright 2016 Open Source Robotics Foundation, Inc.
22#
23# Licensed under the Apache License, Version 2.0 (the "License");
24# you may not use this file except in compliance with the License.
25# You may obtain a copy of the License at
26#
27# http://www.apache.org/licenses/LICENSE-2.0
28#
29# Unless required by applicable law or agreed to in writing, software
30# distributed under the License is distributed on an "AS IS" BASIS,
31# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
32# See the License for the specific language governing permissions and
33# limitations under the License.
34import rospy
35import rospy.core
36
37#from .. import patch # Imported late to avoid circular import
38from .. import ros1
39from . node import Node
40
41
42def init(*, args=None, context=None):
43 """
44 Does nothing (ROS2 API compatibility stand-in)
45
46 @param args ignored (ROS2 API compatibility stand-in)
47 @param context ignored (ROS2 API compatibility stand-in)
48 """
49 from .. import patch # Imported late to avoid circular import
50 patch.patch_ros1_rclify()
51
52
53def create_node(node_name, *, context=None, cli_args=None, namespace=None,
54 use_global_arguments=True, enable_rosout=True, start_parameter_services=True,
55 parameter_overrides=None, allow_undeclared_parameters=False,
56 automatically_declare_parameters_from_overrides=False
57):
58 """
59 Initializes ROS1 and returns an instance of `rosros.rclify.node.Node`.
60
61 @param node_name a name to give to the node
62 @param context ignored (ROS2 API compatibility stand-in)
63 @param cli_args command-line arguments to be used by the node
64 @param namespace node namespace
65 @param use_global_arguments should the node use process-wide command-line arguments
66 @param enable_rosout publish logging to `/rosout`
67 @param start_parameter_services ignored (ROS2 API compatibility stand-in)
68 @param parameter_overrides list of `Parameter` to override the
69 initial values of parameters declared on the node
70 @param allow_undeclared_parameters allow undeclared parameters;
71 this option doesn't affect `parameter_overrides`
72 @param automatically_declare_parameters_from_overrides
73 implicitly declare parameters from `parameter_overrides`
75 """
76 return Node(
77 node_name, context=context, cli_args=cli_args, namespace=namespace,
78 use_global_arguments=use_global_arguments,
79 enable_rosout=enable_rosout,
80 start_parameter_services=start_parameter_services,
81 parameter_overrides=parameter_overrides,
82 allow_undeclared_parameters=allow_undeclared_parameters,
83 automatically_declare_parameters_from_overrides=automatically_declare_parameters_from_overrides
84 )
85
86
87def spin_once(node=None, *, executor=None, timeout_sec=None):
88 """
89 Waits until timeout or ROS shut down, or forever if timeout not specified.
90
91 @param node ignored (ROS2 API compatibility stand-in)
92 @param executor ignored (ROS2 API compatibility stand-in)
93 @param timeout_sec time to wait, as seconds or ROS1 duration
94 """
95 ros1.spin_once(timeout_sec)
96
97
98def spin(node=None, executor=None):
99 """
100 Waits forever.
101
102 @param node ignored (ROS2 API compatibility stand-in)
103 @param executor ignored (ROS2 API compatibility stand-in)
104 """
105 ros1.spin()
106
107
108def spin_until_future_complete(node=None, future=None, executor=None, timeout_sec=None):
109 """
110 Waits until future complete or timeout reached or ROS shut down.
111
112 @param node ignored (ROS2 API compatibility stand-in)
113 @param future object with `concurrent.futures.Future`-conforming interface to complete
114 @param executor ignored (ROS2 API compatibility stand-in)
115 @param timeout_sec time to wait, as seconds or ROS1 duration
116 """
117 ros1.spin_until_future_complete(future, timeout_sec)
118
121 """Returns None (ROS2 API compatibility stand-in)."""
122 return None
123
126 """Returns None (ROS2 API compatibility stand-in)."""
127 return None
128
131 """Returns empty string (ROS2 API compatibility stand-in)."""
132 return ""
133
134
135def ok(*, context=None):
136 """
137 Returns whether rospy has been initialized and is not shut down.
138
139 @param context ignored (ROS2 API compatibility stand-in)
140 """
141 return ros1.ok()
142
143
144def shutdown(*, context=None):
145 """
146 Sends the shutdown signal to rospy.
147
148 @param context ignored (ROS2 API compatibility stand-in)
149 """
150 rospy.signal_shutdown(reason="")
151
152
153def try_shutdown(*, context=None):
154 """
155 Sends the shutdown signal to rospy.
156
157 @param context ignored (ROS2 API compatibility stand-in)
158 """
159 rospy.signal_shutdown(reason="")
160
161
162__all__ = [
163 "create_node", "get_default_context", "get_global_executor",
164 "get_rmw_implementation_identifier", "init", "ok", "shutdown",
165 "spin", "spin_once", "spin_until_future_complete", "try_shutdown"
166]
spin()
Spins ROS node forever.
Definition core.py:133
ok()
Returns whether ROS has been initialized and is not shut down.
Definition core.py:157
spin_once(node=None, *executor=None, timeout_sec=None)
Waits until timeout or ROS shut down, or forever if timeout not specified.
Definition rclify.py:93
get_rmw_implementation_identifier()
Returns empty string (ROS2 API compatibility stand-in).
Definition rclify.py:129
shutdown(*context=None)
Sends the shutdown signal to rospy.
Definition rclify.py:148
get_default_context()
Returns None (ROS2 API compatibility stand-in).
Definition rclify.py:119
try_shutdown(*context=None)
Sends the shutdown signal to rospy.
Definition rclify.py:157
get_global_executor()
Returns None (ROS2 API compatibility stand-in).
Definition rclify.py:124
create_node(node_name, *context=None, cli_args=None, namespace=None, use_global_arguments=True, enable_rosout=True, start_parameter_services=True, parameter_overrides=None, allow_undeclared_parameters=False, automatically_declare_parameters_from_overrides=False)
Initializes ROS1 and returns an instance of `rosros.rclify.node.Node`.
Definition rclify.py:74
spin_until_future_complete(node=None, future=None, executor=None, timeout_sec=None)
Waits until future complete or timeout reached or ROS shut down.
Definition rclify.py:115
init(*args=None, context=None)
Does nothing (ROS2 API compatibility stand-in)
Definition rclify.py:48