iNavFlight / inav

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

New Target Request; HIFIONRC F7 AIO 25A/45A #6489

Closed ltwin8 closed 2 years ago

ltwin8 commented 3 years ago

Current Behavior

No fitting target found in inav

Desired Behavior

Please add a target for the board https://www.banggood.com/25_5x25_5mm-HIFIONRC-AIO-F7-Flight-Controller-OSD-Built-in-45A-Blheli_S-2-6S-4-In-1-Brushless-ESC-for-FPV-Racing-Drone-p-1716359.html?cur_warehouse=CN&rmmds=search

I think this board has good potential for inav since it has many useful features, for example: 7 full UARTs A Barometric pressure sensor 25A or 45A 2-6S capable ESC (with BB2 MCU, G-H-30) (depending on version) 5V 3A SBEC whoop-sized, 25.5 x 25.5 mm

Suggested Solution

the resource assignments can be found in here:

https://raw.githubusercontent.com/betaflight/unified-targets/master/configs/default/HFOR-HIFIONRCF7.config

Who does this impact? Who is this for?

likely big part of the hobby since sub 250g is more and more important, this board is light (7.5g) and also packs good features, ESCis not only capable for whoops, I rn it on 1900kv 2306 6S 5" "toothpick-style"

Additional context

I think the above resources are suitable to add the target to the official iNav, if I understand correctly, the target should be very close to the already supported mamba F722 FC

ltwin8 commented 3 years ago

Updated in .zip file below

