@@ -20,8 +20,8 @@ from typing import Any, Generic, Literal, overload, Sequence, TypedDict
20
20
21
21
from rclpy .clock import JumpHandle
22
22
from rclpy .clock_type import ClockType
23
- from rclpy .qos import ( QoSDurabilityPolicy , QoSHistoryPolicy , QoSLivelinessPolicy ,
24
- QoSReliabilityPolicy )
23
+ from rclpy .duration import Duration
24
+ from rclpy . parameter import Parameter
25
25
from rclpy .subscription import MessageInfo
26
26
from rclpy .type_support import MsgT
27
27
@@ -173,10 +173,118 @@ class Subscription(Destroyable, Generic[MsgT]):
173
173
"""Count the publishers from a subscription."""
174
174
175
175
176
- class Node :
176
+ class Node (Destroyable ):
177
+
178
+ def __init__ (self , node_name : str , namespace_ : str , context : Context ,
179
+ pycli_args : list [str ] | None , use_global_arguments : bool ,
180
+ enable_rosout : bool ) -> None : ...
181
+
182
+ @property
183
+ def pointer (self ) -> int :
184
+ """Get the address of the entity as an integer."""
185
+
186
+ def get_fully_qualified_name (self ) -> str :
187
+ """Get the fully qualified name of the node."""
188
+
189
+ def logger_name (self ) -> str :
190
+ """Get the name of the logger associated with a node."""
191
+
192
+ def get_node_name (self ) -> str :
193
+ """Get the name of a node."""
194
+
195
+ def get_namespace (self ) -> str :
196
+ """Get the namespace of a node."""
197
+
198
+ def get_count_publishers (self , topic_name : str ) -> int :
199
+ """Return the count of all the publishers known for that topic in the entire ROS graph."""
200
+
201
+ def get_count_subscribers (self , topic_name : str ) -> int :
202
+ """Return the count of all the subscribers known for that topic in the entire ROS graph."""
203
+
204
+ def get_count_clients (self , service_name : str ) -> int :
205
+ """Return the count of all the clients known for that service in the entire ROS graph."""
206
+
207
+ def get_count_services (self , service_name : str ) -> int :
208
+ """Return the count of all the servers known for that service in the entire ROS graph."""
209
+
210
+ def get_node_names_and_namespaces (self ) -> list [tuple [str , str , str ] | tuple [str , str ]]:
211
+ """Get the list of nodes discovered by the provided node."""
212
+
213
+ def get_node_names_and_namespaces_with_enclaves (self ) -> list [tuple [str , str , str ] |
214
+ tuple [str , str ]]:
215
+ """Get the list of nodes discovered by the provided node, with their enclaves."""
216
+
217
+ def get_action_client_names_and_types_by_node (self , remote_node_name : str ,
218
+ remote_node_namespace : str ) -> list [tuple [str ,
219
+ list [str ]]]:
220
+ """Get action client names and types by node."""
221
+
222
+ def get_action_server_names_and_types_by_node (self , remote_node_name : str ,
223
+ remote_node_namespace : str ) -> list [tuple [str ,
224
+ list [str ]]]:
225
+ """Get action server names and types by node."""
226
+
227
+ def get_action_names_and_types (self ) -> list [tuple [str , list [str ]]]:
228
+ """Get action names and types."""
229
+
230
+ def get_parameters (self , pyparamter_cls : type [Parameter ]) -> dict [str , Parameter ]:
231
+ """Get a list of parameters for the current node."""
232
+
233
+
234
+ def rclpy_resolve_name (node : Node , topic_name : str , only_expand : bool , is_service : bool ) -> str :
235
+ """Expand and remap a topic or service name."""
236
+
237
+
238
+ def rclpy_get_publisher_names_and_types_by_node (node : Node , no_demangle : bool , node_name : str ,
239
+ node_namespace : str
240
+ ) -> list [tuple [str , list [str ]]]:
241
+ """Get topic names and types for which a remote node has publishers."""
242
+
243
+
244
+ def rclpy_get_subscriber_names_and_types_by_node (node : Node , no_demangle : bool , node_name : str ,
245
+ node_namespace : str
246
+ ) -> list [tuple [str , list [str ]]]:
247
+ """Get topic names and types for which a remote node has subscribers."""
248
+
249
+
250
+ def rclpy_get_service_names_and_types_by_node (node : Node , node_name : str , node_namespace : str
251
+ ) -> list [tuple [str , list [str ]]]:
252
+ """Get all service names and types in the ROS graph."""
253
+
254
+
255
+ def rclpy_get_client_names_and_types_by_node (node : Node , node_name : str , node_namespace : str
256
+ ) -> list [tuple [str , list [str ]]]:
257
+ """Get service names and types for which a remote node has servers."""
258
+
259
+
260
+ def rclpy_get_service_names_and_types (node : Node ) -> list [tuple [str , list [str ]]]:
261
+ """Get all service names and types in the ROS graph."""
262
+
263
+
264
+ class TypeHashDict (TypedDict ):
265
+ version : int
266
+ value : bytes
267
+
268
+
269
+ class QoSDict (TypedDict ):
177
270
pass
178
271
179
272
273
+ class TopicEndpointInfoDict (TypedDict ):
274
+ node_name : str
275
+ node_namespace : str
276
+ topic_type : str
277
+ topic_type_hash : TypeHashDict
278
+ endpoint_type : int
279
+ endpoint_gid : list [int ]
280
+ qos_profile : rmw_qos_profile_dict
281
+
282
+
283
+ def rclpy_get_publishers_info_by_topic (node : Node , topic_name : str , no_mangle : bool
284
+ ) -> list [TopicEndpointInfoDict ]:
285
+ """Get publishers info for a topic."""
286
+
287
+
180
288
class Publisher (Destroyable , Generic [MsgT ]):
181
289
182
290
def __init__ (self , arg0 : Node , arg1 : type [MsgT ], arg2 : str , arg3 : rmw_qos_profile_t ) -> None :
@@ -257,14 +365,14 @@ PredefinedQosProfileTNames = Literal['qos_profile_sensor_data', 'qos_profile_def
257
365
258
366
259
367
class rmw_qos_profile_dict (TypedDict ):
260
- qos_history : QoSHistoryPolicy | int
261
- qos_depth : int
262
- qos_reliability : QoSReliabilityPolicy | int
263
- qos_durability : QoSDurabilityPolicy | int
264
- pyqos_lifespan : rcl_duration_t
265
- pyqos_deadline : rcl_duration_t
266
- qos_liveliness : QoSLivelinessPolicy | int
267
- pyqos_liveliness_lease_duration : rcl_duration_t
368
+ depth : int
369
+ history : int
370
+ reliability : int
371
+ durability : int
372
+ lifespan : Duration
373
+ deadline : Duration
374
+ liveliness : int
375
+ liveliness_lease_duration : Duration
268
376
avoid_ros_namespace_conventions : bool
269
377
270
378
@@ -335,6 +443,18 @@ class WaitSet(Destroyable):
335
443
"""Wait until timeout is reached or event happened."""
336
444
337
445
446
+ class RCLError (RuntimeError ):
447
+ pass
448
+
449
+
450
+ class NodeNameNonExistentError (RCLError ):
451
+ pass
452
+
453
+
454
+ class InvalidHandle (RuntimeError ):
455
+ pass
456
+
457
+
338
458
class SignalHandlerOptions (Enum ):
339
459
_value_ : int
340
460
NO = ...
0 commit comments