Skip to content

Commit 0e34880

Browse files
Use get_service in ros2service call (#994)
Signed-off-by: Michael Carlstrom <[email protected]>
1 parent b677df5 commit 0e34880

File tree

1 file changed

+7
-13
lines changed
  • ros2service/ros2service/verb

1 file changed

+7
-13
lines changed

ros2service/ros2service/verb/call.py

Lines changed: 7 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -12,11 +12,12 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414

15-
import importlib
1615
import time
16+
from typing import Optional
1717

1818
import rclpy
1919
from rclpy.qos import QoSPresetProfiles
20+
from rclpy.qos import QoSProfile
2021
from ros2cli.helpers import collect_stdin
2122
from ros2cli.node import NODE_NAME_PREFIX
2223
from ros2service.api import ServiceNameCompleter
@@ -25,6 +26,7 @@
2526
from ros2service.verb import VerbExtension
2627
from ros2topic.api import add_qos_arguments, profile_configure_short_keys
2728
from rosidl_runtime_py import set_message_fields
29+
from rosidl_runtime_py.utilities import get_service
2830
import yaml
2931

3032

@@ -77,23 +79,15 @@ def main(self, *, args):
7779
args.service_type, args.service_name, values, period, default_profile)
7880

7981

80-
def requester(service_type, service_name, values, period, qos_profile):
81-
# TODO(wjwwood) this logic should come from a rosidl related package
82+
def requester(service_type: str, service_name: str, values, period: Optional[float],
83+
qos_profile: QoSProfile) -> None:
8284
try:
8385
parts = service_type.split('/')
84-
if len(parts) == 2:
85-
parts = [parts[0], 'srv', parts[1]]
8686
package_name = parts[0]
87-
module = importlib.import_module('.'.join(parts[:-1]))
8887
srv_name = parts[-1]
89-
srv_module = getattr(module, srv_name)
90-
except (AttributeError, ModuleNotFoundError, ValueError):
88+
srv_module = get_service(service_type)
89+
except (AttributeError, ModuleNotFoundError):
9190
raise RuntimeError('The passed service type is invalid')
92-
try:
93-
srv_module.Request
94-
srv_module.Response
95-
except AttributeError:
96-
raise RuntimeError('The passed type is not a service')
9791

9892
values_dictionary = yaml.safe_load(values)
9993

0 commit comments

Comments
 (0)