Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Gpm null space dimension print #126

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -52,19 +52,29 @@ Eigen::MatrixXd GradientProjectionMethodSolver::solve(const Vector6d_t& in_cart_

Eigen::MatrixXd homogeneous_solution = Eigen::MatrixXd::Zero(particular_solution.rows(), particular_solution.cols());
KDL::JntArrayVel predict_jnts_vel(joint_states.current_q_.rows());

for (std::set<ConstraintBase_t>::iterator it = this->constraints_.begin(); it != this->constraints_.end(); ++it)
Eigen::MatrixXd qdots_out;
uint32_t rows = projector.rows();
uint32_t cols = projector.cols();
if(projector.isApprox(Eigen::MatrixXd::Zero(rows,cols)))
{
ROS_DEBUG_STREAM("task id: " << (*it)->getTaskId());
(*it)->update(joint_states, predict_jnts_vel, this->jacobian_data_);
Eigen::VectorXd q_dot_0 = (*it)->getPartialValues();
Eigen::MatrixXd tmp_projection = projector * q_dot_0;
double activation_gain = (*it)->getActivationGain(); // contribution of the homo. solution to the part. solution
double constraint_k_H = (*it)->getSelfMotionMagnitude(particular_solution, tmp_projection); // gain of homogenous solution (if active)
homogeneous_solution += (constraint_k_H * activation_gain * tmp_projection);
}

Eigen::MatrixXd qdots_out = particular_solution + this->params_.k_H * homogeneous_solution; // weighting with k_H is done in loop
for (std::set<ConstraintBase_t>::iterator it = this->constraints_.begin(); it != this->constraints_.end(); ++it)
{
ROS_DEBUG_STREAM("task id: " << (*it)->getTaskId());
(*it)->update(joint_states, predict_jnts_vel, this->jacobian_data_);
Eigen::VectorXd q_dot_0 = (*it)->getPartialValues();
Eigen::MatrixXd tmp_projection = projector * q_dot_0;
double activation_gain = (*it)->getActivationGain(); // contribution of the homo. solution to the part. solution
double constraint_k_H = (*it)->getSelfMotionMagnitude(particular_solution, tmp_projection); // gain of homogenous solution (if active)
homogeneous_solution += (constraint_k_H * activation_gain * tmp_projection);
}

qdots_out = particular_solution + this->params_.k_H * homogeneous_solution; // weighting with k_H is done in loop
}
else{
qdots_out = particular_solution;
ROS_WARN("Null space projection matrix is null. The constraint may not be satisfied");
}

// //DEBUG: for verification of nullspace projection
// std::stringstream ss_part;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,12 +106,26 @@ Eigen::MatrixXd StackOfTasksSolver::solve(const Vector6d_t& in_cart_velocities,
Eigen::MatrixXd J_temp = J_task * projector_i;
Eigen::VectorXd v_task = it->task_;
Eigen::MatrixXd J_temp_inv = pinv_calc_.calculate(J_temp);
q_i = q_i + J_temp_inv * (v_task - J_task * q_i);
projector_i = projector_i - J_temp_inv * J_temp;
Eigen::FullPivLU<Eigen::MatrixXd> lu_decomp(J_temp_inv);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why do you evaluate J_temp_inv and not projector_i?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Because J_temp_inv is going to project the ith task velocities. If it has rank zero is not adding any velocity for that task.

uint32_t rows = J_temp_inv.rows();
uint32_t cols = J_temp_inv.cols();
if(J_temp_inv.isApprox(Eigen::MatrixXd::Zero(rows,cols))){
ROS_WARN("Null space projection matrix is null. It couldn't satisfy all constraints");
}
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we cannot quit here as projector_i = projector_i - J_temp_inv * J_temp; so even if some projector_i are Zero, the overall projector_i not necessarily is Zero as it is a sum not a multiplication.

Just a warning that the projector of the current task is Zero but continue computation

else{
q_i = q_i + J_temp_inv * (v_task - J_task * q_i);
projector_i = projector_i - J_temp_inv * J_temp;
}
}

