Skip to content

Commit

Permalink
Merge pull request #1993 from wkentaro/evaluate_voxel_segmentation
Browse files Browse the repository at this point in the history
Evaluate box/voxel segmentation with gt. box
  • Loading branch information
k-okada committed Feb 7, 2017
2 parents 9c7bd73 + 07905a4 commit 5ee8d5b
Show file tree
Hide file tree
Showing 15 changed files with 564 additions and 6 deletions.
2 changes: 2 additions & 0 deletions jsk_pcl_ros_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -316,6 +316,8 @@ if (CATKIN_ENABLE_TESTING)
add_rostest(test/pointcloud_to_point_indices.test)
# because of unreleased jsk_tools/test_topic_published.py on hydro
add_rostest(test/bounding_box_array_to_bounding_box.test)
add_rostest(test/evaluate_box_segmentation_by_gt_box.test)
add_rostest(test/evaluate_voxel_segmentation_by_gt_box.test)
add_rostest(test/pointcloud_to_mask_image.test)
add_rostest(test/polygon_array_unwrapper.test)
add_rostest(test/subtract_point_indices.test)
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,121 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 565
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.03
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: jsk_rviz_plugin/BoundingBoxArray
Enabled: true
Name: BoundingBoxArray
Topic: /bounding_box_array_publisher/output
Unreliable: false
Value: true
alpha: 1
color: 25; 255; 0
coloring: Auto
line width: 0.005
only edge: true
show coords: false
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: map
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
Topic: /initialpose
- 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: 3.11077
Enable Stereo Rendering:
Stereo Eye Separation: 0.06
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 1.5598
Y: -0.652339
Z: 0.442043
Name: Current View
Near Clip Distance: 0.01
Pitch: 0.550398
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 2.3204
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a000002c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002c4000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002c4000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002f600fffffffb0000000800540069006d0065010000000000000450000000000000000000000340000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 40
Y: 40
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 565
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.588679
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: false
Line Style:
Line Width: 0.03
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: false
- Class: rviz/MarkerArray
Enabled: true
Marker Topic: /octree_voxel_grid/output_marker_array
Name: MarkerArray
Namespaces:
"": true
Queue Size: 100
Value: true
- Class: jsk_rviz_plugin/BoundingBox
Enabled: true
Name: BoundingBox
Topic: /boxes_to_gt_box/output
Unreliable: false
Value: true
alpha: 0.8
color: 25; 255; 0
coloring: Flat color
line width: 0.005
only edge: true
show coords: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: map
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
Topic: /initialpose
- 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: 1.13202
Enable Stereo Rendering:
Stereo Eye Separation: 0.06
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0.0647113
Y: 0.305025
Z: -0.28407
Name: Current View
Near Clip Distance: 0.01
Pitch: 1.3548
Target Frame: <Fixed Frame>
Value: Orbit (rviz)
Yaw: 4.70859
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016a000002c4fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c0061007900730100000028000002c4000000dd00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002c4fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002c4000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002f600fffffffb0000000800540069006d0065010000000000000450000000000000000000000340000002c400000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: -10
Y: 14
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
<launch>

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

<node name="bounding_box_array_publisher"
pkg="jsk_recognition_utils" type="bounding_box_array_publisher.py">
<rosparam>
rate: 10
frame_id: /map
boxes:
- dimension: [0.09, 0.13, 0.15]
orientation: [0.0, 0.0, 0.0, 1.0]
position: [1.3860276937484741, -0.3705306053161621, 0.5474169254302979]
- dimension: [0.15, 0.09, 0.13]
orientation: [0, 0, 0, 1]
position: [1.4170238971710205, -0.3371482789516449, 0.5605951547622681]
</rosparam>
</node>
<group if="$(arg gui)">
<node name="rviz"
pkg="rviz" type="rviz"
args="-d $(find jsk_pcl_ros_utils)/sample/config/sample_evaluate_box_segmentation_by_gt_box.rviz">
</node>
</group>

