forked from ros-perception/vision_msgs
-
Notifications
You must be signed in to change notification settings - Fork 1
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Fix BoundingBox2D build issues (ros-perception#7)
* Fixing float definition on BoundingBox2D to build * Cleaned up the comments for BoundingBox3D
- Loading branch information
Adam Allevato
authored
Jun 7, 2017
1 parent
642f211
commit 188aa70
Showing
2 changed files
with
12 additions
and
8 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,10 +1,13 @@ | ||
# Note: This message *DOES NOT* plan to move to geometry_msgs in the final | ||
# implementation, because it uses pixels, not meters. | ||
# A 2D bounding box that can be rotated about its center. | ||
# All dimensions are in pixels, but represented using floating-point | ||
# values to allow sub-pixel precision. If an exact pixel crop is required | ||
# for a rotated bounding box, it can be calculated using Bresenham's line | ||
# algorithm. | ||
|
||
# The 2D position (in pixels) and orientation of the bounding box center. | ||
geometry_msgs/Pose2D center | ||
|
||
# The size (in pixels) of the bounding box surrounding the object relative | ||
# to the pose of its center | ||
float size_x | ||
float size_y | ||
# to the pose of its center. | ||
float64 size_x | ||
float64 size_y |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,8 +1,9 @@ | ||
# Note: This message plans to move to geometry_msgs in the final implementation. | ||
# A 3D bounding box that can be positioned and rotated about its center (6 DOF) | ||
# Dimensions of this box are in meters, and as such, it may be migrated to | ||
# another package, such as geometry_msgs, in the future. | ||
|
||
# The 3D position and orientation of the bounding box center | ||
geometry_msgs/Pose center | ||
|
||
# The size of the bounding box surrounding the object relative to the pose of | ||
# its center | ||
# The size of the bounding box, in meters, surrounding the object's center pose. | ||
geometry_msgs/Vector3 size |