Welcome to mirror list, hosted at ThFree Co, Russian Federation.

git.blender.org/blender.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorBrecht Van Lommel <brechtvanlommel@pandora.be>2005-08-27 17:27:49 +0400
committerBrecht Van Lommel <brechtvanlommel@pandora.be>2005-08-27 17:27:49 +0400
commitfa0bbaf380fb634cf3bd385737eef630a226633e (patch)
treef946a42f8846fb08514c1ef2c19bef2c3d7f3f39 /intern/iksolver
parent8d36b517f928e66c52f795ac93364f778926a08e (diff)
Another file missed in IK commit.
Diffstat (limited to 'intern/iksolver')
-rw-r--r--intern/iksolver/extern/IK_solver.h186
1 files changed, 75 insertions, 111 deletions
diff --git a/intern/iksolver/extern/IK_solver.h b/intern/iksolver/extern/IK_solver.h
index 973834f1682..78633fb0d9a 100644
--- a/intern/iksolver/extern/IK_solver.h
+++ b/intern/iksolver/extern/IK_solver.h
@@ -24,7 +24,8 @@
*
* The Original Code is: all of this file.
*
- * Contributor(s): none yet.
+ * Original author: Laurence
+ * Contributor(s): Brecht
*
* ***** END GPL/BL DUAL LICENSE BLOCK *****
*/
@@ -34,26 +35,20 @@
* $Id$
* Copyright (C) 2001 NaN Technologies B.V.
*
- * @author Laurence
+ * @author Laurence, Brecht
* @mainpage IK - Blender inverse kinematics module.
*
* @section about About the IK module
*
* This module allows you to create segments and form them into
- * chains. You can then define a goal point that the end of the
- * chain should attempt to reach - an inverse kinematic problem.
- * This module will then modify the segments in the chain in
- * order to get the end of the chain as near as possible to the
- * goal. This solver uses an inverse jacobian method to find
- * a solution.
+ * tree. You can then define a goal points that the end of a given
+ * segment should attempt to reach - an inverse kinematic problem.
+ * This module will then modify the segments in the tree in order
+ * to get the as near as possible to the goal. This solver uses an
+ * inverse jacobian method to find a solution.
*
* @section issues Known issues with this IK solver.
*
- * - The current solver works with only one type of segment. These
- * segments always have 3 degress of freedom (DOF). i.e. the solver
- * uses all these degrees to solve the IK problem. It would be
- * nice to allow the user to specify different segment types such
- * as 1 DOF joints in a given plane. 2 DOF joints about given axis.
* - There is currently no support for joint constraints in the
* solver. This is within the realms of possibility - please ask
* if this functionality is required.
@@ -77,124 +72,93 @@
extern "C" {
#endif
-/**
- * External segment structure
+/**
+ * Typical order of calls for solving an IK problem:
+ *
+ * - create number of IK_Segment's and set their parents and transforms
+ * - create an IK_Solver
+ * - set a number of goals for the IK_Solver to solve
+ * - call IK_Solve
+ * - free the IK_Solver
+ * - get basis and translation changes from segments
+ * - free all segments
*/
/**
- * This structure defines a single segment of an IK chain.
+ * IK_Segment defines a single segment of an IK tree.
* - Individual segments are always defined in local coordinates.
- * - The segment is assumed to be oriented in the local
+ * - The segment is assumed to be oriented in the local
* y-direction.
- * - seg_start is the start of the segment relative to the end
+ * - start is the start of the segment relative to the end
* of the parent segment.
- * - basis is a column major matrix defining the rest position
- * of the bone.
- * - length is the simply the length of the bone.
- * - basis_change is a 3x3 matrix representing the change
- * from the rest position of the segment to the solved position.
- * In fact it is the transpose of this matrix because blender
- * does something weird with quaternion conversion. This is
- * strictly an ouput variable for returning the results of an
- * an ik solve back to you.
- * The local transformation specified as a column major matrix
- * of a segment is then defined as.
- * translate(seg_start)*basis*transpose(basis_change)*translate(0,length,0)
+ * - rest_basis is a column major matrix defineding the rest
+ * position (w.r.t. which the limits are defined), must
+ * be a pure rotation
+ * - basis is a column major matrix defining the current change
+ * from the rest basis, must be a pure rotation
+ * - length is the length of the bone.
+ *
+ * - basis_change and translation_change respectively define
+ * the change in rotation or translation for rotational joints
+ * and translational joints. basis_change is a column major 3x3
+ * matrix.
+ *
+ * For rotational joints the local transformation is then defined as:
+ * start*rest_basis*basis*basis_change*translate(0,length,0)
+ *
+ * For translational joints:
+ * start*rest_basis*basis*translation_change*translate(0,length,0)
*/
-typedef struct IK_Segment_Extern {
- float seg_start[3];
- float basis[9];
- float length;
- float basis_change[9];
-} IK_Segment_Extern;
-
-typedef IK_Segment_Extern* IK_Segment_ExternPtr;
-
-/**
- * External chain structure.
- * This structure is filled when you call IK_LoadChain.
- * The first segment in the chain is the root segment.
- * The end of the last segment is the end-effector of the chain
- * this is the point that tries to move to the goal in the ik
- * solver.
- * - num_segments is the number of segments in the array pointed
- * to by the member segments.
- * - chain_dof is the number of degrees of freedom of the chain
- * that is the number of independent ways the chain can be changed
- * to reach the goal.
- * - segments points to an array of IK_Segment_Extern structs
- * containing the segments of this chain.
- * - intern is pointer used by the module to store information
- * about the chain. Please do not touch the member in any way.
- */
+typedef void IK_Segment;
-typedef struct IK_Chain_Extern {
- int num_segments;
- int chain_dof;
- IK_Segment_ExternPtr segments;
- void * intern;
-} IK_Chain_Extern;
+enum IK_SegmentFlag {
+ IK_XDOF = 1,
+ IK_YDOF = 2,
+ IK_ZDOF = 4,
+ IK_TRANSLATIONAL = 8
+};
-typedef IK_Chain_Extern* IK_Chain_ExternPtr;
+typedef enum IK_SegmentAxis {
+ IK_X,
+ IK_Y,
+ IK_Z
+} IK_SegmentAxis;
+extern IK_Segment *IK_CreateSegment(int flag);
+extern void IK_FreeSegment(IK_Segment *seg);
-/**
- * Create a clean chain structure.
- * @return A IK_Chain_Extern structure allocated on the heap.
- * Do not attempt to delete or free this memory yourself please
- * use the FreeChain(...) function for this.
- */
+extern void IK_SetParent(IK_Segment *seg, IK_Segment *parent);
+extern void IK_SetTransform(IK_Segment *seg, float start[3], float rest_basis[][3], float basis[][3], float length);
+extern void IK_SetLimit(IK_Segment *seg, IK_SegmentAxis axis, float lmin, float lmax);
+extern void IK_SetStiffness(IK_Segment *seg, IK_SegmentAxis axis, float stiffness);
-extern IK_Chain_ExternPtr IK_CreateChain(void);
+extern void IK_GetBasisChange(IK_Segment *seg, float basis_change[][3]);
+extern void IK_GetTranslationChange(IK_Segment *seg, float *translation_change);
/**
- * Copy segment information into the chain structure.
- * @param chain A chain to load the segments into.
- * @param segments a ptr to an array of IK_Input_Segment_Extern structures
- * @param num_segs the number of segments to load into the chain
- * @return 1 if the chain was correctly loaded into the structure.
- * @return 0 if an error occured loading the chain. This will normally
- * occur when there is not enough memory to allocate internal chain data.
- * In this case you should not use the chain structure and should call
- * IK_FreeChain to free the memory associated with the chain.
- */
+ * An IK_Solver must be created to be able to execute the solver.
+ *
+ * An arbitray number of goals can be created, stating that a given
+ * end effector must have a given position or rotation. If multiple
+ * goals are specified, they can be weighted (range 0..1) to get
+ * some control over their importance.
+ *
+ * IK_Solve will execute the solver, that will run until either the
+ * system converges, or a maximum number of iterations is reached.
+ * It returns 1 if the system converged, 0 otherwise.
+ */
-extern int IK_LoadChain(IK_Chain_ExternPtr chain,IK_Segment_ExternPtr segments, int num_segs);
+typedef void IK_Solver;
-/**
- * Compute the solution of an inverse kinematic problem.
- * @param chain a ptr to an IK_Segment_Extern loaded with the segments
- * to solve for.
- * @param goal the goal of the IK problem
- * @param tolerance .The distance to the solution within which the chain is deemed
- * to be solved.
- * @param max_iterations. The maximum number of iterations to use in solving the
- * problem.
- * @param max_angle_change. The maximum allowed angular change. 0.1 is a good value here.
- * @param output. Results of the solution are written to the segments pointed to by output.
- * Only the basis and basis_change fields are written. You must make sure that you have
- * allocated enough room for the output segments.
- * @return 0 if the solved chain did not reach the goal. This occurs when the
- * goal was unreachable by the chain end effector.
- * @return 1 if the chain reached the goal.
- */
+IK_Solver *IK_CreateSolver(IK_Segment *root);
+void IK_FreeSolver(IK_Solver *solver);
-extern int IK_SolveChain(
- IK_Chain_ExternPtr chain,
- float goal[3],
- float tolerance,
- int max_iterations,
- float max_angle_change,
- IK_Segment_ExternPtr output
-);
-
-/**
- * Free a chain and all it's internal memory.
- */
+void IK_SolverAddGoal(IK_Solver *solver, IK_Segment *tip, float goal[3], float weight);
+void IK_SolverAddGoalOrientation(IK_Solver *solver, IK_Segment *tip, float goal[][3], float weight);
-extern void IK_FreeChain(IK_Chain_ExternPtr);
+int IK_Solve(IK_Solver *solver, float tolerance, int max_iterations);
#ifdef __cplusplus