28 double cycle = (now - this->
last_time_).toSec();
34 Eigen::MatrixXd particular_solution = damped_pinv * in_cart_velocities;
36 Eigen::MatrixXd ident = Eigen::MatrixXd::Identity(pinv.rows(), this->jacobian_data_.cols());
39 Eigen::MatrixXd projector_i = Eigen::MatrixXd::Identity(this->jacobian_data_.cols(), this->jacobian_data_.cols());
40 Eigen::VectorXd q_i = Eigen::VectorXd::Zero(this->jacobian_data_.cols());
41 Eigen::MatrixXd qdots_out = Eigen::MatrixXd::Zero(this->jacobian_data_.cols(), 1);
43 Eigen::VectorXd sum_of_gradient = Eigen::VectorXd::Zero(this->jacobian_data_.cols());
45 KDL::JntArrayVel predict_jnts_vel(joint_states.
current_q_.rows());
48 for (
int i = 0; i < joint_states.
current_q_.rows(); ++i)
50 predict_jnts_vel.q(i) = particular_solution(i, 0) * cycle + joint_states.
current_q_(i);
51 predict_jnts_vel.qdot(i) = particular_solution(i, 0);
55 double inv_sum_of_prionums = 0.0;
56 for (std::set<ConstraintBase_t>::iterator it = this->
constraints_.begin(); it != this->constraints_.end(); ++it)
58 (*it)->update(joint_states, predict_jnts_vel, this->jacobian_data_);
59 const double constr_prio = (*it)->getPriorityAsNum();
60 if ((*it)->getState().getCurrent() ==
DANGER)
67 for (std::set<ConstraintBase_t>::iterator it = this->
constraints_.begin(); it != this->constraints_.end(); ++it)
69 this->
processState(it, projector, particular_solution, inv_sum_of_prionums, sum_of_gradient);
72 sum_of_gradient = this->
params_.
k_H * sum_of_gradient;
92 Eigen::MatrixXd J_task = it->task_jacobian_;
93 Eigen::MatrixXd J_temp = J_task * projector_i;
94 Eigen::VectorXd v_task = it->task_;
96 q_i = q_i + J_temp_inv * (v_task - J_task * q_i);
97 projector_i = projector_i - J_temp_inv * J_temp;
100 qdots_out.col(0) = q_i + projector_i * sum_of_gradient;
106 const Eigen::MatrixXd& projector,
107 const Eigen::MatrixXd& particular_solution,
108 double inv_sum_of_prios,
109 Eigen::VectorXd& sum_of_gradient)
111 Eigen::VectorXd q_dot_0 = (*it)->getPartialValues();
112 const double activation_gain = (*it)->getActivationGain();
113 Eigen::MatrixXd tmp_projection = projector * q_dot_0;
114 const double magnitude = (*it)->getSelfMotionMagnitude(particular_solution, tmp_projection);
117 const double constr_prio = (*it)->getPriorityAsNum();
120 const double gpm_weighting = inv_constr_prio / inv_sum_of_prios;
127 Task_t t = (*it)->createTask();
128 double factor = activation_gain * std::abs(magnitude);
129 t.task_ = factor *
t.task_;
136 sum_of_gradient += gpm_weighting * activation_gain * magnitude * q_dot_0;
147 Task_t t = (*it)->createTask();
148 double factor = activation_gain * std::abs(magnitude);
149 t.task_ = factor *
t.task_;
154 sum_of_gradient += gpm_weighting * activation_gain * magnitude * q_dot_0;
162 if (cstate.
getCurrent() > this->global_constraint_state_ )