25 D‐Ov2Evo: Usage - bjoerngiesler/BBDroids GitHub Wiki

Default Remote Mapping

Default Remote Mapping If Left Remote Set To Primary

Default Remote Mapping If Right Remote Set To Primary

Drive Modes

Drive System Off

In this mode, the drive system is off and passive. Motion of the primary remote joystick is ignored. Balance input is ignored too; you can tilt the droid without the motors starting up. Use this mode to transport the droid from its station to the ground.

Velocity Mode

In this mode, the primary remote's joystick controls the droid's driving / turning velocity. This means if you hold the joystick forward at a certain angle (= pressure), the droid will accelerate to the velocity given by that angle and then hold the velocity. If you let go of the joystick, the droid will decelerate down to zero velocity. The range of the velocity controller is given by the droid's maximum velocity and the remote velocity and rotation gain, see the configuration parameters below.

In the default remote mapping, clicking the primary remote's joystick switches to Velocity Mode (or if auto_pos_hold is true, to Auto Position Hold mode, see below).

Clicking the primary remote's joystick while in Velocity Mode or Auto Position Hold mode switches the drive system off.

Clicking the primary remote's joystick while in Position Control Mode switches to Velocity Mode (or Auto Position Hold Mode).

If auto_pos_hold is true, and there has been zero input from the primary remote's joystick for >0.5s (i.e. the joystick lever is centered, make sure your joystick calibration is good!), the droid automatically switches to Auto Position Hold mode.

Auto Position Hold

This submode uses a position controller to hold the droid at the position it was at when the mode was activated, as long as there is zero input from the primary remote (i.e. the joystick lever is centered). As soon as nonzero joystick input is detected, the droid switches back to Velocity Mode. Position is determined by the wheel encoders.

If auto_pos_hold is false, this mode is skipped.

Position Control Mode

In this mode, the primary remote's joystick controls the droid position and rotation, relative to the position and rotation the droid was in when the mode was activated. This means if you hold the joystick forward at a certain angle (= pressure), the droid will drive to the indicated position (when joystick is moved front-back) or rotate to the indicated angle (when joystick is moved sideways). If you let go of the joystick, the droid will return to its original position. The range of movement for full joystick motion is determined by the respective parameters, see below.

In the default remote mapping, clicking the secondary remote's joystick switches to Position Control Mode.

Clicking the secondary remote's joystick while in Position Control Mode switches the drive system off.

Clicking the secondary remote's joystick while in Velocity Control Mode or Auto Position Hold mode switches to Position Control Mode.

Trust the Self Test

Why We Do A Self Test

Dynamically unstable droids like D-O depend on a couple of things to be correct before their control algorithms can work. What the control algorithm essentially does is control the droid's counterweight pitch against a setpoint, actuating the motors to achieve this and measuring pitch with the IMU. Here is what can go wrong (not an exhaustive list :-)):

  • If the voltmeter cannot be found, or power is too low, we may deep discharge already empty batteries, breaking them.
  • If the IMU cannot be found, the balance controller cannot work.
  • If the neck servo cannot be found or is not working, we may drag the head on the ground in the remaining tests.
  • If the encoder direction is different from the motor direction, the wheel speed controller will observe movement in the wrong direction and accelerate trying to compensate, making the wheels run faster and faster.
  • If both motors are reversed or the IMU is rotated 180°, the droid, trying to balance, will accelerate in the wrong direction, running away into a wall.
  • If one motor is reversed, the droid, trying to balance, will spin on the spot.
  • If the IMU is rotated 90°, balance does not change pitch so the control algorithm is useless and the droid will probably not move at all.

None of these are good; most of these will cause the droid to crash into something at high speed. To make sure all systems are aligned correctly, D-O has a selftest method that is called at every startup, or can be triggered manually by the d-o selftest command in the console.

Run the Self Test On The Ground

Please make sure you run the self test with the droid on the ground. D-O needs a bit of room!

You should only run the selftest in the base if you are already familiar with your droid. The reason is that the droid needs the IMU output in order to be able to tell whether it is actually driving in the right direction when the left and right motors are being run; when it does not see large enough IMU motion it will conclude that it is in the base, but it will not be able to diagnose reversed motors and encoders.