`/*

//this is Part of INAV Sourcecode, more exactly target.h for MAMBAF722, modified by LTwin8 to fit HIFIONRCF7 AIO and HIFIONRCF7 PRO

//Used resources are the INAV-Code and the Betaflight unified target file https://raw.githubusercontent.com/betaflight/unified-targets/master/configs/default/HFOR-HIFIONRCF7.config

pragma once

define USE_TARGET_CONFIG

define TARGET_BOARD_IDENTIFIER "HFOR"

define USBD_PRODUCT_STRING "HIFIONRCF7"

// **** Board LEDs **

define LED0 PA15 //taken from unified target

//#define LED1 PC14 //No 2nd LED defined in unified target

// * Beeper *****

define BEEPER C15 //taken from unified target

define BEEPER_INVERTED

// *** GYRO and ACC ****

define USE_EXTI

define GYRO_INT_EXTI PC4 //taken from unified target, additional Interrupt available on C03

define USE_MPU_DATA_READY_SIGNAL

define MPU6000_CS_PIN SPI1_NSS_PIN //B02 & A04, taken from unified target

define MPU6000_SPI_BUS BUS_SPI1

define USE_IMU_MPU6000

define IMU_MPU6000_ALIGN CW90_DEG //taken from unified target

// *** Baro **

define USE_I2C

define USE_I2C_DEVICE_2

define I2C2_SCL PB6 // SCL pad TX3 //taken from unified target

define I2C2_SDA PB7 // SDA pad RX3 //taken from unified target

define DEFAULT_I2C_BUS BUS_I2C2

define USE_BARO

define BARO_I2C_BUS DEFAULT_I2C_BUS

define USE_BARO_BMP280

define USE_BARO_MS5611

//* Magnetometer / Compass *** //#define USE_MAG //#define MAG_I2C_BUS DEFAULT_I2C_BUS //taken from unified target, no mag onboard

//#define USE_MAG_HMC5883 //#define USE_MAG_QMC5883 //#define USE_MAG_LIS3MDL

// *** SERIAL ****

define USE_VCP

define USE_UART1

define USE_UART2

define USE_UART3

define USE_UART4

define USE_UART5

define USE_UART6

//#define USE_SOFTSERIAL1 //SoftSerial not needed, 6 full UARTs available, for example: GPS, ESC-telemetry, S.Port, VTX (TBS, IRC or DJI), Bluetooth, 1 free UART left, 2 free UARTS left if using only one uart for RC&telemetry (F.Port or CRSF for example)

define UART1_TX_PIN PA9 //taken from unified target

define UART1_RX_PIN PA10 //taken from unified target

define UART2_TX_PIN PA2 //taken from unified target

define UART2_RX_PIN PA3 //taken from unified target

define UART3_TX_PIN PB10 //taken from unified target

define UART3_RX_PIN PB11 //taken from unified target

define UART4_TX_PIN PA0 //taken from unified target

define UART4_RX_PIN PA1 //taken from unified target

define UART5_TX_PIN PC12 //taken from unified target

define UART5_RX_PIN PD2 //taken from unified target

define UART6_TX_PIN PC6 //taken from unified target

define UART6_RX_PIN PC7 //taken from unified target

define SOFTSERIAL_1_TX_PIN PA2 //taken from unified target

define SOFTSERIAL_1_RX_PIN PA2 //taken from unified target

define SERIAL_PORT_COUNT 8

// *** SPI ****

define USE_SPI

define USE_SPI_DEVICE_1 //taken from unified target //MPU6000

define SPI1_NSS_PIN PA4 //taken from unified target //Gyro CS 2

define SPI1_SCK_PIN PA5 //taken from unified target

define SPI1_MISO_PIN PA6 //taken from unified target

define SPI1_MOSI_PIN PA7 //taken from unified target

define USE_SPI_DEVICE_2 //taken from unified target //OSD Chip

define SPI2_NSS_PIN PB12 //taken from unified target

define SPI2_SCK_PIN PB13 //taken from unified target

define SPI2_MISO_PIN PB14 //taken from unified target

define SPI2_MOSI_PIN PB15 //taken from unified target

define USE_SPI_DEVICE_3 //taken from unified target // BlackBox Flash

define SPI3_NSS_PIN PC13 //taken from unified target

define SPI3_SCK_PIN PC10 //taken from unified target

define SPI3_MISO_PIN PC11 //taken from unified target

define SPI3_MOSI_PIN PB5 //taken from unified target

// *** ADC ****

define USE_ADC

define ADC_CHANNEL_1_PIN PC2 //taken from unified target

define ADC_CHANNEL_2_PIN PC0 //taken from unified target

define ADC_CHANNEL_3_PIN PC1 //taken from unified target

define VBAT_ADC_CHANNEL ADC_CHN_1

define RSSI_ADC_CHANNEL ADC_CHN_2

define CURRENT_METER_ADC_CHANNEL ADC_CHN_3

define VBAT_SCALE_DEFAULT 1100 //unknown

// *** OSD ****

define USE_OSD //matches unified target

define USE_MAX7456

define MAX7456_SPI_BUS BUS_SPI2

define MAX7456_CS_PIN SPI2_NSS_PIN

//*** FLASH ****

define USE_FLASHFS //matches unified target, exact chip type not known yet, but seems right, the 30.5mm HIFIONRC has 16MB BB

define USE_FLASH_M25P16

define M25P16_CS_PIN SPI3_NSS_PIN

define M25P16_SPI_BUS BUS_SPI3

define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT //yes, no SD Card

//**** LEDSTRIP *****

define USE_LED_STRIP

define WS2811_PIN PA8 //taken from unified target

// *** FEATURES ****

define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL

define SERIALRX_UART SERIAL_PORT_USART2 //taken from Product Page

define SERIALRX_PROVIDER SERIALRX_SBUS

define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY) //no SoftSerial

define TARGET_IO_PORTA 0xffff //not sure

define TARGET_IO_PORTB 0xffff //not sure

define TARGET_IO_PORTC 0xffff //not sure

define TARGET_IO_PORTD (BIT(2)) //not sure

define MAX_PWM_OUTPUT_PORTS 8 //not sure, would guess 4, because its aiming towards quadcopters

define TARGET_MOTOR_COUNT 4 //taken from unified target, Motors 1,2,3,4 are located on PB0, PB1, PB4, PB3

// ESC-related features

define USE_DSHOT

define USE_SERIALSHOT

define USE_ESC_SENSOR

define USE_SERIAL_4WAY_BLHELI_INTERFACE

`

Above is a modified target.h file (taken from MAMBAF722) and modified to fit the HIFIONRCF7 AIO and HIFIONRCF7 PRO

ltwin8 commented 3 years ago

Updated in .zip file below

`/*

//this is Part of INAV Sourcecode, more exactly target.h for MAMBAF722, modified by LTwin8 to fit HIFIONRCF7 AIO and HIFIONRCF7 PRO

//Used resources are the INAV-Code and the Betaflight unified target file https://raw.githubusercontent.com/betaflight/unified-targets/master/configs/default/HFOR-HIFIONRCF7.config

include

include

include

include "common/axis.h"

include "config/config_master.h"

include "config/feature.h"

include "drivers/sensor.h"

include "drivers/pwm_esc_detect.h"

include "drivers/pwm_output.h"

include "drivers/serial.h"

include "fc/rc_controls.h"

include "flight/failsafe.h"

include "flight/mixer.h"

include "flight/pid.h"

include "rx/rx.h"

include "io/serial.h"

include "sensors/battery.h"

include "sensors/sensors.h"

include "telemetry/telemetry.h"

void targetConfiguration(void) { //no hardwired UARTs, no Softserial } `

