Open RussTedrake opened 8 months ago
Related to #20975.
Proposal: If we agree on motor units,
The reason we have joint torques units is intentional. I agree we should at least document it though to make this very explicit. Now, there might be the question of whether this is the right thing or not. My understanding is that robot hardware offers the user an interface to command joint torques, not motor torques (my understanding here is that the actual relationship between these two could be so non-linear that additional low level electronics and sensing is required). So, does it have any value to offer users with the motor torques option? I can see how this could back fire, with users having to write the conversion back to joint torques by hand themselves.
Thoughts?
per f2f. Russ is collecting info from other users. In many roboticists minds the expectation is to see the gear ratios in the B matrix.
For reference, MuJoCo's actuators have the convention that actuation inputs uᵢ
are in motor units with the documented mapping p
to generalized forces. Gear ratios appear in the definition of the scalar length function lᵢ(q)
for each actuator, the relationship is described here. I don't think they provide an equivalent of what we call the B
matrix directly (since they have a more general and affine model of actuation), but if I'm reading the docs right the equivalent would be [∇ lᵢ(q)]
if all of the actuators are modeled as single-dof motors with gearbox. All this seems to support Russ's proposal here.
I ran into this problem a few times. Most hardware I have seen wants joint torques. However, in simulation I would love to see a setup that includes dc motor dynamics. Commanding motor torques goes into the right direction of proper actuation modeling. To simulate a joint torque robot I am thinking about this: tau_joint_d -> tau_motor_d = tau_joint_d / N -> dc motor dynamics -> tau_motor_commanded (actuation input port)
Thank you for the feedback @wrangelvid.
I ran into this problem a few times. Most hardware I have seen wants joint torques.
That seems to indicate your preferred API is one that drives jont torques directly? The topic of this issue is whether to input joint torques or motor torques. Your feedback is obviously appreciated. Thanks.
in simulation I would love to see a setup that includes dc motor dynamics.
That'd be a nice feature to have for sure. I believe however it does not belong to what we are discussing in this issue. This issue is about MultibodyPlant, and the modeling of "mechanical" components. The system framework in Drake allows you to write a specialized system to model DC motors (or any other motor dynamics) and connect to MultibodyPlant trough actuation ports (plant eats torques, not currents). This in on purpose, to provide modularity. If the modeling of motors is something that interests you, I'd suggest you open a separate issue with a description of the feature you'd like to see in Drake.
That seems to indicate your preferred API is one that drives jont torques directly? The topic of this issue is whether to input joint torques or motor torques. Your feedback is obviously appreciated. Thanks.
I prefer driving the motor torques directly. However, since there there is a nice desired joint state input port, it would be strange if we would loose the option to command feedforward joint torques.
This would also require some care on the Jacobian. The JacobianWrtVariable states that the variable will be in generalized coordinates:
Enumeration that indicates whether the Jacobian is partial differentiation with respect to q̇ (time-derivatives of generalized positions) or with respect to v (generalized velocities).
However, commanding motor torques may benefit from deriving with respect to the motor velocities. For example, in operational space control, when compensating for the end-effector Mass $(JM^{-1}J^T)^{-1}$, the jacobian would typically include the transmission ratios.
In my mind, the use of joint torques rather than motor torques is consistent with using a diagonal approximation for reflected inertia, rather than explicitly modeling the actuator rotor inertia as an extra rigid body in the simulation. Also , for what it's worth, Cassie expects us to send it joint torques, not motor torques.
However, since there there is a nice desired joint state input port,
This would also require some care on the Jacobian.
However, commanding motor torques may benefit from deriving with respect to the motor velocities
Sorry @wrangelvid, but I am not sure how any of those relate to this discussion?
In my mind, the use of joint torques rather than motor torques is consistent with using a diagonal approximation for reflected inertia,
It actually can go either way. In the end we will always model the motor using a reflected ineratia (which is a great approximation by the way). It's a matter of preference and proper documentation. In this issue we are asking for user perference; joint torque vs motor torque.
Also , for what it's worth, Cassie expects us to send it joint torques, not motor torques.
Isn't this true for every robot that provides torque control?
Is the proposal also to change joint position ports to be in motor shaft radians rather than joint radians? For joint velocity ports to be in motor speeds rather than joint speeds?
My inclination is to stay consistently on the the output shaft of the gearbox.
To broaden the solution space, also let me point out I think we could offer both units? When the user asks for a port or a parameter or a jacobian or actuation matrix or whatever, we could have a function argument that specifies which units they want. If we can all agree on a single choice to use everywhere that's perfect, but it sounds like maybe not everyone agrees so it might need be an option.
@ggould-tri wrote
Is the proposal also to change joint position ports to be in motor shaft radians rather than joint radians? For joint velocity ports to be in motor speeds rather than joint speeds?
Fwiw, I don't see this as a problem. We have an "actuation matrix" (typically B) whose job is to convert from actuator units to generalized coordinates.
Again, I would ask people to consider the case of a differential drive. I think this exacerbates/clarifies the issue. (Even if it does not change any minds).
Again, I would ask people to consider the case of a differential drive. I think this exacerbates/clarifies the issue. (Even if it does not change any minds).
We have that problem with Spot. The lower level API takes in joint position, velocities and torque commands on the generalized coordinates. However, the knee joint is a prismatic actuator that is coupled to the shin with a simple linkage. The API abstracts the linkage away and replaces it with a revolute joint. But now the joint torque limits become configuration dependent, while the actual motor torque limit remains constant.
If we had an API considering tapping in both the joint and motor (actuator) interface, we could add a differential transmission that takes a Jacobian, imposes the torque limits on the actuator, but still uses the build in desired state and feed forward joint torque API to replicate the behavior of the actual Spot more precisely.
I am in favor for @jwnimmer-tri suggestion to support both workflows.
Since it seems there is significant support for keeping the "actuation input is joint torques", then I'm now slightly more in favor of documenting and only supporting that workflow, rather than carrying both. It's certainly the less disruptive change. I worry that trying to support all workflows with options is more confusing and too non-committal.
If one does want to model at the motor level (even a differential drive with two motors driving two joints), this would still be possible, but it would happen outside of the multibodyplant, with an actuator model that does this implementation to compute the joint torque which gets passed into the MbP.
We clearly need to document what is currently implemented better.
@amcastro-tri -- ping on this.
@amcastro-tri -- can you please take care of this or delegate?
The recent addition of support for reflected inertia introduced the concept of a gear ratio. Before this PR, the actuation input port clearly had units of generalized force (e.g. joint torque). The current implementation still has these units.
The documentation is unclear now on whether the units of actuation input ports are in motor coordinates or in joint coordinates. For me, the term "actuation input" suggests that it should be in the motor units, not the joint units. This would suggest that we should multiply the actuation input u by the gear ratio to achieve the generalized force. (And
MakeActuationMatrix
should not be a binary matrix, it should have the gear ratios inside it).Proposal: If we agree on motor units, then we should make the change and rip the bandaid off. This impacts people who are setting non-zero gear ratio; these values only recently began to have any effect. Most users are connecting to the input port through a controller which should protect them from any change here. But I believe that the current code is wrong (would not match other simulator implementations... though we could check that).
Related (and coupled). If
MakeActuationMatrix
continues to be only a binary matrix, which does not depend in any way on the context, then it should return aSparseMatrix<double>
. Currently it returns aMatrixX<T>
. But there is no way for any non-double values to be there, and working withMatrixX<T>
is more painful in some pipelines. If the matrix can take values which include the gear ratio, and the gear ratio is ever a parameter in theContext
, thenMakeActuationMatrix
would become a function of the context, and return aMatrixX<T>
. I would preferSparseMatrix<T>
, but am weary of #19712.As we resolved this, let's also not forget effort limits. I remember now that folks were confused about whether the effort limits was in motor torque or joint torque. (It is currently joint torque, but i'm not sure that's correct).
One other thing to help us think about the longer-term correct solution: consider future support of differential drive joints. For instance, littledog had two motors controlling two dofs -- when the spin together that makes one joint move, and when the spin in the opposite directions, the other joint moves. In this case, the submatrix of B would look something like [1,-1; 1, 1], or the gear ratios times that.
Somewhat related to #20992.