API review

Proposer: Sachin

Present at review:

  • Eric
  • Matei
  • Kaijen
  • Gil
  • Tully

Question / concerns / comments

Sachin

  • Please review the messages in the API specification. The documentation is within the messages themselves. There are still questions regarding supporting multi-dof joints within this api.
  • The specification of orientation constraints will also be significantly simplified by taking out the constraint_region_pose specification and leaving in only the constraint_region_shape specification which will serve as a tolerance/constraint region centered at the goal orientation specified in the message.
  • The service GetDynamicMotionPlan will be removed

  • Two additional messages that have not been auto-updated yet are also up for review: [motion_planning_msgs/CollisionOperation]

string COLLISION_SET_ALL="all"
uint8 DISABLE=0
uint8 ENABLE=1
string object1
string object2
uint8 operation

and [motion_planning_msgs/OrderedCollisionOperations]

motion_planning_msgs/CollisionOperation[] collision_operations
  • Also review GetIKWithCollision and IKRequest (contains robot_state)

  • All uint8 that should be bools will be converted to bools.
  • New proposal for SplineTraj and SplineTrajSegment

    •   SplineTrajectory:
         Header header
         SplineTrajectorySegment[] segments
         string[] joint_names
        SplineTrajectorySegment:
         Spline[] splines
         Duration duration
        Spline:
          float64[] coefficients

Matei

  • JointPath

    • very similar to trajectory_msgs/JointTrajectory (which also contains velocities and accelerations)
    • what is the header used for?
  • JointState

    • it seems that by convention all messages here refer strictly to joint positions
      • is this OK? Is it possible that a motion planner might want to deal with velocities / accelerations as well?
      • if they remain like this, rename so that it is clear that they only refer to positions. The fact that they reside in motion_planning_msgs (as opposed to kinematic_msgs for example) obscures that. E.g. JointState -> JointPositionState

  • RobotState

    • just listing here the much-discussed problem of the default value for the robot state.
    • how does one specify "use the current state of the robot"?
  • JointConstraint

    • worried about the weight, which I think defaults to 0. If all weights are 0 is this handled graciously, or must the caller always set some reasonable weights?
    • should there be a JointConstraint with no weights, and then a WeightedJointConstraint message?

  • PositionConstraint

    • change field comment inside message file: "# The desired pose of the robot link" -> "The desired position of the robot link"

    • how do we specify "I want the link above this plane" (e.g. the table)?
  • OrientationConstraint

    • the "shape" of a constraint in {yaw, pitch, roll} space is a difficult concept, but we've discussed this before at length and might not have a better alternative
  • SimplePoseConstraint

    • what makes it "simple"?
    • why is it not a combination of a PositionConstraint and an OrientationConstraint?

    • what does tolerance specified as x,y,z mean for an orientation specified as a quaternion?
  • CollisionOperation

    • specifying "ALL" as a particular string inside of "objectx" is not ideal (even if the string is defined inside the message). Alternative would be adding two boolean flags, object1_all and object2_all
  • AcceptableContact

    • is this superseded to some degree by the new mechanism for enabling / disabling collisions?
  • FilterTrajectoryService

    • not documented

Meeting agenda

To be filled out by proposer based on comments gathered during API review period

Conclusion

Package status change mark change manifest)

  • /!\ Action items that need to be taken.

  • {X} Major issues that need to be resolved

  • /!\ Remove JointPath and instead use JointTrajectory everywhere.

  • /!\ Get rid of wraparound field in JointLimits, JointTrajectoryWithLimits is fine.

  • /!\ Use sensor_msgs/JointState, ask for field accelerations in there.

  • /!\ Add MultiDOFJointStates

    • :string frame_id :string child_frame_id :string joint_name - use groups to resolve this to "base_x_joint", etc. :Pose
  • /!\ Take out header from joint state message

  • /!\ Robot state should contain arrays of joint states and pose states

  • /!\ IK Request should contain robot state + ik link names

  • /!\ Joint constraints - take out header

  • /!\ Position constraints - take out position, add offset from link

  • /!\ Orientation constraints - 3 special cases, (a) fixed, (b) 1-dof around a world fixed axis (b) 1 dof around a gripper fixed axis, tolerances, quaternion, type, axis.

  • /!\ IKService - add robot state, IKWithCollisionService is ok

  • /!\ Acceptable contacts - specify as region names and then specify ordered collision operations on them

  • /!\ Take out pose state

  • /!\ Try not to use uint8 anywhere

  • /!\ GetMotionPlan service

    • Add ordered collision operations to it
    • Change acceptable contacts to be just named regions
    • Must return RobotTrajectory and RobotState

    • Return enum error code
    • remove errors
    • Add penetration depth information to ordered collisions


Wiki: motion_planning_msgs/Reviews/01-21-2010 API Review (last edited 2010-01-22 00:35:58 by TullyFoote)