It is not important to have the neck screwed on, the selftest will diagnose this and make the necessary adjustments. Indeed it's best to have the neck off until you're confident that the droid base can drive well.

How the Self Test Works

The routine works as follows:

  • Make sure IMU and current meter are available and responding. We need these for everything the droid does, so if they do not work correctly we halt right here.
  • Slowly drive all connected servos to their normal position; this means neck upright, head horizontal and pointing to the front. This is important to have the droid body in "normal balance" when calibrating the IMU. We als don't want anything dragging on the ground when we test the motors.
  • Use the IMU to make sure the droid is upright(ish), and integrate a couple hundred values to calibrate out any residual pitch angle.
  • Accelerate the left motor gradually forward up to a certain maximum PWM (no speed control here, this is raw PWM). This will at some point cause the droid to pivot around the right wheel! While acellerating, measure the following, and operate on the measurement:
    • drawn current (from the current meter), and if current is too high stop accelerating immediately;
    • acceleration (from the IMU), and if a certain acceleration was reached stop accelerating immediately;
    • distance driven by the left wheel (from the encoder), and if a certain distance was reached stop accelerating immediately;
  • If not aborted by one of the above criteria, stop accelerating when maximum PWM is reached.
  • Gradually decelerate the left motor back to 0.
  • Use the measured values for diagnostics, and return appropriate error messages:
    • If current too high, the motor is blocked.
    • If high acceleration is measured along the y axis, the IMU is turned by 90°.
    • If the encoder does not report enough distance driven,
      • but sufficient acceleration was measured, the encoder is likely disconnected.
      • and insufficient acceleration was measured, the motor is likely disconnected.
    • If the encoder reports enough distance driven but insufficient acceleration was measured, the droid is probably stationary in its cradle (i.e. the motors turn freely but the droid does not move). This is no reason to abort but it means we cannot distinguish wrong motor direction and wrong encoder direction in the next step.
    • If the motor PWM direction and the direction of the driven distance disagree,
      • but acceleration was measured in the direction of the motor PWM, the encoder leads are likely reversed.
      • and acceleration was also measured opposing the direction of the motor PWM, the motor leads are likely reversed.
    • If we are still here, we have ascertained that
      • the motor is not blocked
      • the IMU is oriented correctly
      • encoder and motor are connected and driving in the same direction as the IMU measures acceleration.
      • We also know if the droid is driving freely or is in its station.
  • Repeat this by running the right motor.

Diagnostics

Mainboard LEDs

Status LED

  • White: Starting up, D-O subsystem not yet started (or stopped again)
  • Red: Error starting up
  • Flashing Red: Low power
  • Blue: Running under USB power (i.e. servos off, drive system off)
  • Yellow: D-O subsystem started, but some non-critical but important component missing (e.g. XBee communication)
  • Green: Running, all OK

Communication LED

  • Off: No communication packets in the last 100ms
  • Flashing Blue: Packet came in from left remote in the last 100ms
  • Flashing Green: Packet came in from right remote in the last 100ms
  • Flashing White: Packet came in from both remotes in the last 100ms

Drive Mode LED

  • Off: Drive mode off
  • Blue: Drive mode on, in speed control mode, drive stick input below deadband
  • Green: Drive mode on, in position control mode (automatic after drive stick in deadband for less than configurable delay)
  • White: Drive mode on, in speed control mode, drive stick input above deadband

Tunable Parameters

D-O has a host of parameters that you can tune to modify the reaction of the wheel speed, balance, and position controllers, ranges and offsets of the neck and head servos, and "free animation" behavior (i.e. automatic control of head and neck depending on body motion and other internal values). All of these can be set in the DOConfig.h file in the include folder. Most of them can also be set using the serial console, and stored in flash memory using store, overriding the DOConfig.h settings until the next software flash.

Axis Conventions

Servo Axis Orientations

  • Neck Pitch: Negative forward, positive backward
  • Head Pitch: Negative forward, positive backward
  • Head Roll: Negative left in direction of driving, positive right in direction of driving
  • Head Heading: Negative right in direction of driving, positive left in direction of driving

IMU Orientation

  • X: forward
  • Y: left in direction of driving
  • Z: up
  • Pitch: positive forward, negative backward
  • Heading: negative left in direction of driving, positive right in direction of driving
  • Roll: not used

Important Compile-Only Settings

