API review

Proposer: Ioan Sucan

Present at review:

  • Dave Hershberger
  • John Hsu
  • Tully Foote
  • Chad Rockey

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?

  • Ioan: That should be in a separate message, yes. Perhaps we can have ShapeWithPose.msg like so:

Shape shape
geometry_msgs/PoseStamped pose
  • Dave: ShapeWithPose should not be like that, the standard is that the Header portion should really be the first entry. That helps various filtering code work nicer. So like this:

Header header
Shape shape
geometry_msgs/Pose pose
  • Ioan: agreed [I think we will not include shapes with pose for now]

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.

  • Ioan: Yes, it would be. I will change that. [DONE]

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.

  • Ioan: True. However, it makes my life much easier to specify the equation of the plane. Initially planes were specified in a separate message, to avoid this problem (a StaticShape); but then we had a message that was not much different and could specify only one type of shape. I am not sure how to handle this properly, but in order to avoid having code that turns poses into plane parameterisations in various places, I would prefer keeping the equation of the plane in.

    • Dave: You don't need to keep the code "in various places", just put it in a library. In any case, don't the planes with equations need to be rotated and translated anyway?

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.

  • Ioan: True. But the intention is to specify primitive shapes that we could use for efficient collision detection. There could be some additional message that represents a scaled Shape, where a Shape + xyz scale could be defined?

Shape shape
geometry_msgs/Vector3 scale
  • Dave: If the point is efficient collision detection, why not just use the mesh description only? Leave out everything else, just use triangles and vertices. That way you don't need *any* special-case code. As it is, you must have 15 different collision functions (box-on-box, box-on-sphere, box-on-mesh, cone-on-plane, etc). If you are using meshes for the box, sphere, etc primitives internally, why not just use them all around? If you want to use the box, sphere, etc as a shorthand externally but you actually use meshes internally, then the XYZ scaling of the shapes is easy, so go with my original suggestion.

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
  • Ioan: Actually, it is important that we have all pairs of collision checking. Representing a sphere or a cylinder as a mesh is more computationally intensive. Having a general scale or only meshes for collision checking is problematic for efficiency.
    • Dave: Ah, OK, this is important information. By proposing to put something called "Shape" into common_msgs, you make us think you are describing something super general and basic, which most packages should use to describe shapes. In that case I think the message specification should be very clean and simple, like a basic Lego brick. However if the message is an expression of an internal component of collision checking, it should not be in common_msgs, and it should not be called "Shape". Why not leave it in arm_navigation_msgs? Or make a new stack/package called "collision_msgs"? Call the message "CollisionShape".

    • The name and location convey important information about the intent and applicability of the message. If it is tailored specifically to collision checking, then name it and place it accordingly.
      • Ioan: I added GeometricPrimitive & Mesh, as possible types of Shape. This way, I can use GeometricPrimitive where needed and I added scale for Shape, making it a more general shape. Is this satisfactory?

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

  • Ioan: I think this may be better represented as a thin box?

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.

  • Ioan: I think we should leave this out for now.

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.

  • Ioan: This message existed for more than a year now without any changes, and has lived in arm_navigation_msgs. Rather than putting it in moveit_msgs, it makes sense to have it in a common location where others (object recognition, grasping) can easily depend on it.
    • Dave: it is easy to depend on it anywhere, just specify the stack name. My point is that changing common_msgs ripples out to affect everything else which depends on common_msgs. If it lives in its own stack, and you change it, it only affects the few stacks which actually depend on the Shape message.

Cheers, Dave

John Hsu

  • What are the use cases?
    • Ioan: I put a bit of extra description below.
  • For generality and from the point of view of collision checking, I thought I should mention compound shapes and convex meshes.
    • Ioan: My only concern here is that it is possible for a mesh to be specified as being convex, when in fact, it is not. We have not needed this so far in the collision checking -- we compute the convex hull when needed, and that needs to be done only once.

Adolfo Rodríguez Tsouroukdissian

  • +1 to having a more compact and general primitive representation that uses a scaling vector instead of dimensions.
    • Ioan: Done.
  • The mesh specification seems sufficient for the current needs of collision checking and other geometric operations. In the long run, it should allow for a more general specification including material properties. This is especially so if the message ends up in a core location like common_msgs. The specification could parallel the rviz mesh marker, that specifies a resource location, eg. "package://path/to/resource.dae".

