|
rosros 0.2.5
Simple unified interface to ROS1 / ROS2 Python API
|
Stand-ins for `rospy.impl.tcpros_service` in ROS2. More...
Classes | |
| class | Service |
| Stand-in for `rospy.Service`, wrapping the creation of ROS2 service. More... | |
| class | ServiceException |
| Exception class for service-related errors. More... | |
| class | ServiceProxy |
| Stand-in for `rospy.ServiceProxy`, wrapping the creation of ROS2 service client. More... | |
Functions | |
| _wait_for_service (service, timeout=None, cls_or_typename=None) | |
| Blocks until service is available. | |
| wait_for_service (service, timeout=None) | |
| Blocks until service is available. | |
Stand-ins for `rospy.impl.tcpros_service` in ROS2.
|
protected |
Blocks until service is available.
Use this in initialization code if your program depends on a service already running.
| service | name of service |
| timeout | time to wait at most, as seconds or ROS duration; None or <0 waits forever |
| cls_or_typename | service type to expect if any, as ROS service class object like `std_msgs.msg.Bool` or service type name like "std_srvs/SetBool" |
| ROSException | if specified timeout is exceeded |
| ROSInterruptException | if shutdown interrupts wait |
Definition at line 59 of file service.py.
| rosros.rospify.service.wait_for_service | ( | service, | |
timeout = None |
|||
| ) |
Blocks until service is available.
Use this in initialization code if your program depends on a service already running.
| service | name of service |
| timeout | timeout time in seconds or Duration, None for no timeout. |
| ROSException | if specified timeout is exceeded |
| ROSInterruptException | if shutdown interrupts wait |
Definition at line 37 of file service.py.