Skip to content

Commit

Permalink
Merge pull request #2753 from knorth55/panorama-info-image-shape
Browse files Browse the repository at this point in the history
  • Loading branch information
k-okada committed Jan 25, 2023
2 parents a8a920f + ee9051a commit c71ebaf
Show file tree
Hide file tree
Showing 5 changed files with 19 additions and 16 deletions.
Expand Up @@ -7,10 +7,6 @@ Sample is `sample_rect_array_in_panorama_to_bounding_box_array.launch`

## Subscribing Topics

* `~panorama_image` (`sensor_msgs/Image`)

Panorama image topic.

* `~panorama_info` (`jsk_recognition_msgs/PanoramaInfo`)

Panorama info topic.
Expand Down
Expand Up @@ -50,22 +50,22 @@ def __init__(self):
self._dimensions_labels = rospy.get_param( '~dimensions_labels', {} )
self._duration_timeout = rospy.get_param( '~duration_timeout', 0.05 )

try:
msg_panorama_image = rospy.wait_for_message(
'~panorama_image', Image, 10)
msg_panorama_info = rospy.wait_for_message(
'~panorama_info', PanoramaInfo, 10)
except (rospy.ROSException, rospy.ROSInterruptException) as e:
rospy.logerr('{}'.format(e))
sys.exit(1)
msg_panorama_info = None
while (not rospy.is_shutdown() and msg_panorama_info is None):
try:
msg_panorama_info = rospy.wait_for_message(
'~panorama_info', PanoramaInfo, 10)
except (rospy.ROSException, rospy.ROSInterruptException) as e:
rospy.logerr('~panorama_info is not subscribed...')
rospy.logerr('waiting ~panorama_info for more 10 seconds')

self._frame_panorama = msg_panorama_info.header.frame_id
self._theta_min = msg_panorama_info.theta_min
self._theta_max = msg_panorama_info.theta_max
self._phi_min = msg_panorama_info.phi_min
self._phi_max = msg_panorama_info.phi_max
self._image_height = msg_panorama_image.height
self._image_width = msg_panorama_image.width
self._image_height = msg_panorama_info.image_height
self._image_width = msg_panorama_info.image_width

self._tf_buffer = tf2_ros.Buffer()
self._tf_listener = tf2_ros.TransformListener(self._tf_buffer)
Expand Down
Expand Up @@ -47,7 +47,6 @@
type="rect_array_in_panorama_to_bounding_box_array.py"
name="rect_array_in_panorama_to_bounding_box_array"
>
<remap from="~panorama_image" to="$(arg INPUT_PANORAMA_IMAGE)" />
<remap from="~panorama_info" to="$(arg INPUT_PANORAMA_INFO)" />
<remap from="~input_class" to="$(arg INPUT_CLASS)" />
<remap from="~input_rects" to="$(arg INPUT_RECTS)" />
Expand Down
2 changes: 2 additions & 0 deletions jsk_perception/src/dual_fisheye_to_panorama.cpp
Expand Up @@ -92,6 +92,8 @@ namespace jsk_perception
msg_panorama_info_.theta_max = M_PI;
msg_panorama_info_.phi_min = -M_PI;
msg_panorama_info_.phi_max = M_PI;
msg_panorama_info_.image_height = output_image_height_;
msg_panorama_info_.image_width = output_image_width_;

onInitPostProcess();
}
Expand Down
8 changes: 7 additions & 1 deletion jsk_recognition_msgs/msg/PanoramaInfo.msg
Expand Up @@ -11,7 +11,13 @@ std_msgs/Header header
string projection_model

#######################################################################
# Field of View Parameters #
# Image shape info #
#######################################################################
uint32 image_height
uint32 image_width

#######################################################################
# Field of View Parameters #
#######################################################################
float64 theta_min
float64 theta_max
Expand Down

0 comments on commit c71ebaf

Please sign in to comment.