These are only in DOConfig.h. Please review them carefully.

  • HEAD_COUNTERWEIGHT (default value true): Set this to false if you are not using a head counterweight. This will eliminate the influence of the faNeckIMUPitch constant below, as this will lead to the droid swinging violently.

Servo ranges and offsets

These all require a d-o stop and d-o start to become effective when set from the serial console.

  • Neck Range (DOConfig.h: neckRange, serial console: neck_range, default value 45.0, unit degrees): Controls the range of allowed motion for the neck, from 180.0+neckOffset-neckRange to 180.0+neckOffset+neckRange. Be careful with this. On a D-O without a head counterweight, it's easy to nosedive when the neck is holding the head too low. On a D-O with a head counterweight, the counterweight limits the neck motion to [-45°..45°], larger angles will cause the servo to block and eventually give up.
  • Neck Offset (DOConfig.h: neckOffset, serial console: neck_offset, default value 0.0, unit degrees): Offsets the neck roll servo's center position. It can be hard to get the neck exactly straight up because of the way the servo gear and neck axis mash. You can use this to correct. Be careful with the interplay with neckRange (which is added to this) though, especially on D-Os with a counterweight, and remember the 45° maximum.
  • Head Roll Range (DOConfig.h: headRollRange , serial console: head_roll_range, default value 45.0, unit degrees): Controls the range of allowed motion for the head roll servo, from 180.0+headRollOffset-headRollRange to 180.0+headRollOffset+headRollRange.
  • Head Roll Offset (DOConfig.h: headRollOffset , serial console: head_roll_offset, default value 0.0, unit degrees): Offsets the head roll servo's center position.
  • Head Pitch Range (DOConfig.h: headPitchRange , serial console: head_pitch_range, default value 45.0, unit degrees): Controls the range of allowed motion for the head pitch servo, from 180.0+headPitchOffset-headPitchRange to 180.0+headPitchOffset+headPitchRange.
  • Head Pitch Offset (DOConfig.h: headPitchOffset , serial console: head_pitch_offset, default value 0.0, unit degrees): Offsets the head pitch servo's center position.
  • Head Heading Range (DOConfig.h: headHeadingRange , serial console: head_heading_range, default value 90.0, unit degrees): Controls the range of allowed motion for the head heading servo, from 180.0+headHeadingOffset-headHeadingRange to 180.0+headHeadingOffset+headHeadingRange. (Note we use "heading" and not "yaw" for this part of the rotation because yaw abbreviates to "y" which can be confused as a direction rather than an angle, while "heading" abbreviates to "h" which cannot.)
  • Head Heading Offset (DOConfig.h: headHeadingOffset , serial console: head_heading_offset, default value 0.0, unit degrees): Offsets the head heading servo.

Free Animation Parameters

These affect different parts of the droid motion that you can use to give your droid personality and make it drive differently than someone else's.

Basic Interaction Formula

The neck angle nod is the most important angle in the droid, because it controls the head forward/backward motion, which is extremely important for the droid moving naturally. It also interacts directly with the body, influencing the body position and speed controllers. Extra care should be given to getting it right. It is controlled by the following formula:

  • when driving forward:
    nod = lean + faNeckIMUAccel*ax + faNeckSPAccel*accelSP + faNeckSpeed*speed + faNeckSpeedSP*speedSP
  • when driving backward:
    nod = lean + faNeckIMUAccel*ax + faNeckSPAccel*accelSP + faNeckSpeed*speed + faNeckSpeedSP*speedSP/2
    (halving the influence of the stick on the neck angle when reversing).

where

  • lean is the lean angle given by the corresponding remote axis,
  • ax is the actual acceleration (from the IMU, not gravity-corrected),
  • speed is the actual speed over ground (from the wheel encoders),
  • speedSP is the setpoint for the speed (taken from the joystick input),
  • accelSP is the acceleration setpoint (speedSP - speed).

If the droid has HEAD_COUNTERWEIGHT set to true, faNeckIMUPitch*p is added to nod, where p is the actual body pitch (from the ARHS filter correcting the IMU).

The head pitch angle is automatically controlled by -nod, making it keep the head parallel to the ground as the neck moves backwards and forwards. It is fully controlled by the formula headPitch = -nod + remoteP_ + faHeadPitchSpeedSP*speedSP, where remoteP_ is the pitch angle given by the corresponding remote axis, and speedSP is the speed setpoint also from the remote.

