[Documentation] [TitleIndex] [WordIndex

API review

Proposer: Ioan Sucan

Present at review:

Question / concerns / comments

Enter your thoughts on the API and any questions / concerns you have here. Please sign your name. Anything you want to address in the API review should be marked down here before the start of the meeting.

Dave Hershberger

How will the position and orientation of one of these shapes be specified? Is that in a separate message?

Shape shape
geometry_msgs/PoseStamped pose

Header header
Shape shape
geometry_msgs/Pose pose

It seems to me that it would be more consistent to have the origin of a cone be the center of the line between the tip of the cone and the center of the base.

It seems to me that the PLANE type does not need any dimensions. Just declare that it is an XY plane (for example) and then however you position and orient other shapes, you do the same for the PLANE and you're done.

Another thing you could do is instead of having different meanings for dimesions[] elements for each type, you could just have a "geometry_msgs/Vector3 scale" element which applies to all types. Then you can describe ellipsoids, elliptical cylinders, elliptical cones, all box sizes, and you can scale your meshes.

Shape shape
geometry_msgs/Vector3 scale

So then the message would look like this:

# When scale = (1,1,1), the box, sphere, cylinder, and cone shapes all have length,
# width, and height of 1.  The origin of the predefined shapes is the center of
# each.
uint16 BOX=1
uint16 SPHERE=2
uint16 CYLINDER=3 # Z is axis of rotation
uint16 PLANE=4    # XY plane
uint16 CONE=5     # Z is axis of rotation, origin is halfway along the height.
uint16 MESH=6

uint16 type

# All shapes can be scaled in X, Y, and Z independently.
geometry_msgs/Vector3 scale

# list of triangles; triangle k is defined by the vertices located
# at indices triangles[3k], triangles[3k+1], triangles[3k+2]
int32[] triangles
geometry_msgs/Point[] vertices

It could even be useful to maintain scale info for the plane, for instance to express a table size.

Is surface treatment totally out of scope for this message? Color, image textures, etc? For anything other than a solid color, it might be difficult to add on as a second or surrounding message.

Finally, is it important to add this to common_msgs? Why not a new stack? Seems like common_msgs should have more well-proven messages which are unlikely to change in future.

Cheers, Dave

John Hsu

Adolfo Rodríguez Tsouroukdissian

Tully Foote

Triangles[] triangles

Dave Hershberger again

The latest version with Shape having x,y,z scale and containing either a GeometricPrimitive or Mesh does not strike me as cleaner than the first version.

My suggestion to include a "scale" vector was to replace the "dimensions" array which means different things for different types. Now you have both, which seems a shame. It wasn't that I saw a big need for object scaling, it was that I wanted, as much as possible, for each field to mean the same thing across all uses of the message. If you really require the "dimensions" array with its collection of different meanings, then leave out the scale vector as far as I'm concerned.

Shape:

uint8 PRIMITIVE=0
uint8 PLANE=1
uint8 MESH=2

uint8 type

GeometricPrimitive primitive
Plane plane
Mesh mesh

Plane:

float64 a
float64 b
float64 c
float64 d

Mesh: Mesh has only vertices and indices, however you want to define them, but no scale.

GeometricPrimitive:

uint8 BOX=0
uint8 CYLINDER=1
uint8 SPHERE=2
uint8 CONE=3

uint8 type

Vector3 dimensions

# For the BOX type, the X, Y, and Z dimensions are the length of the corresponding
# sides of the box.
#
# For the CYLINDER and CONE types, the center line is oriented along the Z axis.
# Therefore the Z component of dimensions gives the height of the cone or cylinder.
# The X component of dimensions gives the diameter of the base of the cone or
# cylinder.  Cone and cylinder primitives are defined to be circular, so the
# Y component is ignored.
#
# For the SPHERE type, only the X component is used, and it gives the diameter of
# the sphere.
#
# All shapes are defined to have their bounding boxes centered around 0,0,0.

This way, the sub-components of "dimensions" are used consistently when they are relevant. For example: for all primitives, the extents of the shape in the X dimension go from -0.5x to +0.5x, where "x" is dimensions.x. Similarly, for box, cylinder, and cone, the extents in the Z dimension go from -0.5z to +0.5z.

If you wanted to get a quick bounding box for a primitive, you could just do this:

switch( prim.type ) {
  case prim.SPHERE:
    prim.dimensions.z = prim.dimensions.x;
    // "break" intentionally left out
  case prim.CYLINDER:
  case prim.CONE:
    prim.dimensions.y = prim.dimensions.x;
    // "break" intentionally left out
}

Then prim.dimensions.x, y, and z are the lengths of the sides of the bounding box of the primitive.

If it were OK for the shapes to be scaled non-uniformly (to get ellipsoids etc), you wouldn't even need that bit of code.

The definition you have now has dimension array entries changing which axis they correspond to, and changing between being a radius or a diameter when the type changes. Plus of course changing from a size description to being a coefficient in the equation of a plane.

For reference, here is the current (as far as I can tell) definition of !arm_navigation_msgs/CollisionObject:

[arm_navigation_msgs/CollisionObject]:
std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
string id
float32 padding
arm_navigation_msgs/CollisionObjectOperation operation
  byte ADD=0
  byte REMOVE=1
  byte DETACH_AND_ADD_AS_OBJECT=2
  byte ATTACH_AND_REMOVE_AS_OBJECT=3
  byte operation
arm_navigation_msgs/Shape[] shapes
  byte SPHERE=0
  byte BOX=1
  byte CYLINDER=2
  byte MESH=3
  byte type
  float64[] dimensions
  int32[] triangles
  geometry_msgs/Point[] vertices
    float64 x
    float64 y
    float64 z
geometry_msgs/Pose[] poses
  geometry_msgs/Point position
    float64 x
    float64 y
    float64 z
  geometry_msgs/Quaternion orientation
    float64 x
    float64 y
    float64 z
    float64 w

It looks to me like every Shape has a corresponding Pose, which should mean the definition of a Plane does not need any parameters, it can just be defined to be an XY plane and the position and orientation are taken from its Pose.

Chad Rockey

If these are added to common_msgs, I think the purpose of the messages will need to be very clear to the end users. Many new users are going to confuse this with URDF, visualization markers, and geometry_msgs. (OK, I'm one of those new users confused with this and URDF).

URDF contains separate collision geometries, is this isolating the collision checks from URDF by converting the specific collision to separate shape boundaries and formatting them into a request? My understanding is that these messages are the abstracted API to the collision checking system so that it doesn't have to understand the model and environment states directly. This seems like a reasonable request as long as we are fine that some applications will want to skip the URDF component and jump into the API at this level.

Meeting agenda

We would like to add a representation of shapes to common_msgs. This is really just a representation of shapes without poses, to describe robot links for collision checking for example, after they are loaded from URDF. Addition of poses can be done in a separate message.

The code is available now at:

https://code.ros.org/svn/ros-pkg/stacks/common_msgs/trunk/shape_msgs

For convenience, here is the definition of the included messages: SolidPrimitive.msg

# Define box, sphere, cylinder, cone 

uint16 BOX=1
uint16 SPHERE=2
uint16 CYLINDER=3
uint16 CONE=4

uint16 type

geometry_msgs/Vector3 dimensions

# For the BOX type, the X, Y, and Z dimensions are the length of the corresponding
# sides of the box.
#
# For the CYLINDER and CONE types, the center line is oriented along the Z axis.
# Therefore the Z component of dimensions gives the height of the cone or cylinder.
# The X component of dimensions gives the diameter of the base of the cone or
# cylinder.  Cone and cylinder primitives are defined to be circular, so the
# Y component is ignored. The tip of the cone is pointing up, along +Z axis.
#
# For the SPHERE type, only the X component is used, and it gives the diameter of
# the sphere.
#
# All shapes are defined to have their bounding boxes centered around 0,0,0.

Plane.msg

# Representation of a plane, using the plane equation ax + by + cz + d = 0

# a := coef[0]
# b := coef[1]
# c := coef[2]
# d := coef[3]

float64[4] coef

Here is Mesh.msg

# Definition of a mesh

# list of triangles; the index values refer to positions in vertices[]
MeshTriangle[] triangles

# the actual vertices that make up the mesh
geometry_msgs/Point[] vertices

and here is MeshTriangle.msg

# Definition of a triangle's vertices
uint32[3] vertex_indices

Please let me know if you have any comments or suggestions of improving the definition of this message.

Conclusion



2024-02-24 12:30