Above is a modified config.c file (taken from MAMBAF722) and modified to fit the HIFIONRCF7 AIO and HIFIONRCF7 PRO

ltwin8 commented 3 years ago

HIFIONRCF722.zip

Hello, I compiled the file and it seems to work, sadly still not able to test since the hardware is on its way to me from china. @digitalentity @DzikuVx

I hope you can Pull this piece into the main code if you approve it.

krizw commented 3 years ago

HIFIONRCF722.zip

Hello, I compiled the file and it seems to work, sadly still not able to test since the hardware is on its way to me from china. @digitalentity @DzikuVx

I hope you can Pull this piece into the main code if you approve it.

Where is the hex file for me to try?

ltwin8 commented 3 years ago

HIFIONRCF722.zip Hello, I compiled the file and it seems to work, sadly still not able to test since the hardware is on its way to me from china. @digitalentity @DzikuVx I hope you can Pull this piece into the main code if you approve it.

Where is the hex file for me to try?

hello, there you go. but please, be careful! I have not really programmed iNav before, but I guess it should be okay, Please test the Gyro and motors before flying, but testing without props...

even if this does not work one should be able to flash back to Betaflight "Note: STM32 bootloader is stored in ROM, it cannot be bricked."

I am more into hardware than deep dive in iNav Software, but I think it should not harm your hardware (besides if it crashes or so)

maybe you can test without props and let me know

thanks for your help

inav_2.7.0_HIFIONRCF722.hex.zip

krizw commented 3 years ago

Hello, I had a very quick go with your Hex, on the bench, the barometer was unavailable (RED), the battery voltage read about 1.4v and the DJI OSD was not showing. Motors ran and were in the correct order, CRSF receiver worked and showed correctly in a tab, GPS worked, Accelerometer calibrated ok. Ports tab showed Uarts 1 to 6 ok, but then another Uart 1 between 5 and 6.

Thank you for your work, I hope we can get an official build eventually. I will try any other versions you make.

Cheers