The head heading angle is controlled by faHeadHeadingTurn*dh + remoteH_, where dh is the heading angular velocity given by the IMU and remoteH_ is the heading angle given by the corresponding remote axis.

The head roll angle is controlled by faHeadRollTurn*dh + remoteR_, where dh is the heading angular velocity given by the IMU and remoteR_ is the roll angle given by the corresponding remote axis. Why isn't it controlled by the roll axis? We don't care about roll here, if the droid experiences roll it's toppling over. But having the head "lean into turns" by rolling in the direction of the turn is a nice effect. You can also experiment with having it "lean out" of turns!

Many of these use the IMU to affect motion, which means that you can also show them off while the droid is not driving. Try holding the droid, turning it left and right and moving it back and forth!

All of these free animation settings become effective immediately when set from the serial console.

  • IMU Accel to Neck (DOConfig.h: faNeckIMUAccel , serial console: fa_neck_imu_accel, default value 0.0, unit: degrees per unit gravity): Controls the influence of the x acceleration measured by the IMU on the neck angle. This can be used to move the head forward/backward while accelerating/decelerating to a given target speed.
  • IMU Pitch to Neck (DOConfig.h: faNeckIMUPitch , serial console: fa_neck_imu_pitch, default value 0.8, unitless multiplier): Controls the influence of the pitch angle measured by the IMU on the neck angle. This can for example be used to keep the head upright as the droid is pitching (e.g. when accelerating/decelerating). Note: Only used if using a head counterweight, see the HEAD_COUNTERWEIGHT parameter in DOConfig.h, as moving a counterweight-less neck in reaction to the body pitch will influence the body pitch, creating an oscillating circuit. Even if you are using a head counterweight, it's a good idea to keep this a bit below 1.0, as even the effect of the servo torque will cause some body pitching and may cause oscillation.
  • Acceleration Setpoint to Neck (DOConfig.h: faNeckSPAccel , serial console: fa_neck_sp_accel, default value -0.005, unit degrees per mm/s): Controls the influence of the remote acceleration setpoint on the neck angle. Very useful to move the head forward as the stick is pushed forward.
  • Speed over Ground to Neck (DOConfig.h: faNeckSpeed, serial console: fa_neck_speed, default value -0.01, unit degrees per mm/s): Controls the influence of the speed over ground on the neck angle. This should be a main influence to move the droid's head forward as it gains speed.
  • Speed over Ground to Neck (DOConfig.h: faNeckSpeedSP , serial console: fa_neck_speed_sp, default value -0.04, unit degrees per mm/s): Controls the influence of the speed over ground setpoint (from the remote, not the actual current speed) on the neck angle. This can be used to push the head forward while the droid is still accelerating, and keep it there.
  • Speed Setpoint to Head Pitch (DOConfig.h: faHeadPitchSpeedSP , serial console: fa_head_pitch_speed_sp, default value -0.01, unit degrees per mm/s): Can be used to turn the head up or down as a reaction to the speed over ground setpoint from the remote.
  • IMU Turn Rate to Head Roll (DOConfig.h: faHeadRollTurn , serial console: fa_head_roll_turn, default value 0.1, unit degrees per degree/s or 1/s): Can be used to roll the head into or out of turns.
  • IMU Turn Rate to Head Heading (DOConfig.h: faHeadHeadingTurn , serial console: fa_head_heading_turn, default value 0.4, unit degrees per degree/s or 1/s): Can be used to turn the head into or out of turns.
  • Speed Setpoint to Aerial Angle (DOConfig.h: faAerialSpeedSP , serial console: fa_aerial_speed_sp, default value 0.05, unit degrees per mm/s): Can be used to move the aerials depending on remote control speed setpoint.
  • Head Anneal Time (DOConfig.h: faHeadAnnealTime , serial console: fa_head_anneal_time, default value 0.5, unit seconds): Controls the speed of motion back to zero when the head control button is released. All servos will move at different speeds so that they all converge at zero at the same point in time.
  • Head Anneal Delay (DOConfig.h: faHeadAnnealDelay , serial console: fa_head_anneal_delay, default value 0.3, unit seconds): Controls the time after which the servos will start to return to zero when the head control button is released.

