Skip to content

Commit

Permalink
some fixes
Browse files Browse the repository at this point in the history
  • Loading branch information
NishanthJKumar committed Jul 17, 2023
1 parent f991a9b commit 3b72d01
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 30 deletions.
29 changes: 13 additions & 16 deletions predicators/spot_utils/perception_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

# NOTE: uncomment this line if trying to visualize stuff locally
# and matplotlib isn't displaying.
# matplotlib.use('TkAgg')
matplotlib.use('TkAgg')

ROTATION_ANGLE = {
'hand_color_image': 0,
Expand Down Expand Up @@ -240,18 +240,6 @@ def process_image_response(
corresponding to the image."""
# pylint: disable=no-member
num_bytes = 1 # Assume a default of 1 byte encodings.
# Make sure all the necessary fields exist.
if image_response.source.image_type != \
image_pb2.ImageSource.IMAGE_TYPE_DEPTH:
raise ValueError('requires an image_type of IMAGE_TYPE_DEPTH.')
if image_response.shot.image.pixel_format != \
image_pb2.Image.PIXEL_FORMAT_DEPTH_U16:
raise ValueError(
'IMAGE_TYPE_DEPTH with an unsupported format, requires ' +
'PIXEL_FORMAT_DEPTH_U16.')
if not image_response.source.HasField('pinhole'):
raise ValueError('Requires a pinhole camera_model.')

if image_response.shot.image.pixel_format == \
image_pb2.Image.PIXEL_FORMAT_DEPTH_U16:
dtype = np.uint16
Expand Down Expand Up @@ -289,9 +277,18 @@ def get_xyz_from_depth(image_response: bosdyn.api.image_pb2.ImageResponse,
depth_value: float, point_x: float,
point_y: float) -> Tuple[float, float, float]:
"""This is a function based on `depth_image_to_pointcloud`"""
# First call process_image_response to do error checking on the
# input image response.
process_image_response(image_response)
# pylint: disable=no-member
# Make sure all the necessary fields exist.
if image_response.source.image_type != \
image_pb2.ImageSource.IMAGE_TYPE_DEPTH:
raise ValueError('requires an image_type of IMAGE_TYPE_DEPTH.')
if image_response.shot.image.pixel_format != \
image_pb2.Image.PIXEL_FORMAT_DEPTH_U16:
raise ValueError(
'IMAGE_TYPE_DEPTH with an unsupported format, requires ' +
'PIXEL_FORMAT_DEPTH_U16.')
if not image_response.source.HasField('pinhole'):
raise ValueError('Requires a pinhole camera_model.')
# Next, compute the xyz point.
fx = image_response.source.pinhole.intrinsics.focal_length.x
fy = image_response.source.pinhole.intrinsics.focal_length.y
Expand Down
31 changes: 17 additions & 14 deletions predicators/spot_utils/spot_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,9 @@ def get_single_camera_image(self,
img_req = build_image_request(
source_name,
quality_percent=100,
pixel_format=image_pb2.Image.PIXEL_FORMAT_RGB_U8)
pixel_format= None if
('hand' in source_name or 'depth' in source_name) else
image_pb2.Image.PIXEL_FORMAT_RGB_U8)
image_response = self.image_client.get_image([img_req])

# Format image before detecting apriltags.
Expand Down Expand Up @@ -487,22 +489,23 @@ def get_sam_object_loc_from_camera(
class_name: name of object class
"""
# Only support using depth image to obatin location
image_request = [
build_image_request(source,
pixel_format=None if
('hand' in source or 'depth' in source) else
image_pb2.Image.PIXEL_FORMAT_RGB_U8)
for source in [source_rgb, source_depth]
]
image_responses = self.image_client.get_image(image_request)

# image_request = [
# build_image_request(source,
# pixel_format=None if
# ('hand' in source or 'depth' in source) else
# image_pb2.Image.PIXEL_FORMAT_RGB_U8)
# for source in [source_rgb, source_depth]
# ]
# image_responses = self.image_client.get_image(image_request)
_, rgb_img_response = self.get_single_camera_image(source_rgb, True)
_, depth_img_response = self.get_single_camera_image(source_rgb, True)
image = {
'rgb': process_image_response(image_responses[0]),
'depth': process_image_response(image_responses[1]),
'rgb': process_image_response(rgb_img_response[0]),
'depth': process_image_response(depth_img_response[0]),
}
image_responses = {
'rgb': image_responses[0],
'depth': image_responses[1],
'rgb': rgb_img_response,
'depth': depth_img_response,
}

res_locations = get_object_locations_with_detic_sam(
Expand Down

0 comments on commit 3b72d01

Please sign in to comment.