Skip to content

Commit

Permalink
update docstring
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 a32743d commit 9d9d717
Show file tree
Hide file tree
Showing 4 changed files with 17 additions and 17 deletions.
18 changes: 12 additions & 6 deletions ipm_library/ipm_library/ipm.py
Original file line number Diff line number Diff line change
Expand Up @@ -88,9 +88,12 @@ def map_point(
:param plane: Plane in which the mapping should happen
:param point: Point that should be mapped
:param time: Time at which the point (or the image where it is from) is was captured
:param plane_frame_id: TF2 frame referenced for the plane
:param output_frame_id: TF2 frame in which the output should be provided
:param time: Time that point (or the image where it is from) was captured. If not
provided, current time will be used for transforms.
:param plane_frame_id: TF2 frame that the plane is defined in. If not provided, it is
assumed that the plane is in CameraInfo's frame.
:param output_frame_id: TF2 frame in which the output should be provided. If not provided,
the returned point will be in CameraInfo's frame.
:rasies CameraInfoNotSetException if camera info has not been provided
:raise: InvalidPlaneException if the plane is invalid
:raise: NoIntersectionError if the point is not on the plane
Expand Down Expand Up @@ -131,9 +134,12 @@ def map_points(
:param plane_msg: Plane in which the mapping should happen
:param points: Points that should be mapped in the form of
a nx2 numpy array where n is the number of points
:param time: Time at which the point (or the image where it is from) is was captured
:param plane_frame_id: TF2 frame referenced for the plane
:param output_frame_id: TF2 frame in which the output should be provided
:param time: Time that points (or the image where it is from) was captured. If not
provided, current time will be used for transforms.
:param plane_frame_id: TF2 frame that the plane is defined in. If not provided, it is
assumed that the plane is in CameraInfo's frame.
:param output_frame_id: TF2 frame in which the output should be provided. If not provided,
the returned points will be in CameraInfo's frame.
:returns: The points mapped onto the given plane in the output frame
:rasies CameraInfoNotSetException if camera info has not been provided
:raises InvalidPlaneException if the plane is invalid
Expand Down
4 changes: 1 addition & 3 deletions ipm_library/test/test_ipm.py
Original file line number Diff line number Diff line change
Expand Up @@ -75,9 +75,7 @@ def test_ipm_map_point_no_transform():
point_original = np.array([[point_original_x], [point_original_y]])
point_original_msg = Point2D(x=point_original_x, y=point_original_y)
# Map points
point_mapped_msg = ipm.map_point(
plane,
point_original_msg)
point_mapped_msg = ipm.map_point(plane, point_original_msg)
# Perform projection back into 2D image using projection matrix K to ensure that
# it's the same as the original point
point_mapped_vec = np.array([[point_mapped_msg.point.x],
Expand Down
2 changes: 1 addition & 1 deletion ipm_service/ipm_service/ipm.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ def point_cloud_mapping_callback(

# Map optional output_frame_id from '' to None
if request.output_frame_id == '':
output_frame_id = self.ipm.get_camera_info().header.frame_id
output_frame_id = None
else:
output_frame_id = request.output_frame_id

Expand Down
10 changes: 3 additions & 7 deletions ipm_service/test/test_ipm_service.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
from sensor_msgs.msg import CameraInfo
from sensor_msgs_py.point_cloud2 import create_cloud, PointField, read_points_numpy
from shape_msgs.msg import Plane
from std_msgs.msg import Header, String
from std_msgs.msg import Header
from tf2_ros import Buffer
from vision_msgs.msg import Point2D

Expand Down Expand Up @@ -158,9 +158,7 @@ def test_map_point():
assert future.result().result == MapPoint.Response.RESULT_SUCCESS

ipm = IPM(Buffer(), camera_info)
expected_point = ipm.map_point(
plane,
point)
expected_point = ipm.map_point(plane, point)
assert future.result().point == expected_point

rclpy.shutdown()
Expand Down Expand Up @@ -249,9 +247,7 @@ def test_map_point_cloud():
assert future.result().result == MapPointCloud2.Response.RESULT_SUCCESS

ipm = IPM(Buffer(), camera_info)
_, expected_points = ipm.map_points(
plane,
points)
_, expected_points = ipm.map_points(plane, points)

np.testing.assert_allclose(
read_points_numpy(future.result().points),
Expand Down

0 comments on commit 9d9d717

Please sign in to comment.