Skip to content

Commit

Permalink
add rect_array_in_panorama_to_bounding_box_array.launch
Browse files Browse the repository at this point in the history
  • Loading branch information
knorth55 committed Dec 7, 2022
1 parent c4204e3 commit fc2b5ec
Show file tree
Hide file tree
Showing 2 changed files with 90 additions and 62 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
<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="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 name="INPUT_PANORAMA_INFO" default="/dual_fisheye_to_panorama/panorama_info" />
<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" vlaue="$(arg create_panorama)" />
<arg name="throttle" vlaue="$(arg throttle)" />
<arg name="panorama_resolution_mode" vlaue="$(arg panorama_resolution_mode)" />
<arg name="gui" value="false" />
</include>

<node if="$(arg resize)" 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>

<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_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)" />
<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>
Original file line number Diff line number Diff line change
Expand Up @@ -2,69 +2,19 @@

<arg name="gui" default="true" />

<arg name="INPUT_PANORAMA_IMAGE" default="/dual_fisheye_to_panorama/output/quater" />
<arg name="INPUT_PANORAMA_INFO" default="/dual_fisheye_to_panorama/panorama_info" />
<arg name="INPUT_CLASS" default="/edgetpu_panorama_object_detector/output/class" />
<arg name="INPUT_RECTS" default="/edgetpu_panorama_object_detector/output/rects" />

<param name="/use_sim_time" value="true" />
<node
pkg="rosbag"
name="rosbag_play"
type="play"
args="$(find jsk_perception)/sample/data/sample_rect_array_in_panorama_to_bounding_box_array.bag --clock --loop" />
<node
pkg="image_transport"
type="republish"
name="panorama_decompress"
args="compressed in:=/dual_fisheye_to_panorama/output raw out:=/dual_fisheye_to_panorama/output"
/>
<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>

<!-- 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>

<!-- 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_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)" />
<rosparam>
frame_fixed: "camera"
dimensions_labels:
person: [0.5, 0.5, 1.5]
</rosparam>
</node>
<node pkg="rosbag" name="rosbag_play" type="play"
args="$(find jsk_perception)/sample/data/sample_rect_array_in_panorama_to_bounding_box_array.bag --clock --loop" />
<node pkg="image_transport" type="republish" name="panorama_decompress"
args="compressed in:=/dual_fisheye_to_panorama/output raw
out:=/dual_fisheye_to_panorama/output" />
<include file="$(find jsk_perception)/launch/rect_array_in_panorama_to_bounding_box_array.launch">
<arg name="launch_insta360" value="false" />
<arg name="launch_coral" value="false" />
<arg name="static_transform_publisher" value="false" />
<arg name="resize" value="true" />
<arg name="gui" value="true" />
</include>

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

</launch>

0 comments on commit fc2b5ec

Please sign in to comment.