PID Controller parameters

The droid's control architecture is described on a separate page, please check there before changing any parameters here!

These all take effect immediately when set by the serial console, and will also reset all controllers to 0 error.

  • Wheel Speed P, I, D constants (DOConfig.h: wheelKp, wheelKi, wheelKd, serial console: wheel_kp, wheel_ki, wheel_kd): These control the proportional, integrative and derivative error response of the wheel speed controllers. Please see the page on wheel encoder calibration and controller tuning for reference.
  • Balance P, I, D constants (DOConfig.h: balKp, balKi, balKd, serial console: bal_kp, bal_ki, bal_kd): These control the proportional, integrative and derivative error response of the balance controller. Set to 0 to disable (full roly-poly), slowly increase bal_kp until the droid starts to oscillate on sudden stops/starts, back off bal_kp until the droid stops oscillating. If required, add bal_ki and bal_kd to taste. Tutorial to follow.
  • Position P, I, D constants (DOConfig.h: posKp, posKi, posKd, serial console: pos_kp, pos_ki, pos_kd): These control the proportional, integrative and derivative error response of the position controller that gets activated if there is no velocity input from the remotes. Set to 0 to disable and be able to passively push the droid (by holding down the front or back edge of the body) when standing. Slowly increase pos_kp until the droid starts to oscillate when released. Back off pos_kp until the droid stops oscillating. Add pos_ki to make it return to its starting position. Add pos_kd if absolutely necessary. Tutorial to follow.

Other parameters

  • Maximum Speed (DOConfig.h: maxSpeed, serial console: max_speed, default value 1000, unit mm/s): Sets the droid's maximum speed over ground. Effective immediately when set by the serial console.
  • Acceleration (DOConfig.h: accel, serial console: accel, default value 2500, unit mm/s/s): Sets the droid's acceleration. Effective immediately when set by the serial console.
  • Automatically Switch to Position Control (DOConfig.h: autoPosControl, serial console: auto_pos_control, default value true, unit boolean): Controls whether the droid will switch to position control mode automatically. If set to false, the droid will stay in velocity control mode until explicitly instructed. Effective immediately when set by the serial console.
  • Neck Pitch to Body Pitch Setpoint (DOConfig.h: leanHeadToBody, serial console: lean_head_to_body, default value 0.8, unitless multiplier): Sets the body balance controller setpoint as the inverse of the neck setpoint multiplied with this constant. This is very helpful for making the droid stay in place when the neck servo is moved, especially on droids that do not use a neck counterweight. This is not affected by free animation on the neck. Effective immediately when set by the serial console.
  • Motor PWM Deadband (DOConfig.h: motorDeadband, serial console: mot_deadband, default value 10, PWM duty cycle with 255=100%): Sets the deadband for the motor PWM, so that it emits zero if the setpoint for the motors is within a range of zero up to this deadband in either direction. Can be used to quiet down the motor PWM whine when not moving. Effective immediately when set by the serial console.
  • Remote Speed Axis Gain (DOConfig.h: speedAxisGain, serial console: speed_axis_gain, default value 1.0, unitless multiplier): This multiplier is used to scale the remote speed setpoint (which ranges from -1.0 to 1.0) to the value of maxSpeed according to the formula speedSP = speedAxisGain * remoteSpeedSetpoint * maxSpeed. Effective immediately when set by the serial console.
  • Remote Rotation Axis Gain (DOConfig.h: rotAxisGain, serial console: rot_axis_gain, default value 0.4, unitless multiplier): This multiplier is used to scale the remote speed setpoint (which ranges from -1.0 to 1.0) to the value of maxSpeed according to the formula rotSP = rotAxisGain * remoteRotSetpoint * maxSpeed. Effective immediately when set by the serial console.
  • Aerial Offset (DOConfig.h: aerialOffset, serial console: aerial_offset, default value 0, unit degrees): Can be used to offset the aerial position at rest. Effective immediately when set by the serial console.
  • Aerial Animation Angle (DOConfig.h: aerialAnim, serial console: aerial_anim, default value -45, unit degrees): Determines which angle aerials get set to when the corresponding button gets pushed. Effective immediately when set by the serial console.
⚠️ **GitHub.com Fallback** ⚠️