RC Servo information

[A picture of RC servos]
A Futaba S3003 and Align RC-18G

Servo motors, typically used in radio controlled cars and planes, are very useful in hobby robotics and animatronics. I have gathered here some information about the servos I have used. This page is not, nor will it be, an exhaustive source of servo information, but mainly a collection of my personal notes that may be useful to other people as well.

RC servos use PWM to control the position of the horn. The pulse width is typically 1 to 2 milliseconds long for 90° motion, but most servos can do more. The midpoint is usually at 1.5 ms. Short pulses turn the horn clockwise (at least on the servos I've tested.) The pulses are sent every 20 milliseconds or so. RC servos don't seem to be too picky about the space between pulses.

If the control pulses are stopped, the servo will turn off the motor. I've measured no discernible difference between pulses off, and pulses on with the horn positioned correctly. However, the servo will sometimes 'vibrate' around the desired position, drawing current (133 milliamps measured with a Futaba S3003,) so it might be a good idea to stop the pulses if holding the position is not important. Note that some servos do not tolerate the lack of control pulses and will try to turn the horn as far as it will go, possibly damaging the motor. I haven't yet encountered one that exhibits this behaviour, but it is good to keep in mind.

Generating the control pulses is fairly easy using a simple timer circuit or a microcontroller. A PIC running at 4MHz executes 1000 instructions in one millisecond, so a simple busyloop can be used to time the pulses. Some PICs have a builtin PWM module, but they are typically too high frequency for servo use. See below for an example program.

Servos have three wires for power and control signal. Black is ground, red is power supply, and white is the control signal. There are other color schemes, but BWR seems to be the most common. Input voltages range from 4.8V to 6V. The control pulse voltage can be the same as the input voltage, but shouldn't exceed it.

Links to more information:

Servo notes
ModelTorqueAnglePulse width
Futaba S30030.32 N·m180°0.5ms–2.1ms
Align RC-18G0.19 N·m140°0.5ms–2.0ms
Vertical 5g micro servo0.09 N·m?ms–?ms

The values in the above table were scrounged up from datasheets and/or determined experimentally, and may not be accurate.

Controlling a servo with a PIC

Servo control pulses can be easily generated with a PIC microcontroller. Here is an example program (sans port initialization and such) that should work on any PIC model.

; Clockspeed of 4 MHz (1 million instructions per second) assumed.
Loop
	movlw SERVO_ON      ; Set servo control output pin high
	movwf SERVO_PORT    ; and delay 0.5 to 2.1 ms
	call PulseDelay

	movlw SERVO_OF      ; Servo control pin low
	movwf SERVO_PORT
	call Wait20ms       ; A fixed delay.

	goto Loop

PulseDelay
	; Initial fixed delay of 499 + 2 µs
	movlw 0x7d
	movwf DELAY
	nop                ; 1 * DELAY µs
	decfsz DELAY, f    ; 1 * DELAY + 1 µs
	goto $-2           ; 2 * DELAY - 2 µs
	; Total delay: 4 * DELAY - 1

	; Variable delay 0 – 1.7 milliseconds
	movf PULSELEN, W   ; If PULSELEN is 0, return here
	btfsc STATUS, Z
	return
	movwf DELAY
AdjustLoop
	nop                ; 4 * DELAY µs
	nop
	nop
	nop
	decfsz DELAY, f    ; 1 * DELAY + 1 µs
	goto AdjustLoop    ; 2 * DELAY - 2 µs
	; Total delay 7 * DELAY - 1 µs
	return

; Wait for around 20ms
Wait20ms
	movlw 0x1a
	movwf DELAY
IdleLoop
	movlw 0xff         ; 1 * DELAY µs
	movwf DELAY1       ; 1 * DELAY µs
	decfsz DELAY1, f   ; DELAY * (1 * DELAY1 + 1) µs
	goto $-1           ; DELAY * (2 * DELAY1 -2) µs
	decfsz DELAY, f    ; 1 * DELAY + 1 µs
	goto IdleLoop      ; 2 * DELAY - 2 µs
	; Total delay 4 * DELAY - 1 + DELAY * (3 * DELAY1 -1) µs
	return

Below is a modification to the above program to drive three servos. Since RC servos don't care much about the length of the interval between the control pulses, we can still use a fixed delay. The worst case variation of the interval is around 7.6 ms.


Loop
	movlw SERVO1        ; Pulse on for servo 1
	movwf SERVO_PORT
	movf PULSE1LEN, W
	movwf PUlSELEN
	call PulseDelay

	movlw SERVO2        ; Pulse on for servo 2
	movwf SERVO_PORT
	movf PULSE2LEN, W
	movwf PUlSELEN
	call PulseDelay

	movlw SERVO3        ; Pulse on for servo 3
	movwf SERVO_PORT
	movf PULSE3LEN, W
	movwf PUlSELEN
	call PulseDelay


	movlw SERVO_OFF     ; All servo pulses off
	movwf PORTC
	call Wait20ms       ; A fixed delay.

	goto Loop

A hardware timer can be used to keep the delay between pulses constant.


	movlw b'xx0x0111'	; Use internal clock for timer0 and a prescaler of 1:256
	movwf OPTION_REG

Loop
	movlw d'255' - d'78'; Reset timer (78*256*1µs = 19.968 ms [assuming 4Mhz clock])
	movwf TMR0
	bcf INTCON, T0IF

	movlw SERVO1        ; Pulse on for servo 1
	movwf SERVO_PORT
	movf PULSE1LEN, W
	movwf PUlSELEN
	call PulseDelay

	movlw SERVO2        ; Pulse on for servo 2
	movwf SERVO_PORT
	movf PULSE2LEN, W
	movwf PUlSELEN
	call PulseDelay

	movlw SERVO3        ; Pulse on for servo 3
	movwf SERVO_PORT
	movf PULSE3LEN, W
	movwf PUlSELEN
	call PulseDelay


	movlw SERVO_OFF     ; All servo pulses off
	movwf PORTC

	btfss INTCON, T01F  ; Wait for Timer0 overflow
	goto $-1

	goto Loop

The programs above waste the CPU's time on busyloops. If you have only one or two servos, there's plenty of time to do other things while waiting for the 20ms timeout. In an event driver program you can use an interrupt to set a flag which triggers the pulse generation. Here is a pseudocode sample how this might be done:


InterruptHandler:
	if timerinterrupt
		increase counter
		if counter==20ms
			set flag SERVOPULSE
			reset counter
	return

Main:
	initialize timer
MainLoop:
	if flag SERVOPULSE
		clear flag SERVOPULSE
		disable interrupts
		set servo1 pin high
		delay pulsetime1
		set servo1 pin low
		enable interrupts        ; Pending interrupts will be serviced now
		; Handle more servos if any
	; Do other things
	goto MainLoop

The actual pulse generation is done in the main loop, as it's generally not a good idea to spend too much time in the interrupt handler. If you can't afford to waste the (number of servos) * ~2 ms it takes to generate the pulses, you can use the hardware timer for the pulses as well, but that takes a bit more coding.