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

Support "mechanical reduction" in MultibodyPlant urdf parser #21948

Open
RussTedrake opened this issue Sep 25, 2024 · 8 comments
Open

Support "mechanical reduction" in MultibodyPlant urdf parser #21948

RussTedrake opened this issue Sep 25, 2024 · 8 comments
Assignees

Comments

@RussTedrake
Copy link
Contributor

RussTedrake commented Sep 25, 2024

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.

// Parse and add the optional drake:rotor_inertia parameter.
XMLElement* rotor_inertia_node =
actuator_node->FirstChildElement("drake:rotor_inertia");
if (rotor_inertia_node) {
double rotor_inertia;
if (!ParseScalarAttribute(rotor_inertia_node, "value", &rotor_inertia)) {
Error(*rotor_inertia_node,
fmt::format("joint actuator {}'s drake:rotor_inertia does not have"
" a \"value\" attribute!", actuator_name));
return;
}
plant->get_mutable_joint_actuator(actuator.index())
.set_default_rotor_inertia(rotor_inertia);
}
// Parse and add the optional drake:gear_ratio parameter.
XMLElement* gear_ratio_node =
actuator_node->FirstChildElement("drake:gear_ratio");
if (gear_ratio_node) {
double gear_ratio;
if (!ParseScalarAttribute(gear_ratio_node, "value", &gear_ratio)) {
Error(*gear_ratio_node,
fmt::format("joint actuator {}'s drake:gear_ratio does not have a"
" \"value\" attribute!", actuator_name));
return;
}
plant->get_mutable_joint_actuator(actuator.index())
.set_default_gear_ratio(gear_ratio);
}

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.

@RussTedrake RussTedrake added component: multibody parsing Loading models into MultibodyPlant and removed component: multibody plant MultibodyPlant and supporting code labels Sep 25, 2024
@jwnimmer-tri jwnimmer-tri changed the title Support "mechanical reduction" and <motorInertai> in MultibodyPlant urdf parser Support "mechanical reduction" and <motorInertia> in MultibodyPlant urdf parser Sep 25, 2024
@jwnimmer-tri
Copy link
Collaborator

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
Copy link
Contributor Author

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.

@RussTedrake RussTedrake changed the title Support "mechanical reduction" and <motorInertia> in MultibodyPlant urdf parser Support "mechanical reduction" in MultibodyPlant urdf parser Sep 25, 2024
@rpoyner-tri
Copy link
Contributor

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
Copy link
Contributor Author

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

@jwnimmer-tri
Copy link
Collaborator

jwnimmer-tri commented Sep 25, 2024

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
Copy link
Contributor

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
Copy link
Collaborator

jwnimmer-tri commented Sep 26, 2024

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
Copy link
Contributor Author

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.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
Status: No status
Development

No branches or pull requests

4 participants