Tully Foote

  • I'm a little concerned by the merging of meshes and primitives. They have completely non-overlapping fields which suggests to me that they should be a separate message.
  • Why are you using an unstructured datatype for the triangle indicies?
    • Triangle:
      uint16 vertex_index_1
      uint16 vertex_index_2
      uint16 vertex_index_3

Triangles[] triangles
  • This change sounds good to me.
  • Also I feel the int32 should be a uint32 as it's an index value.
    • Ioan: Makes sense. Will change. [Done]
  • Also do we want full 64 bit resolution on the points in the mesh? This seems like a potentially high data volume like point clouds and the 50% reduction in transmission costs would be helpful. And as long as you're not drawing meshes millions of meters on a side you won't loose precision.
    • True. However, mesh data is not sent at such high frequency as point clouds, and I would prefer sticking to 64 bit precision.
      • (Tully) That's fine then.
  • I think we're getting close. This is much cleaner. I'm still a little hesitant about the flag to switch between them, but I understand the argument for a single flow that doesn't need to be syncronized. However I don't completely understand the use case of subscribing directly to this message when it's completely standalone, not forming an element of another message. And if it's forming an element of another message that other message would eliminate the need for the simpler data flow.
    • Ioan: I expect this message would usually be part of other messages. I am not sure I follow your suggestion though.
      • Tully: I guess what I'm asking is if this is going to be an element in other compound messages. Providing the Shape message which is just a flag and a Primative or Mesh. Code for processing the meshes and primatives is necessarily different, thus by using a flag and the two datatypes it requires all code to test the type and branch execution based on the type. Unless there's a library built around that specific datatype, it seems like it might be too specific to promote into common_msgs.
        • Chad: I agree, this might be too specific. If used generally, I'm concerned that users may unknowingly expect these to recreate specific tools such as visualization markers and URDF.
          • Ioan: message Shape removed from latest common_msgs
  • A few other small thoughts on naming.
    • The Triangle message should likely be scoped to MeshTriangle as it's not useful without the Mesh.vertices next to it.

      • Makes sense. Done.
    • I know I proposed the vertex_index_1/2/3 but I think that it is on the more verbose than necessary end, especially as the datatype and some good comments will make it clear that it is indices. So something simpler like "uint32[3] vertex_indices" as the payload of the triangle. It'll make coding much simpler and they definitely don't need to be named. But we still keep the encapsulation.
      • Ioan: Makes sense. Done

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.

  • Tully: That's a good point. Having the x,y,z scale is easier to comprehend than arbitrary dimentions. There's a question whether we should support non-symmetrical primatives, (since most of the primatives are fully defined by 1 or two dimentions. ) The only one which needs more than 3 dimentions at the moment is the plane definition. However the plane is already an odd duck, as non of the other shapes support orientation, and the plane in it's current form also supports offsets. For example a similar datatype is a line, would we want it to have orientation and offsets too?
  • Dave: Here is a version which would keep consistent meanings for "dimension" components as much as possible, but still leave your plane parameters in place:

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.

  • Ioan: The suggestions Dave makes are fine with me. Plane is not really a geometric primitive, and should be out anyway. Changing how dimensions[] is represented is fine as well. What do you think of Plane moving to geometry_msgs though? As it was pointed out, it does have pose information as opposed to the rest of the shapes. And then we take it out of Shape as well. l

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.

  • Ioan: I see the confusion. URDF is completely separate from ROS messages. Although it defines shapes, it does not enforce how those shapes should be represented. The added messages (SolidPrimitive & Mesh & Plane) are used to transport representations of shapes on ROS topics. We use these to transport information from grasping to planning for instance, from object recognition to planning, from loaded robot models to collision checking. The messages should be useful to represent shapes in a manner that is compatible with various components of ROS, among which collision detection. However, these messages are not specific to planning or to collision detection. I see these messages as a missing link, since visual markers do exist already, but the semantic counterpart if you will, did not. On a related note: the additional shape_tools package can be used to help converting some shapes to markers.

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

  • As the discussion proceded, updates were applied. As of version 1.8.10 of common_msgs, all requested comments have been addressed.


Wiki: common_msgs/Reviews/2012-06-12_API_Review (last edited 2012-06-18 20:33:58 by Ioan Sucan)