Chris ------ Original Message ------ From: "ltwin8" notifications@github.com To: "iNavFlight/inav" inav@noreply.github.com Cc: "krizw" kriz.w@talk21.com; "Comment" comment@noreply.github.com Sent: Wednesday, 13 Jan, 21 At 17:46 Subject: Re: [iNavFlight/inav] New Target Request; HIFIONRC F7 AIO 25A/45A (#6489)

HIFIONRCF722.zip https://github.com/iNavFlight/inav/files/5810055/HIFIONRCF722.zip Hello, I compiled the file and it seems to work, sadly still not able to test since the hardware is on its way to me from china. @digitalentity https://github.com/digitalentity @DzikuVx https://github.com/DzikuVx I hope you can Pull this piece into the main code if you approve it. Where is the hex file for me to try? hello, there you go. but please, be careful! I have not really programmed iNav before, but I guess it should be okay, Please test the Gyro and motors before flying without props... even if this does not work one should be able to flash back to Betaflight "Note: STM32 bootloader is stored in ROM, it cannot be bricked." I am more into hardware than deep dive in iNav Software, but I think it should not harm your hardware (besides if it crashes or so) maybe you can test without props and let me know thanks for your help inav_2.7.0_HIFIONRCF722.hex.zip https://github.com/iNavFlight/inav/files/5810234/inav_2.7.0_HIFIONRCF722.hex.zip — You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/iNavFlight/inav/issues/6489#issuecomment-759611100 , or unsubscribe https://github.com/notifications/unsubscribe-auth/ARAT5DPQOURTJTMR3WOCSY3SZXL6FANCNFSM4V3YUNLA .

ltwin8 commented 3 years ago

Thanks for testing.

motors ran on dshot? which UART was the DJI OSD? have you tried all? maybe I mixed something up (for example inav uart2 is board uart5)

Battery not working, OK I thought that would be so, have you tried and adjusted the scale? I had no idea and just set 110 if that not works, what does Analog RSSI and current show? background: VBAT, RSSI, CURR are all ADC Channels, maybe I mixed them up and as soon as you plug the lipo for example RSSI shows strange behavior

CRSF Worked on a UART? numbering correct?

Baro was unavailable that means the I2C is not working, looking into it.

second UART1 shown, okay, I look into that

ltwin8 commented 3 years ago

Update on Baro: I am looking into the type, I2C Bus should be okay, PB06 as SCL PB07 as SDA

I am looking into #define USE_I2C_PULLUP

attached a new hex, should address I2C

Please set the bat scale to 1100, that's what the mamba f722 uses and they seem to have the same voltage divider

inav_2.7.0_HIFIONRCF722.hex.zip

ltwin8 commented 3 years ago

Duplicated UART, my bad, sorry, soft serial was still in there... updated 👍

inav_2.7.0_HIFIONRCF722.hex.zip

krizw commented 3 years ago

Dshot 300 workedDJI osd was on UART 1Crsf was on UART 2ESC telemetry on UART 3BLUETOOTH on UART 4 (forgot to test) MSPGPS on UART 5All connections worked in BF 4.2.4On 13 Jan 2021 19:31, ltwin8 notifications@github.com wrote: Thanks for testing. motors ran on dshot? which UART was the DJI OSD? have you tried all? maybe I mixed something up (for example inav uart2 is board uart5) sorry edit while writing: I skip this for now, I remember something that DJI OSD and Inav don't like each other. Battery not working, OK I thought that would be so, have you tried and adjusted the scale? I had no idea and just set 110 if that not works, what does Analog RSSI and current show? background: VBAT, RSSI, CURR are all ADC Channels, maybe I mixed them up and as soon as you plug the lipo for example RSSI shows strange behavior CRSF Worked on a UART? numbering correct? Baro was unavailable that means the I2C is not working, looking into it. second UART1 shown, okay, I look into that

—You are receiving this because you commented.Reply to this email directly, view it on GitHub, or unsubscribe.

ltwin8 commented 3 years ago

Okay, shot working should mean timer correct, good thing

Maybe you can try again DJI osd, one UART1 was soft serial with wrong pins in disguise, so maybe in the last uploaded hex it works.

does the blackbox work?

Can you upload fonts to the analog osd? (I know you use digital just to see if the SPI Interface to it works, I think iNav errors out if it can not communicate with the OSD during uploading)

Does the Battery voltage show correct after "set vbat_scale = 1100" ?

so just to keep track the issues -DJI OSD not working -VBAT wrong Value -duplicated UART -Baro not working

I will update List when issue is fixed

krizw commented 3 years ago

DJI osd workingOsd analogue font loadsBatt voltage works with 1100 scaleBaro working ( on bench not flown )Data flash shows data saved ( not checked data content )Good workOn 13 Jan 2021 20:04, ltwin8 notifications@github.com wrote: Okay, shot working should mean timer correct, good thing Maybe you can try again DJI osd, one UART1 was soft serial with wrong pins in disguise, so maybe in the last uploaded hex it works. does the blackbox work? Can you upload fonts to the analog osd? (I know you use digital just to see if the SPI Interface to it works, I think iNav errors out if it can not communicate with the OSD during uploading) Does the Battery voltage show correct after "set vbat_scale = 1100" ? so just to keep track the issues -DJI OSD not working -VBAT wrong Value -duplicated UART -Baro not working I will update List when issue is fixed

—You are receiving this because you commented.Reply to this email directly, view it on GitHub, or unsubscribe.

ltwin8 commented 3 years ago

Okay, thanks for testing.

If any issues please update me

I can not guarantee, but I think flying should be okay.

krizw commented 3 years ago

could you define the magnetometer, please

//* Magnetometer / Compass *** //#define USE_MAG //#define MAG_I2C_BUS DEFAULT_I2C_BUS //taken from unified target, no mag onboard

//#define USE_MAG_HMC5883 //#define USE_MAG_QMC5883 //#define USE_MAG_LIS3MDL

krizw commented 3 years ago

Could you add the magnetometer, please?

------ Original Message ------ From: "ltwin8" notifications@github.com To: "iNavFlight/inav" inav@noreply.github.com Cc: "krizw" kriz.w@talk21.com; "Comment" comment@noreply.github.com Sent: Wednesday, 13 Jan, 21 At 21:35 Subject: Re: [iNavFlight/inav] New Target Request; HIFIONRC F7 AIO 25A/45A (#6489)

Okay, thanks for testing. If any issues please update me I can not guarantee, but I think flying should be okay. — You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/iNavFlight/inav/issues/6489#issuecomment-759753892 , or unsubscribe https://github.com/notifications/unsubscribe-auth/ARAT5DKGBLVSRFM7HGZBU7TSZYG2TANCNFSM4V3YUNLA .

ltwin8 commented 3 years ago

Hello,

AFAIK there is no magnetometer on the board?

Maybe add one through I2C?

krizw commented 3 years ago

I have added one on the I2C, i think drivers required, it's not working as it is.On 23 Jan 2021 21:00, ltwin8 notifications@github.com wrote: Hello, AFAIK there is no magnetometer on the board? Maybe add one through I2C?

—You are receiving this because you commented.Reply to this email directly, view it on GitHub, or unsubscribe.

ltwin8 commented 3 years ago

Okay, i will compile a version for it

ltwin8 commented 3 years ago

I hope this will help you

inav_2.7.0_HIFIONRCF722.hex.zip

krizw commented 3 years ago

Obviously, I have no idea, but this is how it is set up on my matek f405. Thanks in advance.

// *** I2C ****// SLC clash with WS2812 LED#ifdef MATEKF405OSD // OSD - no native I2C #define USE_I2C #define USE_I2C_DEVICE_EMULATED #define I2C_DEVICE_EMULATED_SHARES_UART3 #define SOFT_I2C #define SOFT_I2C_SCL PC10 //TX3 pad #define SOFT_I2C_SDA PC11 //RX3 pad #define DEFAULT_I2C_BUS BUS_I2C_EMULATED#else // AIO / CTR / STD #define USE_I2C #define USE_I2C_DEVICE_1

define I2C1_SCL PB6 #define I2C1_SDA

PB7 #define DEFAULT_I2C_BUS BUS_I2C1#endif#define USE_BARO#define BARO_I2C_BUS DEFAULT_I2C_BUS#define USE_BARO_BMP280#define USE_BARO_MS5611#define USE_BARO_BMP085#define USE_BARO_DPS310#define USE_MAG#define MAG_I2C_BUS DEFAULT_I2C_BUS#define USE_MAG_AK8963#define USE_MAG_AK8975#define USE_MAG_HMC5883#define USE_MAG_QMC5883#define USE_MAG_IST8310#define USE_MAG_IST8308#define USE_MAG_MAG3110#define USE_MAG_LIS3MDL#define TEMPERATURE_I2C_BUS DEFAULT_I2C_BUS#define USE_RANGEFINDER#define USE_RANGEFINDER_MSP#define USE_RANGEFINDER_HCSR04_I2C#define RANGEFINDER_I2C_BUS DEFAULT_I2C_BUS#define PITOT_I2C_BUS DEFAULT_I2C_BUS

------ Original Message ------ From: "ltwin8" notifications@github.com To: "iNavFlight/inav" inav@noreply.github.com Cc: "krizw" kriz.w@talk21.com; "Comment" comment@noreply.github.com Sent: Saturday, 23 Jan, 21 At 21:09 Subject: Re: [iNavFlight/inav] New Target Request; HIFIONRC F7 AIO 25A/45A (#6489)

Okay, i will compile a version for it — You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/iNavFlight/inav/issues/6489#issuecomment-766179550 , or unsubscribe https://github.com/notifications/unsubscribe-auth/ARAT5DPO2IBFZBW4RVSTCKLS3M3KPANCNFSM4V3YUNLA .

krizw commented 3 years ago

You are fast, wow.

------ Original Message ------ From: "ltwin8" notifications@github.com To: "iNavFlight/inav" inav@noreply.github.com Cc: "krizw" kriz.w@talk21.com; "Comment" comment@noreply.github.com Sent: Saturday, 23 Jan, 21 At 21:24 Subject: Re: [iNavFlight/inav] New Target Request; HIFIONRC F7 AIO 25A/45A (#6489)

I hope this will help you inav_2.7.0_HIFIONRCF722.hex.zip https://github.com/iNavFlight/inav/files/5861062/inav_2.7.0_HIFIONRCF722.hex.zip — You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/iNavFlight/inav/issues/6489#issuecomment-766181538 , or unsubscribe https://github.com/notifications/unsubscribe-auth/ARAT5DO2RY5MYDCXQ4ZONI3S3M5CBANCNFSM4V3YUNLA .

ltwin8 commented 3 years ago

i have uncommented

`

define MAG_I2C_BUS DEFAULT_I2C_BUS //taken from unified target, no mag onboard

define USE_MAG_HMC5883

define USE_MAG_QMC5883

define USE_MAG_LIS3MDL

`

that should do.

krizw commented 3 years ago

I hope this will help you

inav_2.7.0_HIFIONRCF722.hex.zip

no improvement.

ltwin8 commented 3 years ago

Oh okay, could you try if your setup works on BF? (the baro itself?)

krizw commented 3 years ago

Oh okay, could you try if your setup works on BF? (the baro itself?)

BARO works on both BF and INAV MAG does not work on either

ltwin8 commented 3 years ago

sorry, I mean the mag, okay, if it not works maybe is the wiring wrong?

krizw commented 3 years ago

You cannot even get the MAG icon in RED (settings correct, but no data), even if my wiring were wrong (2 wires) the MAG icon would be red.

------ Original Message ------ From: "ltwin8" notifications@github.com To: "iNavFlight/inav" inav@noreply.github.com Cc: "krizw" kriz.w@talk21.com; "Comment" comment@noreply.github.com Sent: Saturday, 23 Jan, 21 At 22:07 Subject: Re: [iNavFlight/inav] New Target Request; HIFIONRC F7 AIO 25A/45A (#6489)

sorry, I mean the mag, okay, if it not works maybe is the wiring wrong? — You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/iNavFlight/inav/issues/6489#issuecomment-766187110 , or unsubscribe https://github.com/notifications/unsubscribe-auth/ARAT5DJSZT22EM4OO7N7QX3S3NCCLANCNFSM4V3YUNLA .

ltwin8 commented 3 years ago

i will test it once I have the hardware and mill test where the Pads are connected.

so mag do not work in BF either?

Bolgor commented 3 years ago

Hello. I had problem witch beitian BN 880 mag on Hifionrc f7 pro on betaflight. I am a beginner but I managed to turn on the magnitometr after resource remaping of pads and few changes in cliI can send the dump file witch my configuration but I dont know IT is correct. Maybe that will help you.

ltwin8 commented 3 years ago

I guess you used UART 3 for that?

Bolgor commented 3 years ago

Probably. https://1drv.ms/t/s!AsMpMZ_U-o0R8lLE5W1-v-ei2VIG But i remapping motor 5 and 6 too.

ltwin8 commented 3 years ago

https://www.st.com/resource/en/datasheet/stm32f723vc.pdf

Page 81/82, so you used i2c capable pins...

done that in my repo for the AIO where UART 3 should be i2c

but I do not know inav well enough to know how to use 2 i2c (internal baro, external mag for example) Busses

Bolgor commented 3 years ago

After only remapping mag didn't work. I change few options in cli and mag started:

set align_mag = CW270FLIP set mag_align_roll = 0 set mag_align_pitch = 1800 set mag_align_yaw = 2700 set mag_bustype = I2C set mag_i2c_device = 2 set mag_i2c_address = 0 set mag_spi_device = 2 set mag_hardware = AUTO set mag_declination = 0 set mag_calibration = 50,-40,-260 set baro_bustype = I2C set baro_spi_device = 1 set baro_i2c_device = 1 set baro_i2c_address = 0 set baro_hardware = AUTO

But I don't know that parameters will help you.

krizw commented 3 years ago

Did the mag show up in red after you remapped, and then blue after CLI changes?On 27 Jan 2021 08:06, Bolgor notifications@github.com wrote: After only remapping mag didn't work. I change few options in cli and mag started: set align_mag = CW270FLIP set mag_align_roll = 0 set mag_align_pitch = 1800 set mag_align_yaw = 2700 set mag_bustype = I2C set mag_i2c_device = 2 set mag_i2c_address = 0 set mag_spi_device = 2 set mag_hardware = AUTO set mag_declination = 0 set mag_calibration = 50,-40,-260 set baro_bustype = I2C set baro_spi_device = 1 set baro_i2c_device = 1 set baro_i2c_address = 0 set baro_hardware = AUTO But I don't know that parameters will help you.

—You are receiving this because you commented.Reply to this email directly, view it on GitHub, or unsubscribe.

Bolgor commented 3 years ago

I don't remember about red blinking light (remapped that few months ago) after remapping but maybe this movie will be helpful: https://youtu.be/coHFI4fsTes

krizw commented 3 years ago

What remapping did you do, to get the mag working?

------ Original Message ------ From: "Bolgor" notifications@github.com To: "iNavFlight/inav" inav@noreply.github.com Cc: "krizw" kriz.w@talk21.com; "Comment" comment@noreply.github.com Sent: Wednesday, 27 Jan, 21 At 19:16 Subject: Re: [iNavFlight/inav] New Target Request; HIFIONRC F7 AIO 25A/45A (#6489)

I don't remember about red blinking light (remapped that few months ago) after remapping but maybe this movie will be helpful: https://youtu.be/coHFI4fsTes https://youtu.be/coHFI4fsTes — You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/iNavFlight/inav/issues/6489#issuecomment-768514416 , or unsubscribe https://github.com/notifications/unsubscribe-auth/ARAT5DMVDUI7ADWXKTJV3LLS4BQ7VANCNFSM4V3YUNLA .

ltwin8 commented 3 years ago

inav_2.7.0_HIFIONRCF722.hex.zip maybe you can try this, SCL on on TX3 and SDA on RX3

LeonardovichD commented 3 years ago

Hi! I have hifionrc board and want to work it with inav. Could I help you with some tests? I'm able to do some one by one steps, but i'm noob in programming. Tell me what to do)

ltwin8 commented 3 years ago

can you measure where the SDA and SCL Pads are connected to? which cpu pins

LeonardovichD commented 3 years ago

can you measure where the SDA and SCL Pads are connected to? which cpu pins

If you write how to do this) Be my brains, and I'll be your hands. Also I can give you access to my computer by teamviewer

ltwin8 commented 3 years ago

you take a multimeter with very fine tips and measure in resistance mode where the pads are connected to, continuity testing

LeonardovichD commented 3 years ago

10pin scl 11pin sda

LeonardovichD commented 3 years ago

https://drive.google.com/file/d/1Ace4vfIft7m2OiXP0cshKjpYQP5rGQcT/view?usp=drivesdk

Bolgor commented 3 years ago

I made this changes: resource MOTOR 5 C09 remapping to resource SERIAL_RX 3 C09 after that resource MOTOR 5 NONE resource MOTOR 6 C08 remapping to resource SERIAL_TX 3 C08 after that resource MOTOR 6 NONE resource I2C_SCL 2 NONE remapping to resource I2C_SCL 2 B10 resource I2C_SDA 2 NONE remapping to resource I2C_SDA 2 B11

In the link fresh betaflight dump file and file after few changes done by me. https://1drv.ms/u/s!AsMpMZ_U-o0RgbVhqLGdqeUn6_4T9g?e=azeGrM

LeonardovichD commented 3 years ago

It was helpful?

ltwin8 commented 3 years ago

Pin 10 and pin 11 are needed the uart3 pins regarding to configuration. so an additional bus

ltwin8 commented 3 years ago

thank you, that was helpful

ltwin8 commented 3 years ago

just let me change something, I can not #define use_mag because error.

I hope it is enough to set external i2c bus default and then do it in configurator

ltwin8 commented 3 years ago

inav_2.7.0_HIFIONRCF722.hex.zip

Default bus set to the Pads (Port B bit 10 and 11), UART3 NOT usable, that are the i2c2 pins i2c1 (internal, connected to Baro) not any more default

when testing please report back if:

Shothertz commented 3 years ago

Hi! The pic https://drive.google.com/file/d/1Ace4vfIft7m2OiXP0cshKjpYQP5rGQcT/view?usp=drivesdk is 90° out. SDA is on pin 59 (PB7) and SCL on pin 58 (PB6) The internal baro and the external mag runs on the same i2c bus resource I2C_SCL 1 B06 resource I2C_SDA 1 B07

Set the mag i2c on adresses 0

set mag_bustype = I2C set mag_i2c_device = 1 set mag_i2c_address = 0 set mag_spi_device = 0 set mag_hardware = AUTO set mag_declination = 0 set mag_calibration = 0,0,0 set baro_bustype = I2C set baro_spi_device = 0 set baro_i2c_device = 1 set baro_i2c_address = 0 set baro_hardware = AUTO

Tested and working on mine HIFIONRC F7 PRO V2 + GPS BN880 + mag on BetaFlight