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

Confused about the orientation of frames #1099

Closed
sayali-purdue opened this issue Mar 2, 2020 · 12 comments
Closed

Confused about the orientation of frames #1099

sayali-purdue opened this issue Mar 2, 2020 · 12 comments

Comments

@sayali-purdue
Copy link

As per ROS convention, optical frame id should have (X- right, Y- down, Z- forward). Therefore, as per my understanding, in the code, the static transform from _frame_id[STREAM] to _optical_frame_id[STREAM] uses quaternion_optical which changes the axis orientation from (X- forward, Y- left, Z- up) to (X- right, Y- down, Z- forward). This means that _frame_id[STREAM] should have the orientation (X- forward, Y- left, Z- up).

However, I am confused about the transform from _base_frame_id to _frame_id[STREAM]. The code changes the axes orientation for the translation and rotation to (X- right, Y- down, Z- forward). This contradicts my understanding in the above paragraph.

Can somebody please explain me these transforms in terms of orientations? Also, what is the expected orientation of _frame_id[STREAM]?

Thanks!

@RealSenseCustomerSupport
Copy link
Collaborator


Hi @sayali-purdue,

Please provide references to ROS official documentation and ROS/ROS Wrapper source code lines for each convention/transformation/etc. you have mentioned. That way we will be sure that we on the same page and referencing to the same information.

Thank you!

@sayali-purdue
Copy link
Author

Thanks for the reply.

I am referring to the ROS conventions in:
https://www.ros.org/reps/rep-0103.html#axis-orientation

The transform code is in the function 'BaseRealSenseNode::calcAndPublishStaticTransform()' (line #1781) in file https://github.com/IntelRealSense/realsense-ros/blob/development/realsense2_camera/src/base_realsense_node.cpp

The transform from _base_frame_id to _frame_id[STREAM] is performed at line #1812, and
the transform from _frame_id[STREAM] to _optical_frame_id[STREAM] is performed at line #1815. The snapshot of the corresponding code snippet is given below:

Screen Shot 2020-04-17 at 3 47 49 PM

The quaternion_optical is defined at line #1785 as shown below:

Screen Shot 2020-04-17 at 3 45 10 PM

Please let me know if you need more details.

Thanks again!

@doronhi
Copy link
Contributor

doronhi commented Jul 14, 2020

I believe your confusion comes from not taking into account the original camera's orientation of the transformation.
The transformation between a sensor and the _base_frame_id (usually the infra1 sensor) sensor, as set into Q in the line auto Q = rotationMatrixToQuaternion(ex.rotation); is given in the inner coordinates of the camera. Luckily, that system has the same orientation as the "_optical" coordinate system.
Multiplying it by quaternion_optical converts it to standard ros frame_id (i.e. X-forward, Y-left, Z-up).
The wrapper also publishes the transformation that between frame_id and optical_frame_id - the same one already used - quaternion_optical.

The expected orientation of _frame_id[STREAM]: X-forward, Y-left, Z-up.

@RealSenseSupport
Copy link
Collaborator

@sayali-purdue,

Has the comment provided by @doronhi helped to find an answer to your question?

Thank you!

@RealSenseSupport
Copy link
Collaborator

@sayali-purdue,

Do you still need help with this question?

Thank you!

@sayali-purdue
Copy link
Author

Thank you for the response and follow-up.

As per your explanation, I understand that the orientation of the (inner) camera system is (X- right, Y- down, Z- forward), which means that the orientation of Q or ex.rotation is (X- right, Y- down, Z- forward). Then, multiplication with quaternion_optical in the next line changes Q's orientation to (X-forward, Y-left, Z-up). This transformed Q is used in the transform between _base_frame_id and _frame_id[STREAM].

If this is true, then shouldn't the axes system of translation, trans, be changed before using it in this transform? Can you please clarify, which axes each of the field of ex.translation represents? For example, does ex.translation[0] contains value for x-axis, ex.translation[1] contains value for y-axis and ex.translation[2] contains value for z-axis? I think, now my confusion lies at code line #1811. With this understanding, trans variable should be initialized as float3 trans{ex.translation[2], -ex.translation[0], -ex.translation[1]} to change the axes system from (X- right, Y- down, Z- forward) to (X-forward, Y-left, Z-up).

Would really appreciate if you could help me to understand the translation part of these static transforms.

Thanks!

@doronhi
Copy link
Contributor

doronhi commented Jul 19, 2020

I think you are correct. The axes system of translation is changed, as you said, inside the publish_static_tf function. That's the reason why there is no issue with the resulted transformation but this is indeed a bad practice.
If you care, I would appreciate a PR to correct this.

@RealSenseSupport
Copy link
Collaborator

@sayali-purdue,

Please let us know if you'd like to submit a PR or if you need any further clarifications regarding this topic.

Thank you!

@sayali-purdue
Copy link
Author

I would be interested in submitting a PR. However, I am afraid if I will be able to do it before end of this month. Please let me know by when do you expect to see the PR.

Thanks!

@doronhi
Copy link
Contributor

doronhi commented Aug 3, 2020

Hi @sayali-purdue ,
No problem, we have no expectations. This is not a critical issue.
Either you submit a PR or me or someone else will take care of this issue later on.
Thanks for pointing the issue up.

@EhrazImam
Copy link

I think you are correct. The axes system of translation is changed, as you said, inside the publish_static_tf function. That's the reason why there is no issue with the resulted transformation but this is indeed a bad practice. If you care, I would appreciate a PR to correct this.

I've tried this but nothing helped is their any other method of changing the orientation of camera in ROS???

@phu251099
Copy link

phu251099 commented Aug 16, 2023

@sayali-purdue @doronhi
Hi, i am also currently facing the problem of D435i camera IMU speed axis not coincident with ROS speed axis. I changed the code at line 2031 ("float3 trans{ex.translation[2], -ex.translation[0], -ex.translation[1]}") as you said above but the problem still can't be solved. It would be great if you could assist me in solving this problem.

tra
tf imu

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

No branches or pull requests

6 participants