Spool process understanding

Hi all,

Currently studying the code base and trying to understand the ‘spool’ functionality. Spooling is quite useful for some of my applications and so I’d like to understand it fully before changing my fork and submitting PRs etc.

Files I have been studying:
AP_Motors/AP_MotorsMulticopter.h and .cpp
AP_Motors/AP_Motors_Class.h and .cpp
arducopter/motors.cpp

So I understand that the spool time (controlled by paramters MOT_SPOOL_TIME and optionally MOT_SPOOL_TIM_DN) is the time taken to move the motor output signal between 0 and min throttle.

I’m getting a bit confused about some of the spool control states and variables in the code. I’d like to understand the logical flow that occurs between having a ‘disarmed’ quad and an ‘armed’ quad on the ground with the motors spinning at MOT_SPIN_ARM.

  1. What is ‘GROUND_IDLE’?
    Intuitively I would have assumed that this case was the ‘armed’ and motors spinning at ‘min’ speed with zero thrust command. However, the comments in the code suggest that the motors could also be stationary in GROUND_IDLE.

  2. What is _spin_up_ratio?
    Kind of related to 1. As I understand it, it’s simply a fractional expression of where we are in the spooling process. I.e. if _spin_up_ratio=0, output to the motors is 0, if _spin_up_ratio=1, output to the motors is MOT_SPIN_ARM. Is this correct?
    However if this is the case, I’m a bit confused about the below code from AP_MotorsMulticopter.cpp. It implies that when in state GROUND_IDLE and trying to transition to THROTTLE_UNLIMITED, that the _spin_up_ratio is ramped to achieve this. I would have thought that in GROUND_IDLE, _spin_up_ratio should already =1.

case SpoolState::GROUND_IDLE: {
...
   case DesiredSpoolState::THROTTLE_UNLIMITED: {
      const float spool_step = _dt_s / _spool_up_time;
      _spin_up_ratio += spool_step;
      // constrain ramp value and update mode
      if (_spin_up_ratio >= 1.0f) {
          _spin_up_ratio = 1.0f;
          if (!get_spoolup_block()) {
              // Only advance from ground idle if spoolup checks have passed
              _spool_state = SpoolState::SPOOLING_UP;
          }
      }
      break;
    }
...
}

I guess it’s confusing to me that _spin_up_ratio seems to ‘spool’ here, and only once _spin_up_ratio=1 do we set _spool_state = SpoolState::SPOOLING_UP. I think I must be misunderstanding what GROUND_IDLE actually means.

  1. What is the relationship between _spin_up_ratio and _throttle_thrust_max?
    Assuming my thinking in 1. and 2. is correct, what purpose is _throttle_thrust_max serving in the spooling process? Since the spooling only applies between 0 ↔ MOT_SPIN_ARM, why is a limit required that seems to cover the full throttle scale?

Sorry if this is all a bit messy, just trying to get my understanding right. Any sort of guide here would be appreciated, even if you can’t answer specifics of the questions!

Thanks

Okay I’ve spent the day studying this and I think I’m getting the hang of it.

Below is a rough state diagram. As I understand it, there are 3 desirable spool states - SHUT_DOWN, GROUND_IDLE, THROTTLE_UNLIMITED.
During the transition between SHUT_DOWN (motors off, disarmed), and GROUND_IDLE (motors at MOT_SPIN_ARM, armed), there is some logic to ramp up the _spin_up_ratio between 0 - 1 to ease the motors on.

Slightly confusingly, this isn’t treated within the SPOOLING_UP or SPOOLING_DOWN states. It’s all handled within switch cases such as the one in my OP, without being explicitly named as an intermediate case.

Then, when going between GROUND_IDLE and THROTTLE_UNLIMITED, the intermediate SPOOLING_UP and SPOOLING_DOWN states are used to smoothly transition between MOT_SPIN_ARM and MOT_SPIN_MIN.

The diagram below maybe illustrates some of this a little better. (I realised i forgot to mark the ‘SHUT DOWN’ at the very start of the plot here).

