| cmdMO_CFG | Index |
Command Code:
The Packet:
| 0 | 1 | 2 | 3 | 4 | 5 | 6 | ||||||
| address | 5 | cmdMO_CFG | moID | paramID | paramH | paramL |
| moID - | The channel (zero based) whose parameters are to be set or retrieved. |
| paramID - | The index of the parameter to change or retrieve. |
| paramH - | The high byte of the new parameter. |
| paramL - | The low byte of the new parameter. |
Description:
This command is only available on BrainStem modules with the motion control feature.
The cmdMO_CFG command is used to set or retrieve motion control configuration parameters. If no parameter data is included in the packet, a reply packet is sent reporting the current value for the requested parameter.
Parameters:
Parameter 0 --- MODE
The first byte of this parameter is a control mode code. The second byte of this parameter has mode flags. The control mode codes and their descriptions are listed below.
| Code | Name | Description |
|---|---|---|
| 0 | OFF | PWM, Encoders, and PID are all off |
| 1 | STEP | Bipolar stepper motor control |
| 2 | PWM | PWM outputs enabled |
| 3 | PWMENC | PWM and encoders enabled encoder control input (velocity) viewable with cmdMO_PEEK PID control disabled |
| 4 | A2DPOS | Position control from analog input |
| 5 | ENCPOS | Position control from encoder input |
| 6 | A2DVEL | Velocity control from analog input |
| 7 | ENCVEL | Velocity control from encoder input |
| 8 | PWMA2D | PWM enabled analog control input viewable with cmdMO_PEEK PID control disabled |
| Note: | When using encoder input for only one channel, avoid using the encoder pins for the other channel as general-purpose inputs. The processor will waste time monitoring transitions on those general-purpose inputs. If they are left unused but still configured as inputs, use pull-down resistors to ground them. Otherwise, they could pick up stray signals. |
The flags for the second byte are described below. Bits 0 and 1 can be used to switch the sign of the control input and switch directions of the motors. This enables the user to assign an arbitrary direction to a DC motor. When using bipolar stepper motors, these two bits control the polarity of the two control coils. This enables the user to assign an arbitrary direction to a bipolar stepper motor. Bit 2 configures the board to use single-output or mono encoders instead of quadrature encoders. When using mono encoders, bit 0 should always be cleared and the mono encoder input should be connected to both quadrature inputs. Bit 3 enables a brake output during the back-EMF latency period. Some h-bridges need a brake input to function properly in back-EMF mode. When using stepper motors, bits 2 and 3 are used to select the stepping mode. There are three standard modes for stepping motors: 00=wave, 01=high-torque, 10=half-step.
| Bit | DC Motor Function | Stepper Function |
|---|---|---|
| 0 | 0=normal, 1=invert PID input | 0=normal, 1=invert coil A control |
| 1 | 0=normal, 1=invert output to motor | 0=normal, 1=invert coil B control |
| 2 | 0=quadrature enc, 1=mono enc | bit 1 of stepper sequence code |
| 3 | 0=back-EMF brake disabled, 1=back-EMF brake enabled | bit 2 of stepper sequence code |
| 4* | 0=normal PWM mode, 1=servo PWM mode | (n/a) |
* Change introduced in Moto 1.0 Firmware Build 8
Bit 4 of the configuration flags enables servo PWM mode. This switches the PWM output from a 0%-100% duty cycle waveform to a servo PWM waveform with 1ms to 2ms pulses sent every 20ms. This servo PWM signal can drive electronic speed controls or servos. In this mode, motor direction is determined by the pulse width. However, the function of the direction output is unchanged. It will still be on or off depending on the motor direction.
Parameter 1 --- P
This value is the scaling factor for the proportional (P) term of the PID equation. This factor is applied to the current error. The error is calculated as the setpoint minus the current feedback input.
Parameter 2 --- I
This value is the scaling factor for the integral (I) term of the PID equation. This factor is applied to the integral of the error. The integral of the error is calculated as the sum of the last 32 error values.
Parameter 3 --- D
This value is the scaling factor for the derivative (D) term of the PID equation. This factor is applied to the derivative of the error. The derivative of the error is calculated as the current error minus the previous error.
Parameter 4 --- COFFSET
This is a control input offset constant*. It may be used to shift the acceptable setpoint range. This is useful in back-EMF feedback mode. For other modes, it is usually set to 0.
* Change introduced in Moto 1.0 Firmware Build 8
In servo PWM mode, the COFFSET parameter is a timing offset for the servo output pulse. It can be used to adjust the center (off) point for an electronic speed control or servo. Adjustment values range from -1000 to 1000.
Parameter 5 --- PWMRAIL
This parameter limits the PWM output. It can be used to limit the maximum motor output in any PID or PWM control mode. Changing this parameter will not have any noticeable effect until a new setpoint or duty cycle is entered. This parameter should be non-negative. Behavior with a negative value is undefined.
Parameter 6 --- PERIOD
This value is the time between PID computations or stepper motor steps in units of 0.1ms. The minimum value for this term is 10* (1ms).
* Change introduced in Moto 1.0 Firmware Build 8
The minimum value for the PERIOD parameter is 5 (0.5ms).
Parameter 7 --- LATENCY
This value specifies a time between PID computations when the PWM output is turned off. This time is in units of 0.1ms. This value should only be non-zero when using back-EMF across a motor as a control input. This value must be less than the Period.
Parameter 8 --- PWMFREQ
This parameter applies to both motor channels. The Channel ID must be included but has no effect. The two bytes of this parameter determine the PWM frequency. The high byte is a prescaler. Values of 0,1,2 correspond to prescalers of 1,4,16 respectively. The low byte is a frequency factor. The formulas for determining the PWM frequency and bits of resolution for duty cycle control are shown below. The maximum PWM frequency that allows full 10-bit resolution is 39.06KHz.
Some examples of PWM frequency settings are listed below.
| Frequency | paramH,paramL | Resolution (bits) |
|---|---|---|
| 100KHz | 0,99 | 8 |
| 50KHz | 0,199 | 9 |
| 40KHz | 0,255 | 10 |
| 20KHz | 1,124 | 10 |
| 10KHz | 1,249 | 10 |
| 2.5KHz | 2,249 | 10 |
| NOTE: | Full 10-bit control of the PWM duty cycle is only possible when paramL is 255 (0xFF). When paramL is 255, the Moto module can generate PWM frequencies of 39.062KHz, 9.765KHz, or 2.441KHz. These are the only frequencies that should be used for PID motion control. |
Specifying PID Factors
The scaling factors for the P, I, and D terms use a signed fixed-point representation. The lower 5 bits are fractional. The most significant bit is the sign bit. The middle 10 bits are the integer part of the value. Some examples of this numbering scheme are shown below.
| Hex Value | Factor |
|---|---|
| 0x0001 | 0+1/32 (0.031) |
| 0x0010 | 0+1/2 (0.500) |
| 0x001F | 0+31/32 (0.969) |
| 0x0020 | 1+0/32 (1.000) |
| 0x007A | 3+26/32 (3.813) |
| 0x0C80 | 100+0/32 (100.000) |
| 0x7FFF | 1023+31/32 (1023.969) |
Velocity vs. Position Control
In a velocity control mode, the result of the PID equation is added to the current PWM output. In a position control mode, the result of the PID equation becomes the new PWM output. The two types of feedback produce different results. It is up to the user to pick the best control mode for an application. In general, a velocity control mode is required when a 0 error should create a 0 change in the current output and a position control mode is required when a 0 error should create a 0 output.