34 Eigen::MatrixXd particular_solution = damped_pinv * in_cart_velocities;
38 Eigen::MatrixXd ident = Eigen::MatrixXd::Identity(pinv.rows(), this->jacobian_data_.cols());
41 Eigen::MatrixXd homogeneous_solution = Eigen::MatrixXd::Zero(particular_solution.rows(), particular_solution.cols());
42 KDL::JntArrayVel predict_jnts_vel(joint_states.
current_q_.rows());
44 for (std::set<ConstraintBase_t>::iterator it = this->
constraints_.begin(); it != this->constraints_.end(); ++it)
47 (*it)->update(joint_states, predict_jnts_vel, this->jacobian_data_);
48 Eigen::VectorXd q_dot_0 = (*it)->getPartialValues();
49 Eigen::MatrixXd tmp_projection = projector * q_dot_0;
50 double activation_gain = (*it)->getActivationGain();
51 double constraint_k_H = (*it)->getSelfMotionMagnitude(particular_solution, tmp_projection);
52 homogeneous_solution += (constraint_k_H * activation_gain * tmp_projection);
55 Eigen::MatrixXd qdots_out = particular_solution + this->
params_.
k_H * homogeneous_solution;