Skip to content

Commit 9220b1c

Browse files
committed
[shape_msgs] New Bounds Msg
Signed-off-by: David V. Lu <[email protected]>
1 parent 3631ac9 commit 9220b1c

File tree

2 files changed

+26
-0
lines changed

2 files changed

+26
-0
lines changed

shape_msgs/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@ find_package(geometry_msgs REQUIRED)
1616
find_package(rosidl_default_generators REQUIRED)
1717

1818
set(msg_files
19+
"msg/Bounds.msg"
1920
"msg/Mesh.msg"
2021
"msg/MeshTriangle.msg"
2122
"msg/Plane.msg"

shape_msgs/msg/Bounds.msg

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
# Bounds which are useful in several contexts, e.g. to avoid spawning with other object overlap,
2+
# or parking in a spot that is too small.
3+
# Certain goals or points might be valid for a small object, but not suitable for a large one,
4+
# or a differently shaped one.
5+
# Bounds can be also checked to ensure certain scenario conditions are met.
6+
# For entities, these limits are relative to entity's canonical link transform, following ROS rep-103 convention.
7+
8+
# As bounds are optional in most interfaces, TYPE_EMPTY signifies empty bounds, to be understood as "unbounded".
9+
# Otherwise, the fields are expected to define a valid volume.
10+
# For spawning with a named pose, you should check whether the entity simulation model fits within the bounds
11+
# before calling SpawnEntity, to avoid overlaps and unstable behavior.
12+
13+
# bounds type
14+
uint8 TYPE_EMPTY = 0 # No bounds. The points vector will be empty.
15+
uint8 TYPE_BOX = 1 # Axis-aligned bounding box, points field should have two values,
16+
# which are upper right and lower left corners of the box.
17+
uint8 TYPE_CONVEX_HULL = 2 # Points define a convex hull (at least 3 non-collinear points).
18+
uint8 TYPE_SPHERE = 3 # A sphere with center and radius. First element of points vector is the center.
19+
# The x field of the second point of the vector is the radius (y and z are ignored).
20+
21+
22+
uint8 type
23+
geometry_msgs/Vector3[] points # Points defining the bounded area. Check type field to determine semantics.
24+
# Valid sizes are zero (no bounds), 2 (sphere or box, depending on type field),
25+
# and 3 or more (convex hull).

0 commit comments

Comments
 (0)