diff --git a/doc/jsk_perception/nodes/rect_array_in_panorama_to_bounding_box_array.md b/doc/jsk_perception/nodes/rect_array_in_panorama_to_bounding_box_array.md index adfa13e358..cf4ed8d64a 100644 --- a/doc/jsk_perception/nodes/rect_array_in_panorama_to_bounding_box_array.md +++ b/doc/jsk_perception/nodes/rect_array_in_panorama_to_bounding_box_array.md @@ -44,5 +44,5 @@ Duration of timeout for lookup transform ## Sample ```bash -roslaunch jsk_perception sample_rect_array_in_panorama_to_bounding_box_array.launch +roslaunch jsk_perception sample_human_3d_detection.launch ``` diff --git a/doc/jsk_recognition_utils/nodes/resize_panorama_info.md b/doc/jsk_recognition_utils/nodes/resize_panorama_info.md new file mode 100644 index 0000000000..25f07f95ed --- /dev/null +++ b/doc/jsk_recognition_utils/nodes/resize_panorama_info.md @@ -0,0 +1,27 @@ +# resize\_panorama\_info.py + +## What is this ? + +Resize `jsk_recognition_msgs/PanoramaInfo` message. + +## Subscribing Topic + +* `~input` (`jsk_recognition_msgs/PanoramaInfo`) + + Input original panorama info. + +## Publishing Topic + +* `~output` (`jsk_recognition_msgs/PanoramaInfo`) + + Output resize panorama info. + +## Parameters + +* `~scale_height` (Float, default: 1.0) + + Resize scale for height + +* `~scale_width` (Float, default: 1.0) + + Resize scale for width diff --git a/jsk_perception/launch/dual_fisheye_to_panorama.launch b/jsk_perception/launch/dual_fisheye_to_panorama.launch new file mode 100644 index 0000000000..e06e56611d --- /dev/null +++ b/jsk_perception/launch/dual_fisheye_to_panorama.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_perception/launch/insta360_air.launch b/jsk_perception/launch/insta360_air.launch new file mode 100644 index 0000000000..a66d258bc2 --- /dev/null +++ b/jsk_perception/launch/insta360_air.launch @@ -0,0 +1,115 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + vertical_parts: 1 + horizontal_parts: 2 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/jsk_perception/launch/panorama_human_3d_detection.launch b/jsk_perception/launch/panorama_human_3d_detection.launch new file mode 100644 index 0000000000..af4022c736 --- /dev/null +++ b/jsk_perception/launch/panorama_human_3d_detection.launch @@ -0,0 +1,93 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + frame_fixed: $(arg frame_fixed) + dimensions_labels: + person: [0.5, 0.5, 1.5] + + + + + + + + + + + + + diff --git a/jsk_perception/sample/sample_dual_fisheye_to_panorama.launch b/jsk_perception/sample/sample_dual_fisheye_to_panorama.launch index f371db61c0..7e27febabf 100644 --- a/jsk_perception/sample/sample_dual_fisheye_to_panorama.launch +++ b/jsk_perception/sample/sample_dual_fisheye_to_panorama.launch @@ -1,34 +1,4 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - + diff --git a/jsk_perception/sample/sample_insta360_air.launch b/jsk_perception/sample/sample_insta360_air.launch index d78d892022..b778e6d3ea 100644 --- a/jsk_perception/sample/sample_insta360_air.launch +++ b/jsk_perception/sample/sample_insta360_air.launch @@ -1,115 +1,4 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - vertical_parts: 1 - horizontal_parts: 2 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + diff --git a/jsk_perception/sample/sample_panorama_human_3d_detection.launch b/jsk_perception/sample/sample_panorama_human_3d_detection.launch new file mode 100644 index 0000000000..4cc2b146d1 --- /dev/null +++ b/jsk_perception/sample/sample_panorama_human_3d_detection.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + diff --git a/jsk_perception/sample/sample_rect_array_in_panorama_to_bounding_box_array.launch b/jsk_perception/sample/sample_rect_array_in_panorama_to_bounding_box_array.launch deleted file mode 100644 index 9d0a9a5a0e..0000000000 --- a/jsk_perception/sample/sample_rect_array_in_panorama_to_bounding_box_array.launch +++ /dev/null @@ -1,69 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - frame_fixed: "camera" - dimensions_labels: - person: [0.5, 0.5, 1.5] - - - - - - - - diff --git a/jsk_perception/scripts/install_sample_data.py b/jsk_perception/scripts/install_sample_data.py index e733d79e23..c701829eca 100755 --- a/jsk_perception/scripts/install_sample_data.py +++ b/jsk_perception/scripts/install_sample_data.py @@ -120,9 +120,9 @@ def main(): download_data( pkg_name=PKG, - path='sample/data/sample_rect_array_in_panorama_to_bounding_box_array.bag', - url='https://drive.google.com/uc?id=1f613TsYuPk1DWuGuUfkJVBbPv2-4Io69', - md5='04ba99ee993860634c0064d167b5cbe5', + path='sample/data/sample_panorama_human_3d_detection.bag', + url='https://drive.google.com/uc?id=1AqptBNBG5_fF9nYPlAC-ZoRr7exsD5w7', + md5='fdf8839b03305daa2c0ddbce02a1764a', extract=False, ) diff --git a/jsk_recognition_utils/node_scripts/resize_panorama_info.py b/jsk_recognition_utils/node_scripts/resize_panorama_info.py new file mode 100755 index 0000000000..f11dbe9833 --- /dev/null +++ b/jsk_recognition_utils/node_scripts/resize_panorama_info.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python + +import rospy + +from jsk_topic_tools import ConnectionBasedTransport + +from jsk_recognition_msgs.msg import PanoramaInfo + + +class ResizePanoramaInfo(ConnectionBasedTransport): + + def __init__(self): + super(ResizePanoramaInfo, self).__init__() + self.scale_height = float(rospy.get_param('~scale_height', 1.0)) + self.scale_width = float(rospy.get_param('~scale_width', 1.0)) + self.pub = self.advertise('~output', PanoramaInfo, queue_size=1) + + def subscribe(self): + self.sub = rospy.Subscriber( + '~input', PanoramaInfo, self._sub_cb, queue_size=1) + + def unsubscribe(self): + self.sub.unregister() + + def _sub_cb(self, msg): + msg.image_height = int(msg.image_height * self.scale_height) + msg.image_width = int(msg.image_width * self.scale_width) + self.pub.publish(msg) + + +if __name__ == '__main__': + rospy.init_node('resize_panorama_info') + app = ResizePanoramaInfo() + rospy.spin()