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

[Admittance] applies control frame transform to mass matrix #1139

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
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 @@ -248,6 +248,17 @@ bool AdmittanceRule::calculate_admittance_rule(AdmittanceState & admittance_stat
D.block<3, 3>(0, 0) = D_pos;
D.block<3, 3>(3, 3) = D_rot;

// The same for mass
Eigen::Matrix<double, 6, 6> M_inv = Eigen::Matrix<double, 6, 6>::Zero();
Eigen::Matrix<double, 3, 3> M_inv_pos = Eigen::Matrix<double, 3, 3>::Zero();
Eigen::Matrix<double, 3, 3> M_inv_rot = Eigen::Matrix<double, 3, 3>::Zero();
M_inv_pos.diagonal() = admittance_state.mass_inv.block<3, 1>(0, 0);
M_inv_rot.diagonal() = admittance_state.mass_inv.block<3, 1>(3, 0);
M_inv_pos = rot_base_control * M_inv_pos * rot_base_control.transpose();
M_inv_rot = rot_base_control * M_inv_rot * rot_base_control.transpose();
M_inv.block<3, 3>(0, 0) = M_inv_pos;
M_inv.block<3, 3>(3, 3) = M_inv_rot;

// calculate admittance relative offset in base frame
Eigen::Isometry3d desired_trans_base_ft;
kinematics_->calculate_link_transform(
Expand Down Expand Up @@ -276,8 +287,7 @@ bool AdmittanceRule::calculate_admittance_rule(AdmittanceState & admittance_stat
F_base.block<3, 1>(3, 0) = rot_base_control * F_control.block<3, 1>(3, 0);

// Compute admittance control law in the base frame: F = M*x_ddot + D*x_dot + K*x
Eigen::Matrix<double, 6, 1> X_ddot =
admittance_state.mass_inv.cwiseProduct(F_base - D * X_dot - K * X);
Eigen::Matrix<double, 6, 1> X_ddot = M_inv * (F_base - D * X_dot - K * X);
bool success = kinematics_->convert_cartesian_deltas_to_joint_deltas(
admittance_state.current_joint_pos, X_ddot, admittance_state.ft_sensor_frame,
admittance_state.joint_acc);
Expand Down