From a32743d8e9fd034b3cbbcd5fa70411ef6b499679 Mon Sep 17 00:00:00 2001 From: Kenji Brameld Date: Thu, 1 Sep 2022 08:17:42 +0900 Subject: [PATCH] use builtin string type in service interfaces Signed-off-by: Kenji Brameld --- ipm_interfaces/package.xml | 1 - ipm_interfaces/srv/MapPoint.srv | 4 ++-- ipm_interfaces/srv/MapPointCloud2.srv | 4 ++-- ipm_service/ipm_service/ipm.py | 28 +++++++++++++++++++-------- ipm_service/test/test_ipm_service.py | 10 ++-------- 5 files changed, 26 insertions(+), 21 deletions(-) diff --git a/ipm_interfaces/package.xml b/ipm_interfaces/package.xml index 97193a2..c2c690f 100644 --- a/ipm_interfaces/package.xml +++ b/ipm_interfaces/package.xml @@ -15,7 +15,6 @@ sensor_msgs shape_msgs vision_msgs - std_msgs ament_lint_auto ament_lint_common diff --git a/ipm_interfaces/srv/MapPoint.srv b/ipm_interfaces/srv/MapPoint.srv index f1972b3..a0c4966 100644 --- a/ipm_interfaces/srv/MapPoint.srv +++ b/ipm_interfaces/srv/MapPoint.srv @@ -1,8 +1,8 @@ shape_msgs/Plane plane vision_msgs/Point2D point builtin_interfaces/Time time -std_msgs/String plane_frame_id -std_msgs/String output_frame_id +string plane_frame_id +string output_frame_id --- # Result code defintions uint8 RESULT_SUCCESS=0 diff --git a/ipm_interfaces/srv/MapPointCloud2.srv b/ipm_interfaces/srv/MapPointCloud2.srv index 3e371f8..892e9dd 100644 --- a/ipm_interfaces/srv/MapPointCloud2.srv +++ b/ipm_interfaces/srv/MapPointCloud2.srv @@ -1,7 +1,7 @@ shape_msgs/Plane plane sensor_msgs/PointCloud2 points -std_msgs/String plane_frame_id -std_msgs/String output_frame_id +string plane_frame_id +string output_frame_id --- # Result code defintions uint8 RESULT_SUCCESS=0 diff --git a/ipm_service/ipm_service/ipm.py b/ipm_service/ipm_service/ipm.py index c1ed666..5feb771 100644 --- a/ipm_service/ipm_service/ipm.py +++ b/ipm_service/ipm_service/ipm.py @@ -58,11 +58,17 @@ def point_mapping_callback( response.result = MapPoint.Response.RESULT_NO_CAMERA_INFO return response - # Map optional marking from '' to None - if request.output_frame_id.data == '': + # Map optional plane_frame_id from '' to None + if request.plane_frame_id == '': + plane_frame_id = None + else: + plane_frame_id = request.plane_frame_id + + # Map optional output_frame_id from '' to None + if request.output_frame_id == '': output_frame_id = None else: - output_frame_id = request.output_frame_id.data + output_frame_id = request.output_frame_id # Maps the given point and handle different result scenarios try: @@ -70,7 +76,7 @@ def point_mapping_callback( request.plane, request.point, request.time, - request.plane_frame_id.data, + plane_frame_id, output_frame_id) response.result = MapPoint.Response.RESULT_SUCCESS except NoIntersectionError: @@ -97,11 +103,17 @@ def point_cloud_mapping_callback( response.result = MapPointCloud2.Response.RESULT_NO_CAMERA_INFO return response - # Map optional marking from '' to None - if request.output_frame_id.data == '': + # Map optional plane_frame_id from '' to None + if request.plane_frame_id == '': + plane_frame_id = None + else: + plane_frame_id = request.plane_frame_id + + # Map optional output_frame_id from '' to None + if request.output_frame_id == '': output_frame_id = self.ipm.get_camera_info().header.frame_id else: - output_frame_id = request.output_frame_id.data + output_frame_id = request.output_frame_id # Map the given point and handle different result scenarios try: @@ -109,7 +121,7 @@ def point_cloud_mapping_callback( request.plane, read_points_numpy(request.points), request.points.header.stamp, - request.plane_frame_id.data, + plane_frame_id, output_frame_id) # Convert them into a PointCloud2 diff --git a/ipm_service/test/test_ipm_service.py b/ipm_service/test/test_ipm_service.py index eba2436..905f6c5 100644 --- a/ipm_service/test/test_ipm_service.py +++ b/ipm_service/test/test_ipm_service.py @@ -148,10 +148,7 @@ def test_map_point(): plane.coef[3] = -1.0 # 1 meter distance client = test_node.create_client(MapPoint, 'map_point') - req = MapPoint.Request( - point=point, - plane=plane, - plane_frame_id=String(data='camera_optical_frame')) + req = MapPoint.Request(point=point, plane=plane) future = client.call_async(req) rclpy.spin_once(ipm_service_node, timeout_sec=0.1) @@ -242,10 +239,7 @@ def test_map_point_cloud(): plane.coef[3] = -1.0 # 1 meter distance client = test_node.create_client(MapPointCloud2, 'map_pointcloud2') - req = MapPointCloud2.Request( - points=point_cloud, - plane=plane, - plane_frame_id=String(data='camera_optical_frame')) + req = MapPointCloud2.Request(points=point_cloud, plane=plane) future = client.call_async(req) rclpy.spin_once(ipm_service_node, timeout_sec=0.1)