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 #include "constrained_ik/solver_state.h"
00020 #include <limits>
00021 #include <ros/ros.h>
00022
00023 using namespace Eigen;
00024
00025 namespace constrained_ik
00026 {
00027
00028 void SolverState::reset(const Eigen::Affine3d &goal, const Eigen::VectorXd &joint_seed)
00029 {
00030 this->goal = goal;
00031 this->joint_seed = joint_seed;
00032 this->iter = 0;
00033 this->joints = VectorXd::Constant(joint_seed.size(), std::numeric_limits<double>::max());
00034 this->joints_delta = VectorXd::Zero(joint_seed.size());
00035 this->pose_estimate = Affine3d::Identity();
00036 }
00037
00038
00039 }
00040