API review

Proposer: Stuart Glaser

Present at review:

  • List reviewers

This review is to approve actions and messages moved from the pr2_controllers_msgs package. The messages have been moved in order to provide an interface to trajectory and head control that is not PR2 specific.

The review covers three messages/actions: the JointTolerance message, the FollowJointTrajectory action, and the PointHeadAction action, all described below.

  • JointTolerance message

string name
float64 position
float64 velocity
float64 acceleration
  • FollowJointTrajectory action (was JointTrajectory action)

trajectory_msgs/JointTrajectory trajectory
duration goal_time_tolerance
JointTolerance[] path_tolerance
JointTolerance[] goal_tolerance

---
int32 error_code
int32 SUCCESSFUL = 0
int32 INVALID_GOAL = -1
int32 INVALID_JOINTS = -2
int32 OLD_HEADER_TIMESTAMP = -3
int32 PATH_TOLERANCE_VIOLATED = -4
int32 GOAL_TOLERANCE_VIOLATED = -5

---
Header header
string[] joint_names
trajectory_msgs/JointTrajectoryPoint desired
trajectory_msgs/JointTrajectoryPoint actual
trajectory_msgs/JointTrajectoryPoint error
  • PointHeadAction action

geometry_msgs/PointStamped target
geometry_msgs/Vector3 pointing_axis
string pointing_frame
duration min_duration
float64 max_velocity
---
---

Question / concerns / comments

Wim

  • Tolerances need more documentation: does a tolerance x mean [-x, x] or [-x/2, x/2] or something else?

Sachin

  • JointTolerance message

    • what is expected behavior when tolerances are violated? What if this message is not filled out - what does 0 joint tolerance mean?
  • FollowJointTrajectory message

    • duration goal_time_tolerance - what does this parameter represent?
    • path and goal tolerance - what happens if some joint tolerances are not specified? What is the default tolerance for those joints? What if someone wants to specify position tolerances but not velocity or torque?
  • PointHeadAction action -

    • maybe rename the fields pointing_axis and pointing_frame to axis and frame (unless this will become a painful API change)
    • what does the min_duration parameter do?
    • what does the max_velocity parameter do?
    • what if these parameters are not filled out (i.e default to 0.0)?

Gil

  • Second the request for in message documentation - the one for tolerance is especially crucial
  • Do we have use cases for other kinds of trajectory tolerance. Or is this the only one?
  • Is there a sense of priority among tolerances? Is there a way to specify, for instance, that position has a very narrow tolerance but that the controller doesn't need to work very hard to achieve set velocities or accelerations?
  • Why the design choice to have a single set of priorities controlling the entire path and another one for the goal? I'm not sure how these interact.
  • If there's a goal time tolerance does it make sense to have a separate failure condition for that, or does that fall under GOAL_TOLERANCE_VIOLATED.
  • I'm ok with pointing_ in front of frame and axis, fwiw.

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


Wiki: control_msgs/Reviews/2011_01_06_API_Review (last edited 2011-01-07 21:34:31 by EGilJones)