<node name="boxes_to_gt_box"
pkg="jsk_pcl_ros_utils" type="bounding_box_array_to_bounding_box">
<remap from="~input" to="bounding_box_array_publisher/output" />
<rosparam>
index: 0
</rosparam>
</node>
<node name="boxes_to_box"
pkg="jsk_pcl_ros_utils" type="bounding_box_array_to_bounding_box">
<remap from="~input" to="bounding_box_array_publisher/output" />
<rosparam>
index: 1
</rosparam>
</node>

<node name="evaluate_box_segmentation_by_gt_box"
pkg="jsk_pcl_ros_utils" type="evaluate_box_segmentation_by_gt_box.py">
<remap from="~input/box_gt" to="boxes_to_gt_box/output" />
<remap from="~input/box" to="boxes_to_box/output" />
</node>

</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
<launch>

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

<param name="/use_sim_time" value="true" />
<node name="play"
pkg="rosbag" type="play"
args="$(find jsk_pcl_ros_utils)/sample/data/bunny_marker_array.bag --clock --loop">
</node>

<node name="bounding_box_array_publisher"
pkg="jsk_recognition_utils" type="bounding_box_array_publisher.py">
<rosparam>
rate: 10
frame_id: /map
boxes:
- dimension: [0.15, 0.14, 0.11]
orientation: [0.0, 0.0, 0.0, 1.0]
position: [-0.025551795959472656, 0.11148339509963989, 0.01671653985977173]
</rosparam>
</node>

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

<node name="boxes_to_gt_box"
pkg="jsk_pcl_ros_utils" type="bounding_box_array_to_bounding_box">
<remap from="~input" to="bounding_box_array_publisher/output" />
<rosparam>
index: 0
</rosparam>
</node>

<node name="evaluate_voxel_segmentation_by_gt_box"
pkg="jsk_pcl_ros_utils" type="evaluate_voxel_segmentation_by_gt_box.py">
<remap from="~input/box_gt" to="boxes_to_gt_box/output" />
<remap from="~input/markers" to="/octree_voxel_grid/output_marker_array" />
</node>

</launch>
43 changes: 43 additions & 0 deletions jsk_pcl_ros_utils/scripts/evaluate_box_segmentation_by_gt_box.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
#!/usr/bin/env python

from jsk_recognition_msgs.msg import Accuracy
from jsk_recognition_msgs.msg import BoundingBox
import jsk_recognition_utils
import rospy
from jsk_topic_tools import ConnectionBasedTransport


class EvaluateBoxSegmentationByGTBox(ConnectionBasedTransport):

def __init__(self):
super(EvaluateBoxSegmentationByGTBox, self).__init__()
self.box_gt = None
self.pub = self.advertise('~output', Accuracy, queue_size=1)
self.sub_box_gt = rospy.Subscriber(
'~input/box_gt', BoundingBox, self._cb_box_gt)

def subscribe(self):
self.sub_voxels = rospy.Subscriber(
'~input/box', BoundingBox, self._cb_box)

def unsubscribe(self):
self.sub_voxels.unregister()

def _cb_box_gt(self, box_msg):
self.box_gt = jsk_recognition_utils.bounding_box_msg_to_aabb(box_msg)

def _cb_box(self, box_msg):
if self.box_gt is None:
rospy.logwarn('GT. box is not set, skipping.')
return
box = jsk_recognition_utils.bounding_box_msg_to_aabb(box_msg)
iu = jsk_recognition_utils.get_overlap_of_aabb(self.box_gt, box)

out_msg = Accuracy(header=box_msg.header, accuracy=iu)
self.pub.publish(out_msg)


if __name__ == '__main__':
rospy.init_node('evaluate_box_segmentation_by_gt_box')
EvaluateBoxSegmentationByGTBox()
rospy.spin()
Loading

0 comments on commit 5ee8d5b

Please sign in to comment.