Skip to content

01 Motion and Control Concept WIP

bjoerngiesler edited this page Apr 20, 2023 · 1 revision

Basic concept

Note: This is a work in progress. None of this has been completely implemented well enough to test on an actual droid, which is the litmus test.

image

IMU

Our BB8 has two IMUs, both of them coupled to the mainboard via I2C, although only one is currently used:

  • an Adafruit ISM330DHCX mounted on the drive axle. This is a 6-axis IMU that combines an accelerometer with a gyro, run at a 104Hz update rate.
  • an Adafruit LIS3DH mounted on the dome carrier. This is a 3D accelerometer only, so it cannot be used for absolute rotation etc. We compensate for this by using Dynamixel servos, which know absolute orientation, but in the future maybe a second ISM330DHCX might be a good idea.

IMU filtering

The software uses a Madgwick filter to derive absolute rotation from the ISM330DHCX. Note that this is currently heavy work in progress as in the current implementation the filter outputs very slowly changing roll angles (meaning it does converge, but it takes its sweet time) that cannot be used for dome servoing, but that would be required of course. The Madgwick should be able to do this but currently it doesn't.

IMU calibration

Like all IMUs, the ISM330DHCX has systematic drift (although it is pretty low) and needs to be calibrated to remove it. Currently this is done at startup by taking 100 measurements. Therefore make sure that after powerup the droid is very still for a couple of seconds. Since this is an impractical constraint it will be changed to a concept to hand-trigger calibration from the remote, then flash-store the last calibration and use it on consecutive starts until the next calibration is triggered.

The correct way to do things would be to store a lookup table that links temperature and ideally air humidity to IMU calibration values, together with some interpolation algorithm to generate calibration values for actual measured temperature and air humidity. The ISM330DHCX does not have a temperature sensor but claims to offer extremely high accuracy across temperature ranges, so maybe that is not needed. We will explore this in the future.

Motion Control

Remote Control Filtering

With the current communication concept, all remote axes are mapped to an integer range of -127..127 when they are sent to the droid. A yet to be developed filtering class performs the following actions in order on every axis that is used in the droid:

  • Low-pass (median or average) filter the input, with a configurable window, and move from int to float. This provides denoising, increases resolution and imposes some initial constraint on the change rate.
  • Constrain the change rate to a configurable maximum. Please note that all non-RC input (IMU etc.) is intentionally not constrained in change rate to provide snappy control.
  • Map / interpolate the result. This performs a multi-linear interpolation that can be used to map to motor max/min constraints, to provide higher sensitivity in certain motion areas (e.g. by mapping the lower 50% of a joystick throw to the lower 10% of motion range), and overall to attenuate, invert and transform axes.

Drive

image

The drive motor is a 84RPM gear motor with encoder (https://www.servocity.com/84-rpm-hd-premium-planetary-gear-motor-w-encoder/) that is coupled to the drive axis with an 1:1 gear ratio. It is controlled from the Arduino using a PWM signal, two direction pins and one enable pin. This configuration gives the following specs:

  • Minimum duty cycle to break friction in static holder: ~10% (analogWrite() with a parameter of 20-25 out of 255)
  • Minimum duty cycle to break friction in ball: TBD
  • Encoder ticks per rotation: 4776.384 (taken from data sheet, experimental validation: TBD)
  • Distance driven per tick in BB8 ball: 0.33mm
  • Maximum velocity: TBD
  • Maximum stall current draw: TBD
  • Maximum current draw at full speed drive in ball: TBD

The software (bb::EncoderMotor) supports control via direct setting of PWM, but it also offers PID speed control, and in the future PID position control. Internally, control is done in ticks-per-second units, but bb::EncoderMotor also allows setting and querying speed (setpoint, current) in millimeters per second if a millimeters-per-tick conversion factor is supplied.

Body Roll

image

Body roll is governed by a Dynamixel XM430-W350. The IMU input is used to hold a setpoint steady that is given by the remote. The idea is to drive in a totally straight line if the remote governs a 0° body roll.

At the moment there is no additional controller to work this more actively than the feedback loop from the IMU to the servo's position controller. The servo needs to move the full battery ring and motors though, so we require a lot of force from this sensor. The Dynamixels are pretty good holding position, but under this weight it is not easy. There is also a bit of play in the full roll mechanism, servo, linkage and all. It's not much given the size of the construction but it does exist. Working together, in the rack, it is possible to roll the body by roughly +-1.5° before the servo starts to seriously counteract. This may cause a significant deadband around the current servo setpoint, which may make it hard to defined line or curve. As soon as dome balancing works well, thorough examination needs to be performed.

Dome Pitch

image

Dome pitch is governed by a Dynamixel XM430-W350. The remote control provides an angle setpoint in coordinates of the ground plane, and the IMU is used to "control away" any effect of body motion, e.g. by acceleration/deceleration of the main drive. In addition, a configurable feed-forward amount can be used to pre-effect stronger drive accelerations or decelerations, to anticipate the motion and not have to rely completely on reacting to the motion of the IMU.

Dome Roll

image

Dome roll is governed by a Dynamixel XM430-W350. The remote control provides an angle setpoint in coordinates of the ground plane, and the IMU is used to "control away" any effect of body motion, e.g. by driving the body roll servo to drive a curve.

Dome Yaw

image

This is the simplest control, as it has no cross influence with any other motion. It uses a relatively weak Dynamixel (XL430-W250-T) under direct control from the remote.

Free Animation

The term "Free Animation" has been coined to describe motion of droid axes in reaction to other unrelated motion, to produce some effect of "intention" by creating motion that would be coupled in a real intent-filled being beyond pure control. For example, an accelerating droid might move its dome in the direction of the acceleration, "leaning into the motion". The control concept allows for this kind of motion of course, and it can be produced by an experienced puppeteer using the remote. But it is often useful to provide for this kind of automatic motion so that the puppeteer has an easier time.

There is currently no concept for Free Animation in our control concept, but there definitely should be. As soon as control is working sufficiently well and reliable, this concept needs to be developed.