API review

Proposer: Sachin Chitta

Present at review:

  • Sachin
  • Tully
  • Matei
  • Kaijen
  • Gil

Question / concerns / comments

  • This is a set of messages for kinematics computation. Please review these messages and let me know if there are things that should be specified but are missing.
  • Note that the service IKServiceWithCollision has changed but the Wiki documentation has not auto-updated yet. The new service:

# A service call to carry out an inverse kinematics computation 
# while checking collisions. 

# The inverse kinematics request
kinematics_msgs/IKRequest data

# The state of the robot - use this to specify positions for the rest of the joints on the robot
motion_planning_msgs/RobotState robot_state

# A set of ordered collision operations to determine the resultant collision matrix to use
motion_planning_msgs/OrderedCollisionOperations ordered_collision_operations

# Maximum allowed time for IK calculation
float64 timeout

---

# The returned solution 
# (in the same order as the list of joints specified in the IKRequest message)
float64[] solution

Gunter

Random thoughts - my apologies if they are confused or mis-informed:

  • The package seems focused on inverse kinematics. Should the package name reflect more of that? Kinematics is pretty general?
    • It is focused on inverse kinematics right now but there is no reason other kinematics related messages cannot be added in later. This review will not lock down the package to future additions.

  • In "WithCost", I have no idea how cost would be defined? In general, cost functions could contain lots of things. Why just a list of links?

    • You are right, the particular implementation was to get a collision cost for a set of links.

  • Why doesn't the plain service have a robot state? The request message contains the list of joint to solve, but how do you set the other joints?
    • The assumption is that all the information you need to compute the IK is within this message itself. The robot_state is intended for joints that are not part of the IK computation itself

  • Or is it helpful to explicitly define a starting frame? If not, I assume it's in a world frame and you would need the robot state to localize? Or, wait are you using the stamp frame in pose?? Documentation would help.
    • The starting frame is defined in the header of the message. The link_name defines the link that IK is being performed for while the frame_id in the header defines the frame in which the pose for that link is defined.

  • (In the plain service, w/o robot state), are you assuming all joints between the stamp frame and the tip frame? Can you leave some out?
    • Yes. There is no strictness in the message itself but the way the nodes are implemented, you have to provide starting positions for all the joints that may be used in the IK computation

  • Rather than naming "link_name" in the request, why not use a frame_id? Seems more consistent with the rest? Possible just a Pose, Base_frame_id, Tip_frame_id?
    • The term frame_id has been widely used throughout our stacks and an additional name with frame_id in it may lead to more confusion

  • I'd personally like not to have the Request message. Seems that is just to collect some items that are shared? But other shared items (timeout, robot state) are not collected? I'd rather just spell it out in the service call.
    • Its a base ik request - its all the information you would require just to compute IK if you had a pose in the root frame of the chain, you don't need a timeout, robot state for it.

  • In the fkin, how do you specify the base frame?
    • In the header

In general, it seems these are basically service requests for a pretty specialized code base = one service call for one algorithm? I'm a little worried that for general solvers, there may be other parameters (cost functions, tolerances, etc). So is it worth making this a package by itself, or just keep the service definitions with the code? And then, when we have multiple solvers and service calls we can see where the commonality lies?

  • These packages are supposed to be a starting API spec, not a complete and final API spec. They will evolve as we put in more use-cases but they seem to be sufficient for what we have done so far. Also, the requests themselves are universal, any custom configuration for individual solvers could be done through the ros parameter server.

Eric

  • IKServiceWithCosts - even after reading the discussion here, I don't understand what cost function this is minimizing. If it is a collision cost, it seems that a list of links is still underspecified (does this include self collision, self-collision between adjacent links, obstacle collision, etc.?)
  • May be out of scope for this discussion, but how do JointState and PoseState in motion_planning_msgs/RobotState interact? Is it valid to specify some joint positions and some poses?

  • What is the header in FKService used for? Does it specify what frame to use for the return value?
  • I'm worried that with the current approach we will start requiring a combinatorial number of service calls for IK with XXX and IK with yyy, and that this will become a maintenance nightmare. I'm especially worried about this together with the current naming, because once we have some other type of costs that we want to use, or once we want to add some new parameter to the cost function, it will become very unclear what the meaning of the different service calls are, and keeping the interfaces easy for people to understand may get harder and harder. One alternative would be to have service calls configured with those parameters before-hand, so that requests are all the same. We could do something like expand IKQuery to include a set of key-value pairs, so that it could flexibly represent many different IK algorithms into the future, but to keep the request itself simple and get rid of WithCollision, WithCost, etc. We could even do something like the PolledImage approach, where a user would ask for a service call that is configured the way they want it configured, that would dynamically create and advertise it, and then they could just call it without passing around lots of options.

Matei

  • suggest renaming IKQuery as it can be easily taken as meaning "an actual query to compute IK". How about IKInformationRequest, IKNodeInformationRequest, etc.
  • why do IKServiceWithCollision and IKServiceWithCost have a RobotState field, but IKService does not?

  • is there a default option, where if RobotState is empty, or default, the current state of the robot is used?

Meeting agenda

Conclusion

Package status change mark change manifest)

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

  • {X} Major issues that need to be resolved

  • /!\ Take out IKWithCost - DONE

  • /!\ Move service response into a separate message as well - response is minimal and contained within two messages - one for solution and other for error code

  • /!\ Add an enum for the IKService response - DONE

  • /!\ Change the name of the IKService call - GetPositionIK - DONE

  • /!\ Change the name of the IKQuery call - GetKinematicsEnvironmentInfo - DONE - GetKinematicSolverInfo

  • /!\ Change the name of the FKService call - GetPositionFK - DONE

  • /!\ Change IKRequest name to PositionIKRequest - DONE

  • /!\ Change IKRequest data to PositionIKRequest request - DONE

  • /!\ Change positions to seed_joint_positions in PositionIKRequest - DONE

  • /!\ Change link_name to ik_link_name - DONE

  • /!\ Change float64 timeout to ros::Duration timeout - DONE

  • /!\ Change float64[] solutions to motion_planning_msgs/JointState - DONE - RobotState

  • /!\ FKRequest -change joint positions to JointState - DONE

  • /!\ FKRequest should be for an array of links - DONE

  • /!\ change link_name - fk_link_names - DONE

  • /!\ return will be array of PoseStamped messages + array of strings + enum for errors - dONE

  • /!\ Change IKQuery.response to a message KinematicsEnvironmentInfo - DONE - KinematicSolverInfo


Wiki: kinematics_msgs/Reviews/2010-01-20_API_Review (last edited 2010-03-03 08:08:33 by SachinChitta)