Skip to content

Commit

Permalink
Flattened message structure and made use of CategoryDistribution
Browse files Browse the repository at this point in the history
  • Loading branch information
Kukanani committed May 10, 2017
1 parent 2a1682f commit d3419fe
Show file tree
Hide file tree
Showing 7 changed files with 27 additions and 38 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -48,14 +48,14 @@ find_package(catkin REQUIRED COMPONENTS
# Generate messages in the 'msg' folder
add_message_files(
FILES
CategoryDistribution.msg
ClassifierInfo.msg
Classification2D.msg
Classification3D.msg
ClassifierInfo.msg
Detection2D.msg
Detection2DArray.msg
Detection3D.msg
Detection3DArray.msg
BoundingBox3D.msg
)

## Generate services in the 'srv' folder
Expand Down
3 changes: 3 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@ primary types of classifiers:
2. **Detectors**, which identify class probabilities as well as the poses of
those classes given a sensor input

The class probabilities are stored with a CategoryDistribution message, which
is essentially a map from integer IDs to floats.

Message types exist separately for 2D (using `sensor_msgs/Image`) and 3D (using
`sensor_msgs\PointCloud2`). The metadata that is stored for each object is
application-specific, and so this package places very few constraints on the
Expand Down
5 changes: 0 additions & 5 deletions msg/BoundingBox3D.msg

This file was deleted.

15 changes: 4 additions & 11 deletions msg/Classification2D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,9 @@

Header header

# IDs of elements detected with any nonzero probability.
# Does not have to include all possible object
# ids, the scores for any ids not listed are assumed to be 0.
int64[] ids

# The probabilities or confidence values of the detected elements. Must be
# sorted to correspond with the ids field, above
# 0-1, should sum to 1 or less, must be the same length as ids
float64[] scores
# Class probabilities
CategoryDistribution results

# The 2D data that generated these results (i.e. region proposal cropped out of
# the image). Not required for all detectors, so it may be empty.
sensor_msgs/Image source
# the image). Not required for all use cases, so it may be empty.
sensor_msgs/Image source_img
15 changes: 4 additions & 11 deletions msg/Classification3D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,16 +5,9 @@

Header header

# IDs of elements detected with any nonzero probability.
# Does not have to include all possible object
# ids, the scores for any ids not listed are assumed to be 0.
int64[] ids
# Class probabilities
CategoryDistribution results

# The probabilities or confidence values of the detected elements. Must be
# sorted to correspond with the ids field, above
# 0-1, should sum to 1 or less, must be the same length as ids
float64[] scores

# The 2D data that generated these results (i.e. region proposal cropped out of
# The 3D data that generated these results (i.e. region proposal cropped out of
# the image). Not required for all detectors, so it may be empty.
sensor_msgs/PointCloud2 source
sensor_msgs/PointCloud2 source_cloud
12 changes: 7 additions & 5 deletions msg/Detection2D.msg
Original file line number Diff line number Diff line change
@@ -1,16 +1,18 @@
# Defines a 2D detection result.
# Defines a 3D detection result.
#
# This extends a basic 2D classification by including position information,
# This extends a basic 3D classification by including position information,
# allowing a classification result for a specific position in an image to
# to be located in the larger image.

# non-geometric results of detection.
vision_msgs/Classification2D classification
Header header

# Class probabilities
CategoryDistribution results

# The x/y position and (optional) rotation of the bounding box center.
geometry_msgs/Pose2D pose

# (Optional) The size of the bounding box surrounding the object. The center of
# the bounding box is the position of the detection point.
# the bounding box is the position of the pose.
float32 bbox_size_x
float32 bbox_size_y
11 changes: 7 additions & 4 deletions msg/Detection3D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,10 @@
# allowing a classification result for a specific position in an image to
# to be located in the larger image.

# non-geometric class probability.
vision_msgs/Classification3D classification
Header header

# Class probabilities
CategoryDistribution results

# The element's pose. This pose should be
# defined as the pose of some fixed reference point on the object, such as the
Expand All @@ -14,5 +16,6 @@ vision_msgs/Classification3D classification
# setting classification.header.frame_id.
geometry_msgs/Pose pose

# (Optional) The bounding box in 3D space that surrounds the object.
vision_msgs/BoundingBox3D bbox
# The 3D data that generated these results (i.e. region proposal cropped out of
# the image). Not required for all detectors, so it may be empty.
sensor_msgs/PointCloud2 source_cloud

0 comments on commit d3419fe

Please sign in to comment.