Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020 #ifndef SOLVER_STATE_H
00021 #define SOLVER_STATE_H
00022
00023 #include <Eigen/Core>
00024 #include <Eigen/Geometry>
00025
00026 namespace constrained_ik
00027 {
00028
00032 struct SolverState
00033 {
00034 Eigen::Affine3d goal;
00035 Eigen::VectorXd joint_seed;
00036
00037 int iter;
00038 Eigen::VectorXd joints;
00039 Eigen::VectorXd joints_delta;
00040 Eigen::Affine3d pose_estimate;
00041
00042 void reset(const Eigen::Affine3d &goal, const Eigen::VectorXd &joint_seed);
00043 };
00044
00045 }
00046
00047 #endif // SOLVER_STATE_H
00048