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

Introduced floating base propeller actuation model #1213

Merged
merged 8 commits into from
Jan 25, 2024

Conversation

cmastalli
Copy link
Member

@cmastalli cmastalli commented Jan 23, 2024

This PR introduces a new actuation model that encapsulates floating base systems equipped with propellers in their base. This class replaces our previous actuation model for multi-copters, which was designed to pass a torque-mapping matrix. This old design is unintuitive and hard codes that propellers are oriented along the robot's z-axis in inverse dynamics formulations.

In a nutshell, we can model easily other types of systems such as marine robots.

Apart from this new model, the PR includes:

  • Deprecation of the multi-copter actuation model
  • Unit test for this new actuation model
  • Examples based on this new model

In future, I plan to extend this actuation to cases where the propellers are placed in the robot's limbs. For an efficient implementation, this will require changes in the actuation API which I prefer to avoid now.

@PepMS -- I am sure you want to know about this.

@PepMS
Copy link
Contributor

PepMS commented Jan 24, 2024

Thanks for the info, @cmastalli; I will probably use this modification.

I want to point some things out, though.

First, it is not true that the old matrix tau_f "hard codes that propellers are oriented along the robot's z-axis." The old "tau_f" variable, known in some literature as the thrust allocation matrix, allows you to map the thrust to the base wrench as you please. Its dimensions are $6 \times n_{rot}$, being $n_{rot}$ the number of rotors in your base. So, with this design, it was up to the user to find the specific allocation matrix for their application. In the particular case of planar multirotors (all rotors' axis of rotation perpendicular to the multirotor's base), the allocation matrix has zeros in its two first rows.

I agree with you that what you propose is, indeed, a more user-friendly design. In fact, I have a similar structure in a library independent of Crocoddyl.

Second, in your model, is there any reason you want to include the two aerodynamical constants cf and cm? In the old design, these variables could be joined in a single variable that maps thrust to drag torque (the torque produced along the rotor's axis of rotation due to drag). The only reason (I can think of) why you would need the c_f variable (mapping the square of the speed to the thrust) is that you want the speed of the motors to be the control input. However, if that is the reason, you can keep a more straightforward model by having thrusts as inputs and then compute the speed of the motors outside the OCP.

@cmastalli
Copy link
Member Author

Hi @PepMS!

The multi-copter actuation was hard coding the propeller direction in inverse dynamics formulations. I agree with what you wrote for forward dynamics formulations only. I must also clarify that this is possible to fix, but I won't as the class is deprecated.

We could keep a single coefficient as you seem to suggest. The reasons that I like two are

  • these are well known parameters in the literature.
  • we can compute propeller velocities, and the thrust limits for imposing control bounds.

I should include this second bulletpoint in this PR (before merging). What are your thoughts on?

@PepMS
Copy link
Contributor

PepMS commented Jan 24, 2024

Suppose these parameters are only used to compute the drag torque by dividing them. In that case, I suggest using only one parameter, and you can mention that this parameter is the quotient between both in the documentation. Another option would be to have a constructor with both known variables, and then you only keep the quotient.

I have a few observations to do regarding the computation of propeller velocities:

  1. If you use the constant to compute propeller velocities, you assume the quadratic aerodynamical model, which is simplistic. Some people more complex functions to model the aerodynamics of the rotors.
  2. I ask myself if Crocoddyl is the right place to do these computations. A similar case for the legged robots would be to add the torque-to-current constants for the joints of a legged robot.
  3. In many cases, the computation of rotor velocities is not very useful since the majority of motor speed controllers (ESCs) do not perform speed closed-loop control. Instead, they accept a percentage of maximum throttle, i.e., a variable from 0 to 1, being one full speed, whatever full speed is. That percentage relates very much to the speed of the motor but also depends on other variables, mainly on the battery voltage. For example, we use a polynomial mapping whose inputs are the required thrust and battery voltage, which directly outputs the throttle percentage. We identify this polynomial with a test bench.
  4. I guess you mention the thrust limits because it is easier to know the motor speed limits than the thrust limits. That is true, but the quadratic model loses validity at the extremes. For better consistency, I advocate using thrusts and torques everywhere and not including motor speeds, leaving the aerodynamic model up to the users' choice.

I hope this makes sense :)

@cmastalli
Copy link
Member Author

Suppose these parameters are only used to compute the drag torque by dividing them. In that case, I suggest using only one parameter, and you can mention that this parameter is the quotient between both in the documentation. Another option would be to have a constructor with both known variables, and then you only keep the quotient.

I have a few observations to do regarding the computation of propeller velocities:

  1. If you use the constant to compute propeller velocities, you assume the quadratic aerodynamical model, which is simplistic. Some people more complex functions to model the aerodynamics of the rotors.
  2. I ask myself if Crocoddyl is the right place to do these computations. A similar case for the legged robots would be to add the torque-to-current constants for the joints of a legged robot.
  3. In many cases, the computation of rotor velocities is not very useful since the majority of motor speed controllers (ESCs) do not perform speed closed-loop control. Instead, they accept a percentage of maximum throttle, i.e., a variable from 0 to 1, being one full speed, whatever full speed is. That percentage relates very much to the speed of the motor but also depends on other variables, mainly on the battery voltage. For example, we use a polynomial mapping whose inputs are the required thrust and battery voltage, which directly outputs the throttle percentage. We identify this polynomial with a test bench.
  4. I guess you mention the thrust limits because it is easier to know the motor speed limits than the thrust limits. That is true, but the quadratic model loses validity at the extremes. For better consistency, I advocate using thrusts and torques everywhere and not including motor speeds, leaving the aerodynamic model up to the users' choice.

I hope this makes sense :)

Everything makes sense and appreciate your feedback.

The actions that I see are:

  • Keeping a single coefficient and describing the actuation at the level thrusters.
  • Use the word "Thrust" instead of "Propeller"
  • Add scalars for min/max thrust

I will start working on this. Please let me know if there is something you might to add.

@cmastalli
Copy link
Member Author

@PepMS -- could you review the new changes?

@cmastalli cmastalli merged commit 38c9eb3 into loco-3d:devel Jan 25, 2024
9 of 14 checks passed
@cmastalli cmastalli deleted the topic/propellers branch January 25, 2024 21:01
nim65s added a commit to nim65s/robotpkg that referenced this pull request May 31, 2024
Changed in v2.1.0:

* Updated black + isort + flake8 to ruff in loco-3d/crocoddyl#1256
* Exported version for Python in loco-3d/crocoddyl#1254
* Added pinocchio 3 preliminary support in loco-3d/crocoddyl#1253
* Updated CMake packaging in loco-3d/crocoddyl#1249
* Fixed ruff reported error in loco-3d/crocoddyl#1248
* Fixed yapf reported errors in loco-3d/crocoddyl#1238
* Tested Python stubs in Conda CI in loco-3d/crocoddyl#1228
* Fixed Rviz display in loco-3d/crocoddyl#1227
* Improved CI, updated cmake and fixed launch file in loco-3d/crocoddyl#1220
* Introduced a Rviz display in loco-3d/crocoddyl#1216
* Enabled display of thrust and simplied displayers code in loco-3d/crocoddyl#1215
* Introduced floating base thruster actuation model in loco-3d/crocoddyl#1213
* Fixed quadruped and biped examples in loco-3d/crocoddyl#1208
* Fixed terminal computation in Python models in loco-3d/crocoddyl#1204
* Fixed handling of unbounded values for `ActivationBounds` in loco-3d/crocoddyl#1191
nim65s added a commit to nim65s/robotpkg that referenced this pull request Jun 20, 2024
Changed in v2.1.0:

* Updated black + isort + flake8 to ruff in loco-3d/crocoddyl#1256
* Exported version for Python in loco-3d/crocoddyl#1254
* Added pinocchio 3 preliminary support in loco-3d/crocoddyl#1253
* Updated CMake packaging in loco-3d/crocoddyl#1249
* Fixed ruff reported error in loco-3d/crocoddyl#1248
* Fixed yapf reported errors in loco-3d/crocoddyl#1238
* Tested Python stubs in Conda CI in loco-3d/crocoddyl#1228
* Fixed Rviz display in loco-3d/crocoddyl#1227
* Improved CI, updated cmake and fixed launch file in loco-3d/crocoddyl#1220
* Introduced a Rviz display in loco-3d/crocoddyl#1216
* Enabled display of thrust and simplied displayers code in loco-3d/crocoddyl#1215
* Introduced floating base thruster actuation model in loco-3d/crocoddyl#1213
* Fixed quadruped and biped examples in loco-3d/crocoddyl#1208
* Fixed terminal computation in Python models in loco-3d/crocoddyl#1204
* Fixed handling of unbounded values for `ActivationBounds` in loco-3d/crocoddyl#1191
nim65s added a commit to nim65s/robotpkg that referenced this pull request Jul 1, 2024
Changed in v2.1.0:

* Updated black + isort + flake8 to ruff in loco-3d/crocoddyl#1256
* Exported version for Python in loco-3d/crocoddyl#1254
* Added pinocchio 3 preliminary support in loco-3d/crocoddyl#1253
* Updated CMake packaging in loco-3d/crocoddyl#1249
* Fixed ruff reported error in loco-3d/crocoddyl#1248
* Fixed yapf reported errors in loco-3d/crocoddyl#1238
* Tested Python stubs in Conda CI in loco-3d/crocoddyl#1228
* Fixed Rviz display in loco-3d/crocoddyl#1227
* Improved CI, updated cmake and fixed launch file in loco-3d/crocoddyl#1220
* Introduced a Rviz display in loco-3d/crocoddyl#1216
* Enabled display of thrust and simplied displayers code in loco-3d/crocoddyl#1215
* Introduced floating base thruster actuation model in loco-3d/crocoddyl#1213
* Fixed quadruped and biped examples in loco-3d/crocoddyl#1208
* Fixed terminal computation in Python models in loco-3d/crocoddyl#1204
* Fixed handling of unbounded values for `ActivationBounds` in loco-3d/crocoddyl#1191
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.

2 participants