SBus Servo Out on Serial PortΒΆ

This article explains how to configure a serial port to control S.BUS servos. The SBus protocol supports PWM values for 16 channels, and these are mapped to ArduPilot’s servo channels 1-16. The transmission rate is 100K baud with inverted logic levels (unidirectional: output only), and an inverting cable will be required to use a standard serial port. A simple NPN transistor inverter will suffice:

../_images/sbus_inverter.png

Set the protocol for the desired serial port to SBUS1. For example, to use port Telem2 (serial2) set parameter SERIAL2_PROTOCOL: Telemetry 2 protocol selection to 15. When SBus protocol is selected, the port’s baud rate parameter (in this case SERIAL2_BAUD: Telemetry 2 Baud Rate) will automatically be set to 100,000. Parameter SERVO_SBUS_RATE: SBUS default output rate defaults to 50 Hz, but may be set to any value in the range of [25,250] Hz. Beware that some SBus to PWM adapters e.g. FrSky generate a fixed PWM output rate (~170 Hz) that may damage analog servos. Digital servos and those designed with SBus inputs should handle high frame rates with no problems.