Skip to content

Commit

Permalink
use builtin string type in service interfaces
Browse files Browse the repository at this point in the history
Signed-off-by: Kenji Brameld <[email protected]>
  • Loading branch information
ijnek committed Aug 31, 2022
1 parent b288ec1 commit a32743d
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 21 deletions.
1 change: 0 additions & 1 deletion ipm_interfaces/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
<depend>sensor_msgs</depend>
<depend>shape_msgs</depend>
<depend>vision_msgs</depend>
<depend>std_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions ipm_interfaces/srv/MapPoint.srv
Original file line number Diff line number Diff line change
@@ -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
Expand Down
4 changes: 2 additions & 2 deletions ipm_interfaces/srv/MapPointCloud2.srv
Original file line number Diff line number Diff line change
@@ -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
Expand Down
28 changes: 20 additions & 8 deletions ipm_service/ipm_service/ipm.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,19 +58,25 @@ 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:
response.point = self.ipm.map_point(
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:
Expand All @@ -97,19 +103,25 @@ 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:
header, mapped_points = self.ipm.map_points(
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
Expand Down
10 changes: 2 additions & 8 deletions ipm_service/test/test_ipm_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down Expand Up @@ -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)

Expand Down

0 comments on commit a32743d

Please sign in to comment.