You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
{{ message }}
This repository was archived by the owner on Feb 3, 2025. It is now read-only.
Then write a small example to get the position of the wheel relative to the platform using the following method: joints_wheels_->GetChild()->RelativePose();. This will return the pose relative to the base link of the robot instead of the previous link (which is the "base_motors_platform_link" in the example above).
Output
As result of this, the transformation of the wheels is incorrect and the representation on RVIZ looks like this:
The representation on Gazebo looks fine, so I assume my URDF is good
As per the URDF that I defined, the relative pose in X and Z should be 0.0 0.0 when the model spawns, however this is not the case.
[gazebo-1] Relative Pose: 0.242962 0.157838 -0.091999 -0.000238 -0.039842 0.044572
I hope my explanation is clear. If something else is necessary, I can provide more information.
Thank you.
The text was updated successfully, but these errors were encountered:
In case of links, I think the "parent" entity of the link is the parent model, but I am not sure, probably you can find out this by looking for the use of the Link constructor in the Gazebo codebase.
If that is the case, do you have any suggestions on how to improve the docs?
So, this leads me to believe that for most of the developers, the documentation is clear. For the ones that the documentation is not clear, I hope they find your explanation useful :)
To find the transformation between the child and the parent link, this did the trick for me:
auto pose_wheel = joint->GetChild()->RelativePose() - joint->GetParent()->RelativePose();
Great! Just a small comment, the Pose3::operator- method has been deprecated in ign-math7 as it was not super intuitive its semantics, see gazebosim/gz-math#60 . This is not a super big problem in the context of Gazebo Classic, as Gazebo Classic will never move to another version of ign/gz math. Anyhow, if you want to write the code in a way that is more intuitive to people used to homogeneous matrix operation, you can write:
Environment
Description
Steps to reproduce
joints_wheels_->GetChild()->RelativePose();
. This will return the pose relative to the base link of the robot instead of the previous link (which is the "base_motors_platform_link" in the example above).Output
As result of this, the transformation of the wheels is incorrect and the representation on RVIZ looks like this:


The representation on Gazebo looks fine, so I assume my URDF is good
As per the URDF that I defined, the relative pose in X and Z should be 0.0 0.0 when the model spawns, however this is not the case.
[gazebo-1] Relative Pose: 0.242962 0.157838 -0.091999 -0.000238 -0.039842 0.044572
I hope my explanation is clear. If something else is necessary, I can provide more information.
Thank you.
The text was updated successfully, but these errors were encountered: