iNavFlight / inav

INAV: Navigation-enabled flight control software
https://inavflight.github.io
GNU General Public License v3.0
3.09k stars 1.46k forks source link

Support – Omnibus F3 – No I2C but PWM 5&6 and UART 3 #3023

Closed DerElch87 closed 6 years ago

DerElch87 commented 6 years ago

Introduction

Hi there,

I’m building an INav Bixler and I’m struggling with available UARTs. My understanding of programming is low, I can program small stuff within the Arduino IDE – but that’s the limit. I have no idea about timer interacting, but I know how critical this topic is.

Situation

FPV plane: Bixler 3 Board: Omnibus F3 RC System: FrSky

Problem

Current possible wiring: UART 1: FrSky SBus UART 2: GPS UART 3: NOT USABLE BECAUSE OF CONFLICT WITH PWM 5&6 Soft Serial: Also not possible --> No telemetry possible as far I can see

First idea

Here my idea: For a typical fixed wing like mine you don’t need I2C. I tried to read the OMNIBUS/target.h but I’m a bit unsure about my idea.

It looks like I2C is enabled instead of PWM 7&8.

// Enable I2C instead of PWM7&8 for iNav
#define USE_I2C
#define USE_I2C_DEVICE_1 // PB6/SCL(PWM8), PB7/SDA(PWM7)
#define USE_I2C_PULLUP

