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

gazebo_plugins fix inverted left and right wheel #397

Conversation

cyborg-x1
Copy link

Left and right wheel are inverted - if you put in the real right wheel
in the previous state of the plugin the robot drives into the opposite direction.
Also the formula in another book of the same author says sr-sl instead of sl-sr.
(found online with Google). Did not find the one where it is on page 337 btw.
I tested encoder and world for odometry - seems to work fine.

Left and right wheel are inverted - if you put in the real right wheel
in the previous state of the plugin the robot drives into the opposite direction.
Also the formula in another book of the same author says sr-sl instead of sl-sr.
(found online with Google). Did not find the one where it is on page 337 btw.
I tested encoder and world for odometry - seems to work fine.
@cyborg-x1 cyborg-x1 changed the title gazebo_plugins fix #317 fix inverted left and right wheel gazebo_plugins fix inverted left and right wheel Feb 27, 2016
@cyborg-x1
Copy link
Author

Guys, any comments?

Guess that Travis Error is not my fault:

Policy CMP0046 is not set: Error on non-existent dependency in
add_dependencies. Run "cmake --help-policy CMP0046" for policy details.
Use the cmake_policy command to set the policy and suppress this warning.

My code does just change a few lines of the cpp. They compile for me without error.

@scpeters
Copy link
Member

I think that warning is not related to this PR.

@scpeters
Copy link
Member

This depends on coordinate frames and sign conventions. Has anyone else experienced this issue?

@cyborg-x1
Copy link
Author

It is related to #317

@scpeters
Copy link
Member

thanks, I hadn't noticed the link to that issue.

@cyborg-x1
Copy link
Author

You're welcome. ;-)

@gerkey
Copy link

gerkey commented Feb 29, 2016

We worked around this issue in our example code like so: https://github.com/osrf/rosbook/blob/master/code/tortoisebot/tortoisebot_nav.urdf#L155-L156. I'm pretty sure that it's just always been backward. I suppose that there's a risk of fixing this problem and then breaking everybody who's been working around it.

@scpeters
Copy link
Member

That's what I'm worried about, that the "fix" will break everyone's code.

@cyborg-x1
Copy link
Author

Well we could put a invert wheels setting which is currently set on standard with a warning when you not set it ...

@scpeters
Copy link
Member

Instead of calling it "invert wheels", perhaps we could just be explicit about the coordinate frame it's using. I think the current setting is "correct" if the coordinate frame has the Z axis pointing down, which is actually not uncommon for vehicles:

@cyborg-x1
Copy link
Author

More like z_axis_direction (up/down) then? But I wonder, I tried to rotate my wheels to whatever, it never worked for me ... Is there a working example somewhere where the right wheel is actually the right and left the left and it works correctly with cmd_vel message?

@scpeters
Copy link
Member

Is there a canonical definition of the coordinate frame for the cmd_vel topic?

@gerkey
Copy link

gerkey commented Feb 29, 2016

REP 105 defines the frames used with mobile platforms: http://www.ros.org/reps/rep-0105.html#coordinate-frames. And REP 103, referenced from 105, further specifies that Z should be up: http://www.ros.org/reps/rep-0103.html#coordinate-frame-conventions.

@cyborg-x1
Copy link
Author

So then I guess the question is more like how to call the parameter that everyone does not need to fix it in his code but gets a warning ...what about "legacy_mode" ?

@cyborg-x1
Copy link
Author

Would you agree on this:

gazebo_ros_->getParameterBoolean ( legacy_mode_, "legacyMode", true );

if (!_sdf->HasElement("legacyMode")) 
{
  ROS_ERROR("GazeboRosDiffDrive Plugin missing <legacyMode>, defaults to true\n" 
       "This setting assumes you have a old package where the right and left wheel are changed to fix a former code issue\n"
       "To get rid of this error just set <legacyMode> to false if you just created a new package.\n"
       "To fix an old package you have to exchange left wheel by the right wheel.\n"
       "If you do not want to fix this issue in an old package or your z axis points down instead of the ROS standard defined in REP 103\n"
       "just set <legacyMode> to true.\n"
  );
}

@gerkey
Copy link

gerkey commented Mar 1, 2016

@cyborg-x1 That approach seems to me like the best path forward. We'll have to decide how long to let this warning sit before switching the default behavior, and whenever we do that, we'll surely still break some systems where they didn't notice or care about the warning. But I don't see a better alternative.

@cyborg-x1
Copy link
Author

I changed my code and tested it with my robot model in Gazebo. Works for me in both ways. New and legacy mode (when swapping the wheels).

@cyborg-x1
Copy link
Author

Anything else I need to do? Otherwise it could be merged, I guess

@nkoenig
Copy link
Member

nkoenig commented Apr 26, 2016

This looks good to me. Thanks.

@nkoenig nkoenig merged commit cf95acb into ros-simulation:jade-devel Apr 26, 2016
@jacquelinekay
Copy link
Contributor

Can someone make sure that this change gets noted in the Migration guide? http://wiki.ros.org/kinetic/Migration

@nkoenig
Copy link
Member

nkoenig commented Apr 26, 2016

Working on it now.

@nkoenig
Copy link
Member

nkoenig commented Apr 26, 2016

migration guide updated.

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

Successfully merging this pull request may close these issues.

5 participants