30 double cycle = (now - this->
last_time_).toSec();
33 double derivative_cost_func_value;
34 double current_cost_func_value;
35 double activation_gain;
38 Eigen::MatrixXd qdots_out = Eigen::MatrixXd::Zero(this->
jacobian_data_.cols(), 1);
39 Eigen::VectorXd partial_cost_func = Eigen::VectorXd::Zero(this->
jacobian_data_.cols());
43 Eigen::MatrixXd particular_solution = damped_pinv * in_cart_velocities;
45 Eigen::MatrixXd ident = Eigen::MatrixXd::Identity(pinv.rows(), this->jacobian_data_.cols());
48 KDL::JntArrayVel predict_jnts_vel(joint_states.
current_q_.rows());
51 for (uint8_t i = 0; i < joint_states.
current_q_.rows(); ++i)
53 predict_jnts_vel.q(i) = particular_solution(i, 0) * cycle + joint_states.
current_q_(i);
54 predict_jnts_vel.qdot(i) = particular_solution(i, 0);
59 for (std::set<ConstraintBase_t>::iterator it = this->
constraints_.begin(); it != this->constraints_.end(); ++it)
61 (*it)->update(joint_states, predict_jnts_vel, this->jacobian_data_);
62 current_cost_func_value = (*it)->getValue();
63 derivative_cost_func_value = (*it)->getDerivativeValue();
64 partial_cost_func = (*it)->getPartialValues();
65 activation_gain = (*it)->getActivationGain();
66 magnitude = (*it)->getSelfMotionMagnitude(Eigen::MatrixXd::Zero(1, 1), Eigen::MatrixXd::Zero(1, 1));
72 Eigen::MatrixXd jac_inv_2nd_term = Eigen::MatrixXd::Zero(projector.cols(), partial_cost_func.cols());
73 if (activation_gain > 0.0)
75 Eigen::MatrixXd tmp_matrix = partial_cost_func.transpose() * projector;
79 Eigen::MatrixXd m_derivative_cost_func_value = derivative_cost_func_value * Eigen::MatrixXd::Identity(1, 1);
80 qdots_out = particular_solution + this->
params_.
k_H * activation_gain * jac_inv_2nd_term * (magnitude * m_derivative_cost_func_value - partial_cost_func.transpose() * particular_solution);
84 qdots_out = particular_solution;