Closed torydebra closed 1 year ago
The reason is the following: It's important that the base_link is in the center of rotation of the robot (and at floor level, z=0). This simplifies many odometry calculations, and this is also what the real MiR uses, so we cannot change that. The center of rotation is in the middle (in y direction) of the active wheel axis.
However, the MiR 100 is not symmetrical in the x direction (= front/back direction): The active wheel axis is not in the center of the robot's bounding box, but shifted back by about 0.037 meters in the x direction - the front part of the robot is longer than the rear part. This is why mir_act_wheel_dx = 0.037646
(I simply measured the value from the mesh), and why we cannot shift the base_link to the center of the bounding box.
Ok, thanks for the clarification!
We have an arm mounted on the platform and we noticed some misalignment.
We will put this mir_act_wheel_dx
in the arm link as well
Hi, I noticed that the visual mesh of the base_link has a origin not in 0 0 0, but shifted on the x of
mir_act_wheel_dx
: https://github.com/dfki-ric/mir_robot/blob/ca5f1fea90f9d034afd7e6c66b1e649f0b492bfb/mir_description/urdf/include/mir_v1.urdf.xacro#L199-L200Being a shift of the visual and not on the parent joint, the link stay where it is and all the sons link need this shift as well to be aligned, eg the lasers: https://github.com/dfki-ric/mir_robot/blob/ca5f1fea90f9d034afd7e6c66b1e649f0b492bfb/mir_description/urdf/include/mir_v1.urdf.xacro#L249-L254
Why this? Can not this shift be embedded in the wheels link, since it should be related to the wheel (as the variable name suggests)?