Omnibus F4 V3 PRO - GPIO pin 56 (PWM 7) not available for assignment.This pin is used for Camera Control

Ardurover 4.0 latest version.
Omnibus F4 V3 Pro

I am trying to allocate GPIO pin 56 (PWM 7) of an Omnibus F4 V3 PRO as a Relay PIN. In allocating the pin for this purpose, a message is displayed on Mission Planner Parameter “RELAY”

RELAY_PIN = 56 Digital pin number for first relay control. This is the pin used for camera control.

I have not setup any camera control parameters and cannot find where it would be set.

The Omnibus F4 V3 PRO has 8 PWM PINS. PWM 7 & PWM 8 pins are solder pads on the PC board.

I had referenced the OMNIBUS F4 documentation that suggested these would be available for allocation.

Ardupilot Hardware Options - Omnibus F4 PRO

Refering to ardupilot AP HAL ChibiOS hwdef file hwdef.dat I refereced the GPIO numbers that are available for allocation.

Extracted from hwdef.dat

#pwm output. 1 - 4 on main header, 5 & 6 on separated header w/o 5V supply, 7 & 8 on CH5 and CH6 pads
PB0 TIM1_CH2N TIM1 PWM(1) GPIO(50)
PB1 TIM1_CH3N TIM1 PWM(2) GPIO(51)
PA3 TIM2_CH4 TIM2 PWM(3) GPIO(52)
PA2 TIM2_CH3 TIM2 PWM(4) GPIO(53)
PA1 TIM2_CH2 TIM2 PWM(5) GPIO(54)
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(55)
PC8 TIM8_CH3 TIM8 PWM(7) GPIO(56)
PC9 TIM8_CH4 TIM8 PWM(8) GPIO(59)

I changed BRD_PWM_COUNT = 2 (originally 8).
Thus should have 6 GPIO pins available for allocation. This does not seem to be the case for GPIO 56.

GPIO 59 can be set without any issues.

Initially tried to use GPIO 56 & GPIO 59 for WENC2 quadrature encoder pins, but a boot message log error displayed
“Warning: WEnc: Failed to attach to pin 56”

I have attached the parameter file ardurover parameter file.
ardurover_4.0_parameters_for_Omnibus_F4_V3_PRO.param (17.1 KB)

Has any one else with this flight controller seen this message?
Is there a fix?

Background.
I am trying to build a rover with skid steering and quadrature encoders.

    2 PWM / 6 GPIO pins allocated as follows:

        PWM1    - Left Motor PWM      [MOT_PWM_TYPE = 3 (BrushedWithRelay)]
        PWM2    - Right Motor PWM      [MOT_PWM_TYPE = 3 (BrushedWithRelay)]
        AUX3    - Left Motor Direction
        AUX4    - Right Motor Direction
        AUX5    - Left Motor Encoder A
        AUX6    - Left Motor Encoder B
        AUX7    - Right Motor Encoder A
        AUX8    - Right Motor Encoder B

Thus I need all eight pins.

Michael

Results of Further Testing

I have executed further testing on this matter.
Replaced ArduRover V4.0 with ArduCopter V4.0.6.
Setup frame class as an octo-rotor drone.
Enabled and tested all 8 PWM outputs, all confirmed working.

Changed frame class to a hex-rotor drone.
Changed BRD_PWM_COUNT to 6.
Enabled CHUTE_TYPE = 0 (First relay)
set RELAY_PIN = 56 (PWM7).
On resetting the board, there was no startup error message for allocation of PIN 56. All six rotor PWM outputs were operating correctly.

Based on these results, I believe there may be an issue on the ardurover v4.0 software for allocating PIN 56 as a GPIO pin.
I am not sure if it only applies to the Omnibus F4 V3 PRO flight controller board, as this has 8 PWM outputs that can also be used as GPIO outputs.

Maybe this issue will be addressed on ArduRover v4.1.

Can someone advise me whether I should create a bug report for this issue?

Michael

Solved. The Omnibus F4 V3 PRO can use all 8 PINS with Ardurover Version 4.0.
But there are caveates when attaching PWM wheel encoders to input pins. Only use pins 52,53,54,55 for the encoder inputs. Pins 56,59 do not work.

I have this now working with the following Pin assignments.

    2 PWM PINS / 6 AUX PINS   (BRD_PWM_COUNT= 2)

    PWM1    - Left Motor PWM   (SERVO1_FUNCTION = 73)   [MOT_PWM_TYPE = 3 (BrushedWithRelay)]
    PWM2    - Right Motor PWM   (SERVO2_FUNCTION = 74)   [MOT_PWM_TYPE = 3 (BrushedWithRelay)]
    AUX3    - Right Motor Encoder B   (WENC_PINA = 55)
    AUX4    - Right Motor Encoder A   (WENC_PINB = 54)
    AUX5    - Left Motor Encoder B   (WENC2_PINA = 53)
    AUX6    - Left Motor Encoder A   (WENC2_PINB = 52)
    AUX7    - Left Motor Direction   (RELAY_PIN = 56)
    AUX8    - Right Motor Direction   (RELAY_PIN2 = 59)

And check carefully for any other default pin assignments. In my case

change RPM_PIN = -1 (originally was set as RPM_PIN = 54)

Differential steering motors are operating correctly.
Wheel encoders are displaying the correct distance travelled in meters for each wheel.

Here is an image of the setup I used to test this.

I hope my experience can be of benefit to someone.

2 Likes