-
Notifications
You must be signed in to change notification settings - Fork 246
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
Add SGal(3) #289
Add SGal(3) #289
Conversation
Regarding the left jac. Is the right jacobian ready, then? I think J.Kelly provides the left, and then we'll have to implement also the right via the trick |
The rjac is implemented with respect to the left using the adj (see here). You'll notice in the function some comments, I've implemented the 'easy blocks' of the right jac and validated those against auto diff. |
This would be a time saver over the Adj solution. And it works for all groups. |
I'd have to check but I believe that all the other groups implement a closed-form anyway. |
We should definitely do this in sgal3 |
Also, this statement has no L262: if (theta_sq > Constants<Scalar>::eps) {
cA = (Scalar(2) - theta * sin_t - Scalar(2) * cos_t) / theta_cu;
cB = (theta_cu + Scalar(6) * theta + Scalar(6) * theta * cos_t - Scalar(12) * sin_t) / (Scalar(6) * theta_cu);
cC = (Scalar(12) * sin_t - theta_cu - Scalar(3) * theta_sq * sin_t - Scalar(12) * theta * cos_t) / (Scalar(6) * theta_cu);
cD = (Scalar(4) + theta_sq * (Scalar(1) + cos_t) - Scalar(4) * (theta * sin_t + cos_t) ) / (Scalar(2) * theta_cu);
// cD = (Scalar(4) + theta_sq * (Scalar(1) + cos_t) - Scalar(4) * (theta * sin_t - cos_t) ) / (Scalar(2) * theta_cu);
cE = (theta_sq + Scalar(2) * (cos_t - Scalar(1))) / (Scalar(2) * theta_cu);
cF = (theta_cu + Scalar(6) * (sin_t - theta)) / (Scalar(6) * theta_cu);
} |
Implemented the else clause: if (theta_sq > Constants<Scalar>::eps) {
cA = (Scalar(2) - theta * sin_t - Scalar(2) * cos_t) / theta_cu;
cB = (theta_cu + Scalar(6) * theta + Scalar(6) * theta * cos_t - Scalar(12) * sin_t) / (Scalar(6) * theta_cu);
cC = (Scalar(12) * sin_t - theta_cu - Scalar(3) * theta_sq * sin_t - Scalar(12) * theta * cos_t) / (Scalar(6) * theta_cu);
cD = (Scalar(4) + theta_sq * (Scalar(1) + cos_t) - Scalar(4) * (theta * sin_t + cos_t) ) / (Scalar(2) * theta_cu);
// cD = (Scalar(4) + theta_sq * (Scalar(1) + cos_t) - Scalar(4) * (theta * sin_t - cos_t) ) / (Scalar(2) * theta_cu);
cE = (theta_sq + Scalar(2) * (cos_t - Scalar(1))) / (Scalar(2) * theta_cu);
cF = (theta_cu + Scalar(6) * (sin_t - theta)) / (Scalar(6) * theta_cu);
}else{
cA = theta / Scalar(12);
cB = theta_sq / Scalar(24);
cC = theta_sq / Scalar(10);
cD = theta_cu / Scalar(240);
cE = theta / Scalar(24);
cF = theta_sq / Scalar(120);
} Unfortunately, still no luck, and tests fail. |
please tell me if you want me to commit @artivis |
This is also weird: double assignation of matrix Ref33 S = Jl.template block<3, 3>(3, 3); // first assign
S = t() / Scalar(6) * V // second assign
+ (cA * W + cB * W * W) * (t() * V)
// + cC * t() * (W * V * W)
+ cC * (W * V * (t() * W))
// + cD * t() * (W * W * V * W)
+ cD * (W * W * V * (t() * W))
+ t() * V * (cE * W + cF * W * W)
;
Jl.template block<3, 3>(0, 6) -= S; // update This seems wrong to me. Where is N1 in the (0,6) block of In my opinion we should do: Jl.template block<3,3>(0,6) = N1; // <-- where is N1? Is it block (3,3)?
Ref 33 S = // bla bla all the formulas. S is N2 in Kelly's paper
Jl.template block<3,3>(0,6) -= S; // update with N2 |
A little recap. The tangent space is
Then, the error vector in the log() jacobian test is like so:
that is, it is highest in the angular part (theta). Does that mean that the error lies in the angular matrix blocks of the Jacobian? Because then it is not in |
Quick answers, I'll come back to it later.
|
OK it all makes sense. But I checked N1 many times already and still cannot find the bug. |
This trick of using 3x3 blocks of |
Jajaja, just replace them. We can optimize the code later ... |
OK here's what I did:
Still does not work. Will commit and continue from here. EDIT : pushed all changes, |
Hi @joansola, |
possibly this equivalent one is a little bit less cumbersome (removing the inverse()):
EDIT: modified and pushed |
I suspect this is wrong: template <typename _Derived>
void SGal3TangentBase<_Derived>::fillE(
Eigen::Ref<Eigen::Matrix<Scalar, 3, 3>> E,
const Eigen::Map<const SO3Tangent<Scalar>>& so3
) {
using I = typename Eigen::DiagonalMatrix<Scalar, 3>;
const Scalar theta_sq = so3.coeffs().squaredNorm();
E.noalias() = I(Scalar(0.5), Scalar(0.5), Scalar(0.5)).toDenseMatrix();
// small angle approx.
if (theta_sq < Constants<Scalar>::eps) {
return;
}
const Scalar theta = sqrt(theta_sq); // rotation angle
const Scalar A = (theta - sin(theta)) / theta_sq;
const Scalar B = (theta_sq + Scalar(2) * cos(theta) - Scalar(2)) / (Scalar(2) * theta_sq);
const typename SO3Tangent<Scalar>::LieAlg W = so3.hat();
E.noalias() += A * W + B * W * W;
} since W is not normalized in the code, and it is in the paper (it is u^) |
This actually happens also in matrices |
OK BUGS solved!!! It was indeed the non-normalized Had to change the following:
Missing -- and thus not passing tests:
|
Regarding I see in Kelly's paper he speaks of the action on events, an event being a tuple [p,t] in R3 x R. He also speaks of plenty of other possible actions: rotation, boost, and who knows what else. Given that there are multiple possible actions, and we need to pick one, let us consider this:
So, in SGal(3) we could also keep doing the same as in SE(3). What do you think? The thing is, if we want to combine positions, velocities, etc, considering time, we can always compose two different SGal(3) objects. An action in the likes of SE(3) would mean a compisition with a SGal object with time 0 :
and if the second object has velocity
so, the simple action |
I guess that's reasonable and coherent. Let me implement that and update this PR. |
Codecov Report
Additional details and impacted files@@ Coverage Diff @@
## devel #289 +/- ##
==========================================
- Coverage 98.15% 97.93% -0.23%
==========================================
Files 56 62 +6
Lines 1843 2223 +380
==========================================
+ Hits 1809 2177 +368
- Misses 34 46 +12 |
@joansola all the tests are passing successfully 👍 . |
Does this include the Jacobians of act()? EDIT: I see. Cool! Thanks ! |
I've got everything working fine 👍 . |
yeah, you like freak coding :-) But please use Also perhaps one can define all powers of theta up to Do you think these optims matter so much? |
5008a86
to
0298938
Compare
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Just consider the few comments in this review before merging. they are all easy.
Comments addressed 👍 . |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
still some minor change
Signed-off-by: artivis <deray.jeremie@gmail.com>
Thanks @joansola for your help on this PR! |
Visca!! Thanks to you @artivis |
Add the Galilean Group SGal(3) as per,
Todo: