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

Controlling Crazyflie through RPMs (PWM) #244

Open
piratax007 opened this issue Nov 11, 2024 · 3 comments
Open

Controlling Crazyflie through RPMs (PWM) #244

piratax007 opened this issue Nov 11, 2024 · 3 comments
Labels
question Further information is requested

Comments

@piratax007
Copy link

Hello, I have successfully trained a policy for setpoint tracking using RPM as action space. Now I'm trying to deploy it to a real Crazyflie using a ROS2 package (Crazywarm and Vicon system). As you refer to in #118, exists an empirical study of the relation between PWM and RPMs for Crazyflie (https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/functional-areas/pwm-to-thrust/). My question, is that using the data from that study and comparing with the transformation used by GymPybullet I found high discrepancies as is shown in the plot. The black line corresponds with the linear transformation used by GymPybyllet.
Crazyflie_RPM_vs_PWM
Could you help me to understand this and how can affect the transferability of the trained policy to a real drone?

Thank you so much

@JacopoPan JacopoPan added the question Further information is requested label Nov 26, 2024
@JacopoPan
Copy link
Member

The relation between RPMs and thrust in gym-pybullet-drones is modeled as quadratic:

forces = np.array(rpm**2)*self.KF
torques = np.array(rpm**2)*self.KM

There assumption of linearly between RPMs and PWM (that don't fully hold away from a hover range) in DSLPIDControl.py and CFAviary.py but those shouldn't come into play if you purely trained RL for RPMs in a class derived from BaseRLAviary.py

@piratax007
Copy link
Author

I understand that training using RPMs as actions space the conversion to PWM doesn't play a role. Nevertheless, transferring a policy trained to produce RPMs to a real Crazyflie, requires translating the RPM to PWM because the lowest control signal received by the Crazyflie firmware is PWM.

BaseRLAviary translates the policy outputs to RPM through

target = action[k, :]
if self.ACT_TYPE == ActionType.RPM:
    rpm[k,:] = np.array(self.HOVER_RPM * (1+0.05*target))

Then, to obtain the PWM should be applied:

$PWM = \dfrac{RPM - 4070.3}{0.2685}$

Is it correct?

@JacopoPan
Copy link
Member

In BaseAviary, the relationship between RPMs and thrust is a simple quadratic one using coefficient kf="3.16e-10" which is taken from the system identification resources lined in the .urdf

<!-- links>
      <carlos url="https://arxiv.org/pdf/1608.05786.pdf" />
      <julian url="https://www.research-collection.ethz.ch/handle/20.500.11850/214143" />
      <mit url="http://groups.csail.mit.edu/robotics-center/public_papers/Landry15.pdf" />
</links -->

If you want to go by the system identification in https://www.bitcraze.io/documentation/repository/crazyflie-firmware/master/functional-areas/pwm-to-thrust/ you should modify

forces = np.array(rpm**2)*self.KF

so that thrust = 1.0942e-07rpm^2 - 2.1059e-04rpm + 1.5417e-01 instead
and then consider that thrust = 0.409e-03rpm^2 - 140.5e-03rpm - 0.099 when you want to derive the corresponding PWM command

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
question Further information is requested
Projects
None yet
Development

No branches or pull requests

2 participants