Skip to content

convert jacobian into RPY space#33

Draft
suchkristenwow wants to merge 1 commit intohumblefrom
fix/omnidirectional-3d-jacobian-humble
Draft

convert jacobian into RPY space#33
suchkristenwow wants to merge 1 commit intohumblefrom
fix/omnidirectional-3d-jacobian-humble

Conversation

@suchkristenwow
Copy link
Copy Markdown

It seems like before we were truncating the acceleration to make the matrix dimensions fit (dropping the az column) and now I think we should be properly converting from quaternion to RPY space using the pseudo-inverse of the quaternion-to-RPY jacobian.

Comment on lines +496 to +505
// Convert J[1] from quaternion space (15x4) to RPY space (15x3) using the
// pseudo-inverse of the quaternion-to-RPY Jacobian.
// Chain rule: J[1] = d(state2)/d(quat1) = d(state2)/d(rpy1) * d(rpy)/d(quat)
// So: d(state2)/d(rpy1) = J[1] * pinv(d(rpy)/d(quat))
Eigen::Map<fuse_core::Matrix<double, 3, 4>> j_quat2rpy_map(jacobian_quat2rpy);
fuse_core::Matrix<double, 4, 3> j_quat2rpy_pinv =
j_quat2rpy_map.transpose() * (j_quat2rpy_map * j_quat2rpy_map.transpose()).inverse();
fuse_core::Matrix<double, 15, 3> J1_rpy = J[1] * j_quat2rpy_pinv;

jacobian << J[0], J1_rpy, J[2], J[3], J[4];
Copy link
Copy Markdown
Collaborator

Choose a reason for hiding this comment

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

LGTM broadly; do we need to add a case to cover the singular cases where pitch is +/ 90 degrees? I'd think that would mean the jacobian_quat2rpy would be undefined maybe, so it should perhaps be handled above

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants