Drone-specific firmware settings for ArduCopter

This appendix lists settings for the ArduCopter firmware that must be set in specific ways in order for our firmware to work correctly with a specific type of drone. The appendix extends the generic firmware settings found in the Setup general autopilot parameters chapter.

Entron 300

LED lights

The LEDs of the Entron 300 are connected to servo outputs 9, 10 and 11 (AUX pins 1, 2 and 3) on the autopilot, although the RGB channels are in a non-standard order. The correct configuration of the firmware is as follows:

SHOW_LED0_TYPE 6
SHOW_LED0_CHAN 0
SERVO9_FUNCTION 108
SERVO10_FUNCTION 109
SERVO11_FUNCTION 107

GPS configuration

The GPS unit in the Entron 300 is auto-detected as a U-Blox unit, but it does not implement the full U-Blox protocol specification. In particular, the GPS unit only sends U-Blox NAV-PVT messages, which contains the time-of-week part of the GPS timestamp, but not the GPS week number. The GPS week number is contained in NAV-SOL, but this is not sent by default. ArduCopter’s GPS autoconfiguration method tries to enable both messages, but since the U-Blox protocol is not fully implemented, the auto-configuration fails with a stock ArduPilot firmware. Furthermore, ArduCopter cannot detect the U-Blox hardware generation of the GPS unit, and thus it cannot infer how many milliseconds the GPS measurements are lagging behind inertial measurements.

Our firmware contains patches to work around the issues outlined above, but you still need to set the following parameters in the firmware:

GPS_AUTO_CONFIG 1
GPS_DRV_OPTIONS 4
GPS_DELAY_MS 220

Setting GPS_AUTO_CONFIG to 1 turns on the GPS autoconfiguration mechanism with our patches, enabling the autopilot to configure the GPS such that it sends NAV-SOL messages. GPS_DRV_OPTIONS instructs the firmware to use a baud rate of 115200 for the GPS unit (U-Blox units typically run at a higher baud rate and the default autoconfiguration routine would not try 115200 baud without this setting). GPS_DELAY_MS informs the firmware that the GPS measurements are lagging behind inertial measurements by 220 msec. This was not measured exactly, but this setting is identical to what was used in earlier versions of ArduCopter and seems to work well in practice. If you can supply us with flight logs that would allow us to estimate the GPS delay more precisely, do not hesitate to contact us.

RTK corrections

Our Entron 300 test drone did not seem to understand MSM7 RTK correction messages, only MSM4. When Skybrush Server is used in conjunction with a U-Blox RTK base station, the server automatically configures the base station to send MSM7 messages by default. To work around this, Skybrush Server needs to be reconfigured to send MSM4 messages instead; this can be done either from the configuration page of the gps extension on the web user interface of Skybrush Server (enter http://localhost:5000 in your browser on the machine that is running on the server), or by extending the configuration file of the server (named skybrush.jsonc) as follows:

{
  "EXTENSIONS": {
    ...
    "rtk": {
        ...,
        "use_high_precision": false
    }
  }
}

Sparkl One

LED lights

The LEDs of the Sparkl One are connected to servo outputs 9, 10 and 11 (AUX pins 1, 2 and 3) on the autopilot. The correct configuration of the firmware is as follows:

SHOW_LED0_TYPE 6
SHOW_LED0_CHAN 0
SERVO9_FUNCTION 107
SERVO10_FUNCTION 108
SERVO11_FUNCTION 109