RobotLocomotion / drake

Model-based design and verification for robotics.
https://drake.mit.edu
Other
3.27k stars 1.26k forks source link

Support "mechanical reduction" in MultibodyPlant urdf parser #21948

Open RussTedrake opened 5 days ago

RussTedrake commented 5 days ago

I've found myself wanting to parse a urdf that has actuators specified with a <mechanicalReduction> tag whose value is far from 1. The URDF parser current warns

warning: A 'actuator' element contains a mechanicalReduction element with a value '113.90625' other than the default of 1. MultibodyPlant does not currently support non-default mechanical reductions.

In fact, I think we added support for gear ratios in #14167.

The urdf actuators also have a <motorInertia> specified. These tags are silently ignored.

More bizarre, we actually do support these things, but via custom <drake:rotor_inertia> and <drake:gear_ratio> tags. https://github.com/RobotLocomotion/drake/blob/8c7133c16d91b6ef6bae5e2cd844c31def53e3f7/multibody/parsing/detail_urdf_parser.cc#L832-L860

Is it possible that the urdf spec changed since we added these?

My ask is that we do support the real urdf tags.

Possibly we can/should deprecate the drake custom tags and update any urdfs that we've authored with them? cc @joemasterjohn who authored the initial support.

jwnimmer-tri commented 5 days ago

The urdf actuators also have a <motorInertia> specified.

I might not understand what you're saying here. Is your impression that this is a standard URDF element? I looked through https://wiki.ros.org/urdf/XML and couldn't find it specified anywhere. If you have a pointer to its spec, that would would help unblock.

RussTedrake commented 5 days ago

Oh. You're right. I linked to the urdf spec for mechanicalReduction, and assumed that the other tag was juxtaposed. Ok, I think leaving drake:rotor_inertia as the recommended workflow is correct. I'll amend the description.

rpoyner-tri commented 5 days ago

To my knowledge, URDF has never had any sort of change control or release process. By contrast, SDFormat has spec versions, with defined content. I would agree with Nimmer's idea that the web site is the closest thing we will get to a spec. Still there are files out there in the wild with all sorts of variations of transmission, etc., that are not mentioned in the web site. I suspect that Gazebo or some other simulator software implemented those at one time.

I don't disagree that an argument could be made for accepting more variations of URDF files. That is work we could choose to do. I'm not sure that finding some alternate construction in the wild that overlaps with a drake extension automatically means we should deprecate the drake extension.

RussTedrake commented 5 days ago

@rpoyner-tri -- <mechanicalReduction> is specified on the website. am I missing something?

jwnimmer-tri commented 5 days ago

I interpreted Rico's comment as only scoped to motorInertia -- that if the community at large has already pseudo-standardized motorInertia by just hacking it into whatever parsers they have, then we could plausibly follow suit in Drake.

In any case, I think it's good to keep this ticket scoped to only be about accepting a non-unity mechanicalReduction.

amcastro-tri commented 4 days ago

Reading the docs pointed to by @RussTedrake, I do not understand what the purpose of the <mechanicalReduction> element is.

  1. There doesn't seem to be rotor inertia associated with it, so it doesn't seem its purpose is to model reflected inertia, am I wrong?
  2. Is its only purpose to scale velocites/torques? why? are people modeling the torque on the actual shaft of the motor? that to me seems very strange (since I believe most torque controlled robots measure torque at the joint's shaft, the one that actually matters). That being said, is that even useful? what am I missing here?

Altogether, I do not yet understand what the requested feature is.

jwnimmer-tri commented 4 days ago

My understanding is that <mechanicalReduction> is thought to be a synonym for <drake:gear_ratio>, so the request is to support people saying <mechanicalReduction>#.#<mechanicalReduction> instead of <drake:gear_ratio value='#.#'/>. Under either syntax, the parser would call actuator.set_default_gear_ratio(#.#).

The user would still say <drake:rotor_inertia ... /> to specify the inertia.

RussTedrake commented 21 hours ago

Is its only purpose to scale velocites/torques? why? are people modeling the torque on the actual shaft of the motor? that to me seems very strange (since I believe most torque controlled robots measure torque at the joint's shaft, the one that actually matters). That being said, is that even useful? what am I missing here?

@amcastro-tri -- yes, as I've said repeatedly (#20993), I believe most people model actuator input in motor coordinates, not joint coordinates. I won't restart that battle again here; but I do believe that the existence of only mechanical reduction w/o rotor inertia in the urdf spec does support my point.