As stated above, the problem that you are facing is a more general instance of a constrained motion planning problem than what descartes can express. Although not immediately helpful, recently an update has been pushed to OMPL [1] that introduces generic, geometrically constrained motion planning with sampling-based motion planners [2] (you can view a highlight reel of some of the available demos here at [3]). The code is available at [4].
This new framework allows for geometric constraints to be phrased as functions of a robot’s state, f(q)
, which are satisfied when f(q) = 0
. Your problem can be expressed as a geometric constraint on the 8-DoF system of the positioner and the end-effector. It could possibly look something like:
f(q) = SE3_Distance((desired position and normal vector on surface of the positioner), (pose of end-effector))
where SE3_Distance()
is some metric in SE(3). Unfortunately, right now there is no interface through ROS to access these new features (i.e., through MoveIt! or others), but a bespoke solution is possible. It would require creating a state space for your robot and a constraint, and then running your favorite motion planner on the constrained state space (for your case, probably an asymptotically-optimal one, optimizing for minimal end-effector movement).
Feel free to let me know if you are interested in pursuing this route or if you have any trouble using OMPL.
[1] http://ompl-beta.kavrakilab.org/
[2] http://ompl-beta.kavrakilab.org/constrainedPlanning.html
[3] Decoupling Constraints from Sampling-Based Planners on Vimeo
[4] https://bitbucket.org/ompl/ompl