Skip to content

Commit

Permalink
Merge branch 'kinetic-devel'
Browse files Browse the repository at this point in the history
  • Loading branch information
Kukanani committed Oct 4, 2019
2 parents a31008d + 8e2ed08 commit 70c7701
Show file tree
Hide file tree
Showing 6 changed files with 29 additions and 12 deletions.
8 changes: 8 additions & 0 deletions msg/Detection2D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -15,3 +15,11 @@ BoundingBox2D bbox
# The 2D data that generated these results (i.e. region proposal cropped out of
# the image). Not required for all use cases, so it may be empty.
sensor_msgs/Image source_img

# If true, this message contains object tracking information.
bool is_tracking

# ID used for consistency across multiple detection messages. This value will
# likely differ from the id field set in each individual ObjectHypothesis.
# If you set this field, be sure to also set is_tracking to True.
string tracking_id
8 changes: 8 additions & 0 deletions msg/Detection3D.msg
Original file line number Diff line number Diff line change
Expand Up @@ -17,3 +17,11 @@ BoundingBox3D bbox
# the image). This information is not required for all detectors, so it may
# be empty.
sensor_msgs/PointCloud2 source_cloud

# If this message was tracking result, this field set true.
bool is_tracking

# ID used for consistency across multiple detection messages. This value will
# likely differ from the id field set in each individual ObjectHypothesis.
# If you set this field, be sure to also set is_tracking to True.
string tracking_id
8 changes: 4 additions & 4 deletions msg/ObjectHypothesis.msg
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
# An object hypothesis that contains no position information.

# The unique numeric ID of object detected. To get additional information about
# this ID, such as its human-readable name, listeners should perform a lookup
# in a metadata database. See vision_msgs/VisionInfo.msg for more detail.
int64 id
# The unique ID of the object class. To get additional information about
# this ID, such as its human-readable class name, listeners should perform a
# lookup in a metadata database. See vision_msgs/VisionInfo.msg for more detail.
string id

# The probability or confidence value of the detected object. By convention,
# this value should lie in the range [0-1].
Expand Down
10 changes: 5 additions & 5 deletions msg/ObjectHypothesisWithPose.msg
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
# An object hypothesis that contains position information.

# The unique numeric ID of object detected. To get additional information about
# this ID, such as its human-readable name, listeners should perform a lookup
# in a metadata database. See vision_msgs/VisionInfo.msg for more detail.
int64 id
# The unique ID of the object class. To get additional information about
# this ID, such as its human-readable class name, listeners should perform a
# lookup in a metadata database. See vision_msgs/VisionInfo.msg for more detail.
string id

# The probability or confidence value of the detected object. By convention,
# this value should lie in the range [0-1].
Expand All @@ -17,4 +17,4 @@ float64 score
# parent messages.
# Also note that different classes predicted for the same input data may have
# different predicted 6D poses.
geometry_msgs/PoseWithCovariance pose
geometry_msgs/PoseWithCovariance pose
4 changes: 2 additions & 2 deletions msg/VisionInfo.msg
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ string method
# Location where the metadata database is stored. The recommended location is
# as an XML string on the ROS parameter server, but the exact implementation
# and information is left up to the user.
# The database should store information attached to numeric ids. Each
# numeric id should map to an atomic, visually recognizable element. This
# The database should store information attached to class ids. Each
# class id should map to an atomic, visually recognizable element. This
# definition is intentionally vague to allow extreme flexibility. The
# elements could be classes in a pixel segmentation algorithm, object classes
# in a detector, different people's faces in a face detection algorithm, etc.
Expand Down
3 changes: 2 additions & 1 deletion test/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
include_directories(${catkin_INCLUDE_DIRS})
catkin_add_gtest(vision_msgs_test main.cpp)
catkin_add_gtest(vision_msgs_test main.cpp)
add_dependencies(vision_msgs_test ${${PROJECT_NAME}_EXPORTED_TARGETS})

0 comments on commit 70c7701

Please sign in to comment.