SimpleBGC Gimbal (aka AlexMos gimbal)

The SimpleBGC is a popular brushless gimbal controller that can communicate with ArduPilot (Copter, Plane, and Rover) using a custom serial protocol. More details on the capabilities of this gimbal can be found at basecamelectronics.com

Note

Support for this gimbal is included in Copter 3.4 (and higher).

Where to Buy

The SimpleBGC controller and accompanying 2-axis and 3-axis gimbals can be purchased from basecamelectronics.com and many other retailers.

Connecting the gimbal to the Flight Controller

../_images/simplebgc-gimbal-pixhawk.png

Although the SimpleBGC can be connected using PWM (similar to the Tarot gimbal) we recommend using the serial interface connected to one of the flight controller’s Serial/Telemetry ports like Telem2 as shown above.

In Ardupilot/APM Planner/Mission planner set the following variables:

  • MNT_TYPE to 4 / “Mount Type (None, Servo or MavLink)”
  • SERIAL2_PROTOCOL to 1 / “MavLink” (Notee “SERIAL2” should be “SERIAL1” if using Telem1 port, SERIAL4 if using Serial4/5, etc)
  • SR2_EXTRA1 to 20
  • SR2_POSITION to 10
  • SR2_RC_CHAN to 20 and all other SR2_* variables to 0.

If you wish to control the pitch angle manually you can set:

  • MNT_RC_IN_TILT to 6
  • In the SimpleBCG GUI in the tab “RC Settings” in the field “Input Configuration” set PITCH to “API_VIRT_CH6”.

Warning

If you connect the gimbal as shown in the above diagram, it is NOT possible to establish a connection to the GUI on a PC via USB and have it connected simultaneously to the flight controller. It happens because the UART1 (“serial” in the picture above) is “paralleled to the onboard USB-UART converter (excepting the “Tiny” boards that has a dedicated USB). If you accidentally connect both the GUI via USB and a flight controller via UART1, you might end up with corrupt data on the flash of the gimbal. It can result in unexpected motor movement! The reason details, please check the link .

Setup through the Ground Station

Set the following parameters through your ground station and then reboot the flight controller:

  • MNT_TYPE to 3 / “AlexMos-Serial”
  • SERIAL2_PROTOCOL to 7 / “AlexMos Gimbal Serial” (Notee “SERIAL2” should be “SERIAL1” if using Telem1 port, SERIAL4 if using Serial4/5, etc)

If you are unable to connect you may wish to set the following parameters although normally this should not be required:

  • SERIAL2_BAUD to 115 (means use serial baudrate of 115200)
  • BRD_SER2_RTSCTS to 0 to disable flow control on Telem2 (use BRD_SER1_RSCTS if connecting to Serial1, Serial4/5 never uses flow control)

The gimbal’s maximum lean angles can be set using these parameters:

To control the gimbal’s lean angles from a transmitter set:

  • MNT_RC_IN_TILT to 6 to control the gimbal’s tilt (aka pitch angle) with the transmitter’s Ch6 tuning knob

For a 3-axis gimbal with 360 degrees of yaw set:

Testing the gimbal moves correctly

Testing the pilot’s control of pitch

Once powered the gimbal should point to it’s Tilt Angle Min (i.e. straight down) when your transmitter’s channel 6 tuning knob is at its minimum PWM value (perhaps around 1000) and the camera should point to its maximum tilt angle (i.e. straight forward) when the tuning knob is at its maximum (perhaps around 2000). The Mission Planner Radio calibration page can be used to check the Ch6’s current input PWM value.

Testing ROI

You must have GPS lock to test ROI. The ROI feature points the vehicle and/or camera to point at a target. The instructions above describe setting up the APM/Pixhawk so that it only controls the Tilt (i.e. pitch) of the Tarot gimbal so when a Do-Set-ROI command is received Copter will attempt to turn the vehicle’s nose to point in the direction of the target and tilt camera depending upon the vehicle’s distance and altitude. You can test the gimbal tilt moves correctly by connecting with the mission planner, then on the Flight Data screen’s map, right-mouse-button-click on a point about 50m ahead of the vehicle (the orange and red lines show the vehicle’s current heading), select Point Camera Here and input an altitude of -50 (meters). This should cause the gimbal to point down at about 45 degrees.

../_images/Tarot_BenchTestROI.jpg