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

Wheel odometry to T265 with two wheels #4938

Closed
mzelina opened this issue Sep 25, 2019 · 4 comments
Closed

Wheel odometry to T265 with two wheels #4938

mzelina opened this issue Sep 25, 2019 · 4 comments
Labels
T260 series Intel® T265 library tracking 6-DOF tracking, SLAM and T26x series

Comments

@mzelina
Copy link

mzelina commented Sep 25, 2019

I have a two wheel robot and want to feed odometry data into the T265 to aid in tracking. I have read the documentation and surrounding articles (e.g. #3462 (comment), #3970 (comment)).

The JSON file example describes T as "relative transformation of sensor frame w.r.t. T265 body frame (see T265 data sheet, sec. 4.3 "Coordinate System"). I am not sure if this is the the center of the wheel, where the wheel contacts the surface or some other measurement?

Similar question for W described as "the orientation in axis-angle representation, axis x angle (in rad)". I don't understand how this axis-angle representation maps to direction. One wheel is going positive and one negative to move forward. Is this where this transformation comes into account?

My wheels are mounted behind the camera with the camera centered on the chasis and the wheels being ~0.7m behind and ~0.1m below the center of the camera and a wheel base of 0.46m.

My best guess is these items in my file would be the following for translations (intentionally ommited the other parts of the file). For W I am not sure. Any help appreciated!

"velocimeters": [
        { // Wheel left
            ...
            "extrinsics": {
                "T": [
                    -0.23,
                    -0.1,
                    0.7
                ],
                "W": [ // orientation in axis-angle representation, axis x angle (in rad)
                    ????,
                    ????,
                    ????
                ]
            }
        },
      { // Wheel right
            ...
            "extrinsics": {
                "T": [
                    0.23,
                    -0.1,
                    0.7
                ],
                "W": [ // orientation in axis-angle representation, axis x angle (in rad)
                    ????,
                    ????,
                    ????
                ]
            }
        }
    ]
}
@dorodnic dorodnic added T260 series Intel® T265 library tracking 6-DOF tracking, SLAM and T26x series labels Sep 26, 2019
@mzelina
Copy link
Author

mzelina commented Sep 28, 2019

Missed this previously but the unit test here is helpful if anyone else has issues:

https://github.com/IntelRealSense/librealsense/blob/master/unit-tests/unit-tests-live.cpp#L5535

Still not clear on how exactly to calculate the axis-angle from the robot geometry.

@mzelina
Copy link
Author

mzelina commented Oct 1, 2019

@dorodnic Can you clarify something in your test case for the wheel odometry?

https://github.com/IntelRealSense/librealsense/blob/master/unit-tests/unit-tests-live.cpp#L5535

You are expecting the robot to be stationary in your comments but you are passing 1, 0, 0 for the translational velocity vector. I would have expected that to be 0, 0, 0.

Also, are there any real-world examples for odometry calibration? Perhaps the odometry calibration for the kobuki tests you ran would be useful.

@schmidtp1
Copy link
Contributor

@mzelina,

I have a two wheel robot and want to feed odometry data into the T265 to aid in tracking. I have read the documentation and surrounding articles (e.g. #3462 (comment), #3970 (comment)).

The JSON file example describes T as "relative transformation of sensor frame w.r.t. T265 body frame (see T265 data sheet, sec. 4.3 "Coordinate System"). I am not sure if this is the the center of the wheel, where the wheel contacts the surface or some other measurement?
This is where the wheel contacts the surface.

Similar question for W described as "the orientation in axis-angle representation, axis x angle (in rad)". I don't understand how this axis-angle representation maps to direction. One wheel is going positive and one negative to move forward. Is this where this transformation comes into account?
There is some design freedom in the definition of the velocity frame. I usually align the x-axis with the velocity vector and then define the rotation between the velocity frame and the T265 in the calibration file.
Yes, it can be used to account for that difference between the two wheels.

My wheels are mounted behind the camera with the camera centered on the chasis and the wheels being ~0.7m behind and ~0.1m below the center of the camera and a wheel base of 0.46m.

My best guess is these items in my file would be the following for translations (intentionally ommited the other parts of the file). For W I am not sure. Any help appreciated!

"velocimeters": [
        { // Wheel left
            ...
            "extrinsics": {
                "T": [
                    -0.23,
                    -0.1,
                    0.7
                ],
                "W": [ // orientation in axis-angle representation, axis x angle (in rad)
                    -1.2092,
                    -1.2092,
                    -1.2092
                ]
            }
        },
      { // Wheel right
            ...
            "extrinsics": {
                "T": [
                    0.23,
                    -0.1,
                    0.7
                ],
                "W": [ // orientation in axis-angle representation, axis x angle (in rad)
                    -1.2092,
                    1.2092,
                    1.2092
                ]
            }
        }
    ]
}

The translation is correct for the case that you describe.
I filled in the orientation according to the small sketch below. (Please feel free to double-check it.)
IMG_2708

@RealSenseCustomerSupport
Copy link
Collaborator


Hi @mzelina - Were you able to use the information provided by schmidtp1? Anything else needed?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
T260 series Intel® T265 library tracking 6-DOF tracking, SLAM and T26x series
Projects
None yet
Development

No branches or pull requests

4 participants