Skip to content

Commit

Permalink
[jsk_perception] add sample launch of rect_array_in_panorama_to_bound…
Browse files Browse the repository at this point in the history
…ing_box_array
  • Loading branch information
sktometometo committed Mar 15, 2021
1 parent ea58927 commit e1af6a2
Show file tree
Hide file tree
Showing 2 changed files with 214 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,144 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded: ~
Splitter Ratio: 0.5
Tree Height: 399
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: Image
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Class: rviz/Image
Enabled: true
Image Topic: /draw_rects/output
Max Value: 1
Median window: 5
Min Value: 0
Name: Image
Normalize Range: true
Queue Size: 2
Transport Hint: raw
Unreliable: false
Value: true
- Class: jsk_rviz_plugin/BoundingBoxArray
Enabled: true
Name: BoundingBoxArray
Topic: /rect_array_in_panorama_to_bounding_box_array/bbox_array
Unreliable: false
Value: true
alpha: 0.800000011920929
color: 25; 255; 0
coloring: Label
line width: 0.004999999888241291
only edge: false
show coords: false
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: camera
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 10
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.750397801399231
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 3.593593120574951
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 1025
Hide Left Dock: false
Hide Right Dock: true
Image:
collapsed: false
QMainWindow State: 000000ff00000000fd00000004000000000000025800000363fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000021a000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d006100670065010000025d000001430000001600ffffff000000010000010f00000363fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000003d00000363000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d0065010000000000000780000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000005220000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: true
Width: 1920
X: 0
Y: 27
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
<launch>

<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/20210315_1915.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>

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

Please sign in to comment.