This is all aligning with my initial assumptions. I’m currently working on a fork to mess around with the spool logic. I was initially tackling an issue that meant the motors didn’t spool down, and I’ve made good progress on this, however I’m now running into a new issue where the PWM command does spool down, but the motors still come to a dead stop.. I’ll continue on.

How low are you setting the throttle? Some ESCs (especially PWM ones) only start rotating props at about 1150-1170 and are unable to maintain idle motor rotation below ~1140. Depending on your configuration that may be the issue. I have played with Jeti ESC that requires good 80us of travel between min signal and configured 0 throttle PWM value to go from throttle lock to ready state.

I’ve tried it with either throttle at min or throttle towards midstick when I disarm.
I’m using AM32 firmware on Tekko32 F4 ESCs.

They ramp up nice and smooth, but on disarm they just stop dead, even though the code on my custom build is commanding the PWM to ramp down more slowly.

Annoyingly my bdshot has stopped working between yesterday and today so I can’t provide any more ESC rpm data until I fix that but the above image represents what also happens when I disarm with non-zero throttle.

I messed around with the AM32 config yesterday. I tried disabling ‘complimentary pwm’ which softened the stop a little but also caused the startup to become less smooth. I checked and braking isn’t enabled on them otherwise.

It’s not a huge issue for me at the moment. I was changing the code for different spool down behaviour and I can visualise that it has improved, I think the issues all now lie with my ESC config or some other silly thing like that. I’ll try it on a different platform soon and see if that behaves any different.

Behaving as expected, disarming commands immediate motor stop.

This is where I get a bit lost. As I understand it, if PWM is enabled when disarmed (MOT_SAFE_DISARM), then the motors should spool down in MOT_SPOOL_TIME (or MOT_SPOOL_TIM_DN) to a stop. This is part of the change I’ve been working on in my custom build since having the motors ramp down as opposed to step down is much more useful for one of my applications.

I would expect if MOT_SAFE_DISARM = 1 then the motors stop as soon as disarmed, or if the user commands a motor emergency stop.

Could you try waiting for disarm timeout? I think we should ask Alka to implement command to disable motor instead of stopping.

Stopping the motor ASAP when disarming makes sense if you are trying to minimize collateral damage which I think is the assumed reason for disarm commands through radio.

The image shown was not a manual disarm, it was automatically triggered after timeout.

I understand where you’re coming from, but it seems odd to me to provide a dedicated parameter for spooling the motors down (and dedicated logic in AP_MotorsMulticopter.cpp) if that function isn’t intended to be used.
I think I would prefer to map one switch to emergency stop for the case of crash landing or in flight failure.

I’ve submitted a PR for review. The main fix was that the code supplies logic for a ‘ramp’ transition between GROUND_IDLE and SHUT_DOWN, but that code is never executed due to the forced transition straight to SHUT_DOWN on disarm.

It feels like a lot of this logic is left over from the trad Heli state flow and some of the terminology and logic doesn’t directly translate to multicopters.

There is quite a detailed forum post from a while ago that attempted to clarify the parallels. I need to read this more fully

1 Like

Are you working on a helicopter or a multicopter? We use the same states but in some cases it means slightly different things.

I’m working on multirotor

Another thing that might be confounding here is your use of the motor interlock. I have a feeling that it will override disarm spooldown behavior and cause an immediate cessation of spin, but I would like to take a closer look at the code

I’ve been doing a fair bit of studying the code and updating the PR that I submitted which has opened some further discussion over on github.

In current ardupilot/master, motor interlock and disarm are treated in the same way and at the same point in the code. So if we have an interlock mapped to an RC channel, disabling the interlock or disarming the vehicle both produce the same behaviour. I won’t go over the full detail but it’s all in that github link.

Obviously there’s a lot of hesitation here since disarming corresponds to a potentially safety critical point if a vehicle is endangering somebody or damaging itself. Ultimately the safety has to come first so maybe that PR gets rejected on those grounds which would make complete sense.

1 Like