Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add panorama_human_3d_detection.launch with insta360 air and coral #2754

Open
wants to merge 10 commits into
base: master
Choose a base branch
from
Original file line number Diff line number Diff line change
Expand Up @@ -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
```
27 changes: 27 additions & 0 deletions doc/jsk_recognition_utils/nodes/resize_panorama_info.md
Original file line number Diff line number Diff line change
@@ -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
26 changes: 26 additions & 0 deletions jsk_perception/launch/dual_fisheye_to_panorama.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
<launch>
<arg name="INPUT_IMAGE" default="/insta360/image_raw" doc="topic name of 360 camera image" />
<arg name="refine_align" default="false" doc="If true, panorama is improved by refine align process. Note that this process takes a large CPU load." />
<arg name="fovd" default="185.0" doc="Camera's Field of View [degree]" />
<arg name="save_unwarped" default="false" doc="Save unwarped fisheye images. This is useful to create MLS grids." />
<arg name="resolution_mode" default="high" doc="Resolution mode, 'high' or 'low'" />
<arg name="image_transport" default="raw" doc="Image transport: raw, compressed, etc." />
<arg name="vital_rate" default="1.0" doc="Rate to determine if the nodelet is in health." />

<node name="dual_fisheye_to_panorama"
pkg="nodelet" type="nodelet"
args="standalone jsk_perception/DualFisheyeToPanorama">
<remap from="~input" to="$(arg INPUT_IMAGE)"/>
<param name="light_compen" value="false" />
<param name="refine_align" value="$(arg refine_align)" />
<param name="fovd" value="$(arg fovd)" />
<param name="save_unwarped" value="$(arg save_unwarped)" />
<param name="image_transport" value="$(arg image_transport)"/>
<rosparam
command="load"
file="$(find jsk_perception)/config/dual_fisheye_to_panorama/$(arg resolution_mode)_resolution_config.yaml"
subst_value="true"/>
<param name="vital_rate" value="$(arg vital_rate)" />
</node>

</launch>
115 changes: 115 additions & 0 deletions jsk_perception/launch/insta360_air.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,115 @@
<launch>
<!-- insta360 air settings -->
<arg name="publish_image" default="true" />
<arg name="split_image" default="true" />
<arg name="use_usb_cam" default="false" />
<arg name="camera_name" default="insta360" />
<arg name="vendor" default="0x2e1a" />
<arg name="product" default="0x1000"/>
<!--
Available sizes for mjpeg are
1472 x 736 with 30 fps
2176 x 1088 with 30 fps
3008 x 1504 with 30 fps
-->
<arg name="width" default="3008" />
<arg name="height" default="1504" />
<arg name="video_mode" default="mjpeg" />
<arg name="frame_rate" default="30" />
<arg name="brightness" default="128" />
<arg name="create_panorama" default="true" />
<arg name="throttle" default="false" />
<arg if="$(arg throttle)" name="dual_fisheye_image" default="/$(arg camera_name)/throttled/image_raw" />
<arg unless="$(arg throttle)" name="dual_fisheye_image" default="/$(arg camera_name)/image_raw" />
<arg name="throttled_rate" default="1.0" />
<arg name="refine_align" default="false" />
<arg name="save_unwarped" default="false" />
<arg name="panorama_resolution_mode" default="high" />
<arg name="panorama_image_transport" default="raw" />
<arg name="vital_rate" default="1.0" />
<arg name="gui" default="true" />

<!-- Publish camera image -->
<group if="$(arg publish_image)">
<!-- For melodic or newer -->
<include unless="$(arg use_usb_cam)" file="$(find jsk_perception)/launch/libuvc_camera.launch">
<arg name="camera_name" value="$(arg camera_name)" />
<arg name="vendor" value="$(arg vendor)" />
<arg name="product" value="$(arg product)" />
<arg name="height" value="$(arg height)" />
<arg name="width" value="$(arg width)" />
<arg name="video_mode" value="$(arg video_mode)" />
<arg name="frame_rate" value="$(arg frame_rate)" />
<arg name="brightness" value="$(arg brightness)" /> <!-- -32768 ~ 32767 -->
<arg name="gui" value="$(arg gui)" />
</include>
<!-- For kinetic or older -->
<include if="$(arg use_usb_cam)" file="$(find jsk_perception)/launch/usb_cam.launch">
<arg name="camera_name" value="$(arg camera_name)" />
<arg name="video_device" value="/dev/insta360" />
<arg name="height" value="$(arg height)" />
<arg name="width" value="$(arg width)" />
<arg name="video_mode" value="$(arg video_mode)" />
<arg name="frame_rate" value="$(arg frame_rate)" />
<arg name="brightness" value="$(arg brightness)" /> <!-- 0 ~ 255 -->
<arg name="gui" value="$(arg gui)" />
</include>
</group>

<!-- Split insta360 air image into 2 fisheye image -->
<node if="$(arg split_image)"
pkg="jsk_perception" name="split_image" type="split_image.py" output="screen">
<remap from="~input" to="/insta360/image_raw" />
<rosparam>
vertical_parts: 1
horizontal_parts: 2
</rosparam>
</node>

<group ns="insta360" if="$(arg throttle)">
<node name="throttle_camera_info"
pkg="nodelet" type="nodelet"
args="standalone jsk_topic_tools/LightweightThrottle"
respawn="true">
<remap from="~input" to="camera_info"/>
<remap from="~output" to="throttled/camera_info" />
<param name="update_rate" value="$(arg throttled_rate)" />
</node>
<node name="throttle_rgb"
pkg="nodelet" type="nodelet"
args="standalone jsk_topic_tools/LightweightThrottle"
respawn="true">
<remap from="~input" to="image_raw" />
<remap from="~output" to="throttled/image_raw" />
<param name="update_rate" value="$(arg throttled_rate)" />
</node>
<node name="throttle_rgb_compressed"
pkg="nodelet" type="nodelet"
args="standalone jsk_topic_tools/LightweightThrottle"
respawn="true">
<remap from="~input" to="image_raw/compressed" />
<remap from="~output" to="throttled/image_raw/compressed" />
<param name="update_rate" value="$(arg throttled_rate)" />
</node>
</group>

<include if="$(arg create_panorama)"
file="$(find jsk_perception)/launch/dual_fisheye_to_panorama.launch">
<arg name="INPUT_IMAGE" value="$(arg dual_fisheye_image)" />
<arg name="fovd" value="210" />
<arg name="refine_align" value="$(arg refine_align)" />
<arg name="save_unwarped" value="$(arg save_unwarped)" />
<arg name="resolution_mode" value="$(arg panorama_resolution_mode)" />
<arg name="image_transport" value="$(arg panorama_image_transport)" />
<arg name="vital_rate" value="$(arg vital_rate)" />
</include>

<group if="$(arg gui)">
<node name="image_view" pkg="image_view" type="image_view">
<remap from="image" to="dual_fisheye_to_panorama/output" if="$(arg create_panorama)"/>
<remap from="image" to="$(arg dual_fisheye_image)" unless="$(arg create_panorama)"/>
</node>
</group>


</launch>
93 changes: 93 additions & 0 deletions jsk_perception/launch/panorama_human_3d_detection.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
<launch>
<arg name="launch_insta360" default="true" />
<arg name="launch_coral" default="true" />

<arg name="publish_image" default="true" />
<arg name="split_image" default="true" />
<arg name="camera_name" default="insta360" />
<arg name="create_panorama" default="true" />
<arg name="throttle" default="false" />
<arg name="panorama_resolution_mode" default="low" />
<arg name="panorama_image_transport" default="raw" />
<arg name="vital_rate" default="1.0" />
<arg name="resize" default="false" />

<arg name="frame_fixed" default="camera" />
<arg name="static_transform_publisher" default="true" />
<arg name="gui" default="true" />

<arg name="INPUT_IMAGE" default="/$(arg camera_name)/image_raw" doc="topic name of 360 camera image" />
<arg unless="$(arg resize)"
name="INPUT_PANORAMA_IMAGE" default="/dual_fisheye_to_panorama/output" />
<arg if="$(arg resize)"
name="INPUT_PANORAMA_IMAGE" default="/dual_fisheye_to_panorama/output/quater" />
<arg unless="$(arg resize)"
name="INPUT_PANORAMA_INFO" default="/dual_fisheye_to_panorama/panorama_info" />
<arg if="$(arg resize)"
name="INPUT_PANORAMA_INFO" default="/dual_fisheye_to_panorama/panorama_info/quater" />
<arg name="INPUT_CLASS" default="/edgetpu_panorama_object_detector/output/class" />
<arg name="INPUT_RECTS" default="/edgetpu_panorama_object_detector/output/rects" />

<include if="$(arg launch_insta360)"
file="$(find jsk_perception)/launch/insta360_air.launch">
<arg name="publish_image" value="$(arg publish_image)" />
<arg name="split_image" value="$(arg split_image)" />
<arg name="camera_name" value="$(arg camera_name)" />
<arg name="create_panorama" value="$(arg create_panorama)" />
<arg name="throttle" value="$(arg throttle)" />
<arg name="panorama_resolution_mode" value="$(arg panorama_resolution_mode)" />
<arg name="panorama_image_transport" value="$(arg panorama_image_transport)" />
<arg name="vital_rate" value="$(arg vital_rate)" />
<arg name="gui" value="false" />
</include>

<group if="$(arg resize)">
<node pkg="nodelet" type="nodelet" name="panorama_image_resize"
args="standalone image_proc/resize">
<param name="scale_height" value="0.5" />
<param name="scale_width" value="0.5" />
<remap from="image" to="/dual_fisheye_to_panorama/output" />
<remap from="~image" to="/dual_fisheye_to_panorama/output/quater" />
</node>

<node pkg="jsk_recognition_utils" type="resize_panorama_info.py" name="panorama_info_resize">
<param name="scale_height" value="0.5" />
<param name="scale_width" value="0.5" />
<remap from="~input" to="/dual_fisheye_to_panorama/panorama_info" />
<remap from="~output" to="/dual_fisheye_to_panorama/panorama_info/quater" />
</node>
</group>

<include if="$(arg launch_coral)"
file="$(find coral_usb)/launch/edgetpu_panorama_object_detector.launch">
<arg name="INPUT_IMAGE" value="$(arg INPUT_PANORAMA_IMAGE)" />
</include>

<node if="$(arg static_transform_publisher)"
name="camera_transform_publisher" pkg="tf" type="static_transform_publisher"
args="0 0 0 0 0 0 $(arg camera_name)_link camera 10"/>

<!-- rect_array_in_panorama_to_bounding_box_array -->
<node pkg="jsk_perception" type="rect_array_in_panorama_to_bounding_box_array.py"
name="rect_array_in_panorama_to_bounding_box_array">
<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)" />
<rosparam subst_value="true">
frame_fixed: $(arg frame_fixed)
dimensions_labels:
person: [0.5, 0.5, 1.5]
</rosparam>
</node>

<!-- visualize output of object detector -->
<node pkg="jsk_perception" type="draw_rects" name="draw_rects">
<remap from="~input" to="$(arg INPUT_PANORAMA_IMAGE)" />
<remap from="~input/rects" to="$(arg INPUT_RECTS)" />
<remap from="~input/class" to="$(arg INPUT_CLASS)" />
</node>

<node if="$(arg gui)" pkg="rviz" type="rviz" name="$(anon rviz)"
args="-d $(find jsk_perception)/sample/config/sample_rect_array_in_panorama_to_bounding_box_array.rviz" />

</launch>
34 changes: 2 additions & 32 deletions jsk_perception/sample/sample_dual_fisheye_to_panorama.launch
Original file line number Diff line number Diff line change
@@ -1,34 +1,4 @@
<launch>
<arg name="gui" default="true"/>

<arg name="INPUT_IMAGE" default="/insta360/image_raw" doc="topic name of 360 camera image" />
<arg name="refine_align" default="false" doc="If true, panorama is improved by refine align process. Note that this process takes a large CPU load." />
<arg name="fovd" default="185.0" doc="Camera's Field of View [degree]" />
<arg name="save_unwarped" default="false" doc="Save unwarped fisheye images. This is useful to create MLS grids." />
<arg name="resolution_mode" default="high" doc="Resolution mode, 'high' or 'low'" />
<arg name="vital_rate" default="1.0" doc="Rate to determine if the nodelet is in health." />
<arg name="image_transport" default="raw"/>

<node name="dual_fisheye_to_panorama"
pkg="nodelet" type="nodelet"
args="standalone jsk_perception/DualFisheyeToPanorama">
<remap from="~input" to="$(arg INPUT_IMAGE)"/>
<param name="light_compen" value="false" />
<param name="refine_align" value="$(arg refine_align)" />
<param name="fovd" value="$(arg fovd)" />
<param name="save_unwarped" value="$(arg save_unwarped)" />
<param name="image_transport" value="$(arg image_transport)"/>
<rosparam
command="load"
file="$(find jsk_perception)/config/dual_fisheye_to_panorama/$(arg resolution_mode)_resolution_config.yaml"
subst_value="true"/>
<param name="vital_rate" value="$(arg vital_rate)" />
</node>

<group if="$(arg gui)">
<node name="image_view"
pkg="image_view" type="image_view">
<remap from="image" to="dual_fisheye_to_panorama/output"/>
</node>
</group>
<include file="$(find jsk_perception)/sample/sample_insta360_air.launch"
pass_all_args="true" />
</launch>
Loading