qdots_out.col(0) = q_i + projector_i * sum_of_gradient;
return qdots_out;
uint32_t rows = projector_i.rows();
uint32_t cols = projector_i.cols();
if(projector_i.isApprox(Eigen::MatrixXd::Zero(rows,cols))){
qdots_out.col(0) = q_i;
ROS_WARN("Null space projection matrix is null. It couldn't satisfy the global weighting for all constraints.");
return qdots_out;
}
qdots_out.col(0) = q_i + projector_i * sum_of_gradient; //Why???
return qdots_out;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why //WHY???

identation

}


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,36 +64,41 @@ Eigen::MatrixXd TaskPrioritySolver::solve(const Vector6d_t& in_cart_velocities,
predict_jnts_vel.q(i) = particular_solution(i, 0) * cycle + joint_states.current_q_(i);
predict_jnts_vel.qdot(i) = particular_solution(i, 0);
}

uint32_t rows = projector.rows();
uint32_t cols = projector.cols();
if (this->constraints_.size() > 0)
{
for (std::set<ConstraintBase_t>::iterator it = this->constraints_.begin(); it != this->constraints_.end(); ++it)
{
(*it)->update(joint_states, predict_jnts_vel, this->jacobian_data_);
current_cost_func_value = (*it)->getValue();
derivative_cost_func_value = (*it)->getDerivativeValue();
partial_cost_func = (*it)->getPartialValues(); // Equal to (partial g) / (partial q) = J_g
activation_gain = (*it)->getActivationGain();
magnitude = (*it)->getSelfMotionMagnitude(Eigen::MatrixXd::Zero(1, 1), Eigen::MatrixXd::Zero(1, 1)); // not necessary to pass valid values here.
if (projector.isApprox(Eigen::MatrixXd::Zero(rows,cols)))
{
for (std::set<ConstraintBase_t>::iterator it = this->constraints_.begin(); it != this->constraints_.end(); ++it)
{
(*it)->update(joint_states, predict_jnts_vel, this->jacobian_data_);
current_cost_func_value = (*it)->getValue();
derivative_cost_func_value = (*it)->getDerivativeValue();
partial_cost_func = (*it)->getPartialValues(); // Equal to (partial g) / (partial q) = J_g
activation_gain = (*it)->getActivationGain();
magnitude = (*it)->getSelfMotionMagnitude(Eigen::MatrixXd::Zero(1, 1), Eigen::MatrixXd::Zero(1, 1)); // not necessary to pass valid values here.

ROS_INFO_STREAM("activation_gain: " << activation_gain);
ROS_INFO_STREAM("smm: " << magnitude);
}
ROS_INFO_STREAM("activation_gain: " << activation_gain);
ROS_INFO_STREAM("smm: " << magnitude);
}

Eigen::MatrixXd jac_inv_2nd_term = Eigen::MatrixXd::Zero(projector.cols(), partial_cost_func.cols());
if (activation_gain > 0.0)
{
Eigen::MatrixXd tmp_matrix = partial_cost_func.transpose() * projector;
jac_inv_2nd_term = pinv_calc_.calculate(tmp_matrix);
}
Eigen::MatrixXd jac_inv_2nd_term = Eigen::MatrixXd::Zero(projector.cols(), partial_cost_func.cols());
if (activation_gain > 0.0)
{
Eigen::MatrixXd tmp_matrix = partial_cost_func.transpose() * projector;
jac_inv_2nd_term = pinv_calc_.calculate(tmp_matrix);

Eigen::MatrixXd m_derivative_cost_func_value = derivative_cost_func_value * Eigen::MatrixXd::Identity(1, 1);
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);
}
else
{
Eigen::MatrixXd m_derivative_cost_func_value = derivative_cost_func_value * Eigen::MatrixXd::Identity(1, 1);
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);
}
}
else
{
qdots_out = particular_solution;
ROS_ERROR_STREAM("Should not occur solution: " << std::endl << qdots_out);
ROS_WARN("Null space projection matrix is null. The constraint may not be satisfied");
}
}

// Eigen::MatrixXd qdots_out = particular_solution + homogeneousSolution; // weighting with k_H is done in loop
Expand Down