Archives: Control

Optimizing fast movements

In a mini-project inspired by a Discord chat about a Rubik’s cube solver, I decided to undertake a project to see how quickly I could get moteus to make a controlled 90 degree movement and a controlled 180 degree movement. The project ended up involving a fair amount more work and theory than I had expected, but resulted in an overall solution that is relatively close to optimal for the specified moteus and motor. If you find text too hard, you can watch the video below, otherwise read on to see the details:

Capturing full rate debug data from moteus

Most users of the moteus brushless motor controller will perform diagnostics and monitoring over CAN-FD, using something like tview, the moteus python library or the moteus C++ library. These options are great, since CAN-FD works over long distances, allows multiple devices to be multiplexed and is relatively immune to EMI or other electrical disturbances. The biggest downside is that at best, you can capture telemetry a few thousand times a second. For instance here, 2.5kHz is the maximum achievable update rate with a pi3hat and a single moteus.

What should you do when you want to monitor events that happen faster than that? Well, moteus has a solution for that too, and while it isn’t nearly as convenient, it does get the job done for many uses. It is called “high rate debug output” and lets moteus emit small amounts of telemetry data at every single control cycle, so up to 30kHz. In this post I’ll show how to configure and use it, how to capture the resulting output, and how to plot it or otherwise make use of it.

Correcting the encoder filter frequency

Way back in 2021, I described the approach moteus uses for filtering encoder values and its derivation from the “all-digital phase locked loop”. What I did not realize until now was that the formulas used in that derivation operated based on the “natural frequency” of the filter, not the 3dB cutoff frequency as I had intended. They are related by a constant, but this resulted in the bandwidth of the encoder being higher than expected. Here, I’ll set the record straight, and document how that effects moteus going forward.

TLDR: Now moteus has slightly less audible noise for the same effective control performance. Read on for the details.

Improving motor constant calibration in moteus

moteus is able to for many motors automatically determine all the relevant parameters that are necessary for control. That includes phase resistance, phase inductance, torque constant and pole count. The calibration routines have worked pretty well for a wide variety of motors and all the currently available moteus controllers, but when working to expand the supported envelope recently I undertook an effort to make that support even broader, specifically to improve accuracy when measuring resistance and torque constant, and to reduce outliers when measuring inductance.

Current mode commutation calibration in moteus

Way back in 2019, I documented the approach moteus has used for encoder commutation calibration ever since. In principle, it commands a fixed voltage that is swept through a range of electrical angles. Assuming the voltage is large enough, this will drag the rotor around with it similar to if the motor was a stepper motor. While that is happening, the commutation encoder reading is recorded over time, so that a mapping can be made between commutation encoder and the electrical angle of the motor. When combined with the old dead time compensation technique, it resulted in relatively sinusoidal current waveforms and thus smooth motion of the rotor and a smooth mapping.

Rethinking dead time compensation in moteus

Way back in 2021, I wrote up a post detailing a method for improving the linearity of the relationship between applied voltage and current for moteus, particularly during the calibration phase. At the time, this did solve a real problem – during calibration, moteus applied a fixed voltage to the phase terminals, swept the electrical angle of that voltage, and hoped that the mechanical angle as sensed with the on-axis sense magnet matched well. However, as a result of some new work, I’ve found that the premise behind that approach was flawed and it needs some re-thinking. This describes what I found, and what’s being done to resolve it going forward.

Moaar power!

Exciting news! All the existing moteus controllers in the world now have an upgraded default maximum power and upgraded rated maximum power as of release 2025-03-27! Depending upon the input voltage and PWM rate, sometimes nearly twice the amount. First, check out the comparison table, then the rationale:

Old default max / rated New default & rated
moteus-r4 340W / 450W 900W <= 30V, 400W >= 38V
moteus-c1 75W / 100W 250W <= 28V, 150W >= 41V
moteus-n1 340W / 1200W 2kW <= 36V, 1kW >= 44V

Background, why a power limit?

moteus brushless motor controllers drive 3 phase PMSM motors, accepting a DC input voltage, and outputting current to each of the 3 phases of the motor. It does so using MOSFET based switching, which alternately connects each phase to either ground, or the DC positive input. As that switching progresses, charge is either drawn, or replenished into, the onboard bulk capacitors.

hoverbot

I made a thing!

With that video out of the way, here is a bit more of a write-up!

Motivation

The hoverbot is a simple 2 wheel balancing robot. I built it to demonstrate how the moteus-c1 can be used to drive hoverboard motors and to demonstrate the capabilities of the pi3hat for high rate control and effective attitude reference calculation. It is powered by a single Bosch 18V cordless drill battery and controlled through an identical websocket based interface as the quad A1, primarily operated by a phone with a paired bluetooth joystick.

Optimizing moteus command rate

Probably one of the most frequently asked questions in the mjbots Discord is “how fast can I send new commands to moteus”, or “how fast can I read the status from moteus”. That may be because you want to perform torque based control in your application and require high bandwidth, or just because you have a high torque to inertia ratio system that reacts on very short time-scales. No matter the reason, the principles that control the maximum rate you can send updates are the same.

recapturing position and velocity with moteus

Recently I covered a new feature for the moteus brushless controller that improved robustness for velocity control when external torques exceed the maximum allowable control torque. In this post, I’ll cover a feature that can be used for a similar situation in position control, “recapturing position and velocity”.

In some applications, while in position mode, it can make sense to limit the maximum torque during specific periods so that external torques are able to overpower the controller. The most obvious case would be if the maximum torque is set to 0, or the kp and kd scale are set to 0 temporarily. A problem then arises when resuming control, as the “control position” will be wherever it last was, despite the fact that the actual motor have have been dragged by the external torque some distance away. When the torque limit is released, a large transient can develop as the controller tries to instantaneously get back to the old control position.