Is it possible to “move” PWM 5&6 to the PWM 7&8 pads and disable I2C? Advantage would be that you can use UART 3 for telemetry or anything else! According to OMNIBUS/target.h it seems like there are some timers left, if necessary (But I'm unsure...)

Second idea

Is there a possibility to enable soft serial on PWM pin 7&8 instead of I2C? Like:

#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define USE_SOFTSERIAL1
#define SERIAL_PORT_COUNT       4                    //stays 4 because of disabled  I2C, right?

#define UART1_TX_PIN            PA9
#define UART1_RX_PIN            PA10

#define UART2_TX_PIN            PA14 // PA14 / SWCLK
#define UART2_RX_PIN            PA15

#define UART3_TX_PIN            PB10 // PB10 (AF7)
#define UART3_RX_PIN            PB11 // PB11 (AF7)

#define SOFTSERIAL_1_RX_PIN     PB6
#define SOFTSERIAL_1_TX_PIN     PB7

// Enable I2C instead of PWM7&8 for iNav
// #define USE_I2C
// #define USE_I2C_DEVICE_1 // PB6/SCL(PWM8), PB7/SDA(PWM7)
// #define USE_I2C_PULLUP

Or even better, a separate target like for the Omnibus F4 ones: Omnibus_soft_serial and Omnibus_I2C

I would really appreciate if somebody is willing to help me

Best regards DerElch

shellixyz commented 6 years ago

You can use PWM7/8 instead of PWM5/6 and that frees UART3 on OMNIBUS with this mod: inav_1.9.0_OMNIBUS.hex.zip

diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c
index 0a5d5545..d836d8a1 100644
--- a/src/main/target/OMNIBUS/target.c
+++ b/src/main/target/OMNIBUS/target.c
@@ -33,9 +33,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
     { TIM15, IO_TAG(PA3),  TIM_Channel_2, 1, IOCFG_AF_PP, GPIO_AF_9,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM3 - PA3
     { TIM15, IO_TAG(PA2),  TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_9,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM4 - PA2

-    // For iNav, PWM6&7 (PWM pins 5&6) are shared with UART3
-    { TIM2,  IO_TAG(PB10), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_1,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7)
-    { TIM2,  IO_TAG(PB11), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_1,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7)
+    { TIM17,  IO_TAG(PB7), TIM_Channel_1, 1 | TIMER_OUTPUT_N_CHANNEL, IOCFG_AF_PP, GPIO_AF_1,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM7
+    { TIM16,  IO_TAG(PB6), TIM_Channel_1, 1 | TIMER_OUTPUT_N_CHANNEL, IOCFG_AF_PP, GPIO_AF_1,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM8

     { TIM1, IO_TAG(PA8),   TIM_Channel_1, 1, IOCFG_AF_PP, GPIO_AF_6,  TIM_USE_LED },
 };
diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h
index cf1d85d7..c6b15491 100644
--- a/src/main/target/OMNIBUS/target.h
+++ b/src/main/target/OMNIBUS/target.h
@@ -175,4 +175,4 @@

 #define USABLE_TIMER_CHANNEL_COUNT  8

-#define USED_TIMERS             (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15))
+#define USED_TIMERS             (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17))
DerElch87 commented 6 years ago

@shellixyz First of all thank you very much. I really appreciate it! Some questions, I hope I don't annoy you too much...

To get the right understanding: This enables PWM 7&8 instead of I2C, right? Does that mean that I need kind of a special mixer in INav that it will recognize or handle the different servo pins like the original ones?

Is there sth. like a manuel how to build my own firmware next time with your settings?

And last one so far, do you or sb. else know some good places where to start learning coding like that? To do at least some changes with timers and resources? I'm willing to spend a lot of hours to get a better understanding here because it's really interesting for me.

Thanks again

DerElch87 commented 6 years ago

I tried to change the target.c and target.h files accordingly that I can also compile in the future by my own, but without success. Here the error message I get after the make command for omnibus

Linking OMNIBUS
c:/dev/gcc-arm-none-eabi-4_8-2014q2/bin/../lib/gcc/arm-none-eabi/4.8.4/../../../../arm-none-eabi/bin/ld.exe: obj/main/inav_OMNIBUS.elf section `.bss' will not fit in region `RAM'
c:/dev/gcc-arm-none-eabi-4_8-2014q2/bin/../lib/gcc/arm-none-eabi/4.8.4/../../../../arm-none-eabi/bin/ld.exe: region `RAM' overflowed by 144 bytes
collect2.exe: error: ld returned 1 exit status
make: *** [Makefile:989: obj/main/inav_OMNIBUS.elf] Fehler 1

Where is my mistake that I can't compile it by my own?

Thanks

stronnag commented 6 years ago

You are using an ancient compiler. Moving to a more recent compiler will help.

shellixyz commented 6 years ago

Some questions, I hope I don't annoy you too much...

No worries

This enables PWM 7&8 instead of I2C, right?

Yes basically. You can still use I2C if the mixer is not using PWM7&8 but the mixer has priority.

Does that mean that I need kind of a special mixer in INav that it will recognize or handle the different servo pins like the original ones?

You should not need a special mixer. The PWM outputs will be shifted. If the mixer wanted to use PWM5&6 it will now use PWM7&8 instead.

Is there sth. like a manuel how to build my own firmware next time with your settings?

To build a target you only need to install the ARM toolchain (recent enough like stronnag stated), also the Ruby interpreter and execute make TARGET=you_target inside the iNav source directory. In your case make TARGET=OMNIBUS. You can find more info on how to install the toolchain on your OS in https://github.com/iNavFlight/inav/tree/master/docs/development

And last one so far, do you or sb. else know some good places where to start learning coding like that? To do at least some changes with timers and resources?

The only iNav documentation for developers I know of is located in the directory I linked previously and in the wiki. You should be able to find a good amount of documentation online to learn C programming. For the timers and other related hardware information you need to refer to your FC MCU datasheet. In the case of the OMNIBUS (F3): STM32F303_datasheet.pdf

shellixyz commented 6 years ago

You should join us on the Slack channel we are always happy to help: https://inavflight.slack.com

DerElch87 commented 6 years ago

@shellixyz and @stronnag Thank you both, moving to the latest version (Version 7-2017-q4-major) made the difference. My first ever successful build :) The file size is different to the one linked by you, @shellixyz , but I think thats probably due to different compiler version?!?

You should not need a special mixer. The PWM outputs will be shifted. If the mixer wanted to use PWM5&6 it will now use PWM7&8 instead.

I'm getting a headache when I try to understand how still I2C could be possible... Also when I look at the target.h file:

-    { TIM2,  IO_TAG(PB10), TIM_Channel_3, 1, IOCFG_AF_PP, GPIO_AF_1,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7)
-    { TIM2,  IO_TAG(PB11), TIM_Channel_4, 1, IOCFG_AF_PP, GPIO_AF_1,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7)
+    { TIM17,  IO_TAG(PB7), TIM_Channel_1, 1 | TIMER_OUTPUT_N_CHANNEL, IOCFG_AF_PP, GPIO_AF_1,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM7
+    { TIM16,  IO_TAG(PB6), TIM_Channel_1, 1 | TIMER_OUTPUT_N_CHANNEL, IOCFG_AF_PP, GPIO_AF_1,  TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO }, // Pin PWM8

It simply looks like you changed the pin and put in a ?new unused? timer and added the sentence TIMER_OUTPUT_N_CHANNEL. There is no / almost no change in the target.h file, where I expected the most changes...

I think I'll have to learn a lot new stuff to understand it. Probably I'll join the slack channel the next days after some deeper reading and understanding.

So thanks again a lot, this is definitely more than someone can expect.

Greetings from Germany (where it's getting warm after a long winter, more than 20 degrees this week :))

shellixyz commented 6 years ago

The file size is different to the one linked by you, @shellixyz , but I think thats probably due to different compiler version?!?

Which version did you build ? If you built 1.9.0 then it is likely down to the compiler version. I'm using GCC version 7.1.0.

I'm getting a headache when I try to understand how still I2C could be possible...

I misspoke. In this case I2C would never be possible because PWM7&8 will always be initialized as outputs. A motor output in case of a MR and a servo output in case of a FW.

It simply looks like you changed the pin and put in a ?new unused? timer and added the sentence TIMER_OUTPUT_N_CHANNEL.

If you take a look at the MCU datasheet in the "Alternate function" section you can see which timer(s) can be used with which output. In this case I had to use TIM16 and TIM17 because they were the only available timers for PB6/PB7 that were not already used for a motor output. Motor and servo outputs can't share a timer because the protocol and so the frequency for controlling motors and servos can be different and so the output/timer frequency. TIMER_OUTPUT_N_CHANNEL was added because the TIM16/17 timers only offer complementary channels for using with PB6/PB7 (TIM16/17_CH1N).

There is no / almost no change in the target.h file, where I expected the most changes...

Nothing needs to be changed in target.h besides the use declaration of the new used timers because the only thing needed to be done was to configure PWM7&8 to be used as outputs and that's done in target.c.

Greetings from Germany (where it's getting warm after a long winter, more than 20 degrees this week :))

Greetings from France. Same here about the weather it's getting warmer and that's very appreciable. We had a nice and warm last week-end :)

DerElch87 commented 6 years ago

I'll close this one for now. Hopefully I can try it this weekend, if not then the week after. You'll get feedback from myself :)

Thanks again for this excellent support BR

DerElch87 commented 6 years ago

Hi there, I tried to get Output 5 and 6 to work, but so far I had no success. Output 5 is connected to PWM 7 on the board and Output 6 is connected to PWM 8. Both show no reactions, wheter to stick input neither to moving the FC.

@shellixyz Is there anything special I have to activate for the output change?

Or is this related to --- edit: not related?

Best regards

DerElch87 commented 6 years ago

Oh sorry, I forgot to include a diff:

# diff

# version
# INAV/OMNIBUS 1.9.0 Apr 10 2018 / 15:27:47 (dc4ef594)

# resources

# mixer
mixer AIRPLANE

# servo mix

# servo

# feature
feature -CURRENT_METER
feature MOTOR_STOP
feature GPS
feature TELEMETRY
feature LED_STRIP
feature AIRMODE
feature PWM_OUTPUT_ENABLE

# beeper

# map

# name

# serial
serial 0 32 115200 38400 0 115200
serial 1 2 115200 115200 0 115200
serial 2 64 115200 38400 0 115200

# led

# color

# mode_color

# aux
aux 0 0 1 900 1075
aux 1 1 0 1400 1600
aux 2 3 4 900 1100
aux 3 9 4 900 1100
aux 4 8 4 1925 2100
aux 5 21 5 1900 2100
aux 6 10 0 900 1075
aux 7 14 0 1925 2100
aux 8 27 2 1900 2100
aux 9 28 2 900 1075
aux 10 11 3 900 1075
aux 11 17 2 900 2100

# adjrange

# rxrange

# master
set looptime = 1000
set gyro_sync = ON
set gyro_sync_denom = 1
set gyro_hardware_lpf = 188HZ
set acc_hardware = MPU6000
set acczero_x = 55
set acczero_y = -30
set acczero_z = -237
set accgain_x = 4079
set accgain_y = 4102
set accgain_z = 4066
set mag_hardware = NONE
set baro_hardware = BMP280
set pitot_hardware = NONE
set receiver_type = SERIAL
set serialrx_provider = SBUS
set motor_pwm_rate = 50
set failsafe_throttle_low_delay = 0
set failsafe_procedure = RTH
set small_angle = 180
set gps_provider = UBLOX7
set gps_sbas_mode = AUTO
set gps_min_sats = 7
set nav_rth_allow_landing = FS_ONLY
set nav_rth_altitude = 3000
set osd_video_system = 1
set osd_rssi_alarm = 35
set osd_main_voltage_pos = 2520
set osd_rssi_pos = 2488
set osd_flymode_pos = 2413
set osd_throttle_pos = 65
set osd_altitude_pos = 2298
set osd_vario_num_pos = 2330
set osd_ontime_flytime_pos = 2552
set osd_messages_pos = 2433

# profile
profile 1

set fw_p_pitch = 20
set fw_i_pitch = 30
set fw_ff_pitch = 15
set fw_p_roll = 20
set fw_i_roll = 30
set fw_ff_roll = 15
set fw_p_yaw = 45
set fw_i_yaw = 5
set fw_ff_yaw = 15
set fw_i_level = 15
set pitch_rate = 15
set yaw_rate = 9

# 
shellixyz commented 6 years ago

The outputs are mapped in order so if you disabled PWM5 and PWM6 and the mixer is using 6 outputs (AIRPLANE) then you should get something on PWM7 and PWM8. PWM1/2 => motors, PWM3/4 => ailerons, PWM7 => rudder, PWM8 => elevator.The issue is I think not related to #3096 because the missing timer declaration is for PWM1 (TIM8). I don't know what the issue is.

DerElch87 commented 6 years ago

@shellixyz After a lot of hours / days tryin to understand the timers, change timers and so on, I finally managed it.

I2C was with the firmware (yours and mine with changed timers) still possible. I tested it with enabling of the OLED I2C display feature, it worked all the time.

In the end I outcommented everything in the OMNIBUS target.h file which was I2C related - and voila PWM7 & 8 are working. Seems like it still got initialized before, but not anymore with the change.

Can somebody give me a hint if the change is safe to fly with?

/*
 * This file is part of Cleanflight.
 *
 * Cleanflight is free software: you can redistribute it and/or modify
 * it under the terms of the GNU General Public License as published by
 * the Free Software Foundation, either version 3 of the License, or
 * (at your option) any later version.
 *
 * Cleanflight is distributed in the hope that it will be useful,
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 * GNU General Public License for more details.
 *
 * You should have received a copy of the GNU General Public License
 * along with Cleanflight.  If not, see <http://www.gnu.org/licenses/>.
 */

#pragma once

#define TARGET_BOARD_IDENTIFIER "OMNI" // https://en.wikipedia.org/wiki/Omnibus

#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE

#define BEEPER                  PC15
#define BEEPER_INVERTED

#define USE_SPI
#define USE_SPI_DEVICE_1

#define SPI1_NSS_PIN            PA4
#define SPI1_SCK_PIN            PA5
#define SPI1_MISO_PIN           PA6
#define SPI1_MOSI_PIN           PA7

#define USE_EXTI

#define USE_GYRO
#define USE_GYRO_MPU6000
#define MPU6000_SPI_BUS         BUS_SPI1
#define MPU6000_CS_PIN          PA4
#define GYRO_INT_EXTI            PC13
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO_MPU6000_ALIGN      CW90_DEG

#define USE_ACC
#define USE_ACC_MPU6000
#define ACC_MPU6000_ALIGN       CW90_DEG

#define USE_BARO
#define USE_BARO_BMP280
#define BMP280_SPI_BUS          BUS_SPI1
#define BMP280_CS_PIN           PA13

/*
#define BARO_I2C_BUS             BUS_I2C1
#define USE_BARO_BMP085 // External
#define USE_BARO_BMP180 // External
#define USE_BARO_MS5611 // External

#define USE_MAG
#define MAG_I2C_BUS             BUS_I2C1
#define USE_MAG_HMC5883
#define USE_MAG_QMC5883
#define USE_MAG_IST8310
#define USE_MAG_MAG3110

#define USE_RANGEFINDER
#define USE_RANGEFINDER_HCSR04
#define RANGEFINDER_HCSR04_ECHO_PIN          PB2  // Has 1K series resistor
#define RANGEFINDER_HCSR04_TRIGGER_PIN       PB4  // FT
#define USE_RANGEFINDER_HCSR04_I2C
#define RANGEFINDER_I2C_BUS                  BUS_I2C1
*/

#define USB_CABLE_DETECTION
#define USB_DETECT_PIN          PB5

#define USE_VCP
#define USE_UART1
#define USE_UART2
#define USE_UART3
#define SERIAL_PORT_COUNT       4

#define UART1_TX_PIN            PA9
#define UART1_RX_PIN            PA10

#define UART2_TX_PIN            PA14 // PA14 / SWCLK
#define UART2_RX_PIN            PA15

#define UART3_TX_PIN            PB10 // PB10 (AF7)
#define UART3_RX_PIN            PB11 // PB11 (AF7)

/*
// Enable I2C instead of PWM7&8 for iNav
#define USE_I2C
#define USE_I2C_DEVICE_1 // PB6/SCL(PWM8), PB7/SDA(PWM7)
#define USE_I2C_PULLUP

#define USE_PITOT_MS4525
#define PITOT_I2C_BUS           BUS_I2C1
*/

#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5

#define SPI2_NSS_PIN            PB12
#define SPI2_SCK_PIN            PB13
#define SPI2_MISO_PIN           PB14
#define SPI2_MOSI_PIN           PB15

//#define USE_RX_SPI
#define RX_SPI_INSTANCE SPI2
#define RX_NSS_PIN PB3

#define USE_SDCARD
#define USE_SDCARD_SPI2

#define SDCARD_DETECT_INVERTED

#define SDCARD_DETECT_PIN                   PC14
#define SDCARD_SPI_INSTANCE                 SPI2
#define SDCARD_SPI_CS_PIN                   SPI2_NSS_PIN

// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx.
#define SDCARD_DMA_CHANNEL_TX               DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5

// Performance logging for SD card operations:
// #define AFATFS_USE_INTROSPECTIVE_LOGGING

#define USE_OSD
#define USE_MAX7456
#define MAX7456_SPI_BUS             BUS_SPI1
#define MAX7456_CS_PIN              PB1

#define USE_ADC
#define ADC_INSTANCE                ADC1
//#define BOARD_HAS_VOLTAGE_DIVIDER
#define ADC_CHANNEL_1_PIN           PA0
#define ADC_CHANNEL_2_PIN           PA1
#define ADC_CHANNEL_3_PIN           PB2
#define ADC_CHANNEL_3_INSTANCE      ADC2
#define VBAT_ADC_CHANNEL            ADC_CHN_1
#define CURRENT_METER_ADC_CHANNEL   ADC_CHN_2
#define RSSI_ADC_CHANNEL            ADC_CHN_3

#define USE_LED_STRIP
#define WS2811_PIN                      PA8
#define WS2811_DMA_STREAM               DMA1_Channel2
#define WS2811_DMA_HANDLER_IDENTIFER    DMA1_CH2_HANDLER

//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT

#define DEFAULT_RX_TYPE         RX_TYPE_PPM
#define DEFAULT_FEATURES        (FEATURE_TX_PROF_SEL | FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_OSD)

#define BUTTONS
#define BUTTON_A_PORT           GPIOB // Non-existent (PB1 used for RSSI/MAXCS)
#define BUTTON_A_PIN            Pin_1
#define BUTTON_B_PORT           GPIOB // TRIG button, used for BINDPLUG_PIN
#define BUTTON_B_PIN            Pin_0

#define USE_SPEKTRUM_BIND
// USART3
#define BIND_PIN                PB11

#define HARDWARE_BIND_PLUG
#define BINDPLUG_PIN            PB0

#define USE_SERIAL_4WAY_BLHELI_INTERFACE

// Number of available PWM outputs
#define MAX_PWM_OUTPUT_PORTS    6

#define TARGET_IO_PORTA         0xffff
#define TARGET_IO_PORTB         0xffff
#define TARGET_IO_PORTC         (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF         (BIT(0)|BIT(1)|BIT(4))

#define USABLE_TIMER_CHANNEL_COUNT  8

#define USED_TIMERS             (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17))
DerElch87 commented 6 years ago

Flight test was OK. Can be closed. Thanks and continue with the good work.