Passthrough telemetry over CRSF (crossfire)

did you follo wmy previous post steps, one of them is

git submodule update --init --recursive

I’ll rebase my branch, wait a second

ok rebased, now do

git checkout pr/crsf_telem_passthrough
git reset --hard origin/pr/crsf_telem_passthrough (to force resync with my branch)
git submodule update --init --recursive (to force sync for all modules)
./waf configure --board KakuteF7
./waf clean
./waf plane

Could a video help you to get a global picture of my setup and helps to reproduice ?

Could you also check your TBS nano settings on TX16S , mine are :

  • Version : 4.0.8
  • Mode 12 CH
  • Telemetry : ON
  • RF Profile : Dynamic or 150Hz
  • Failsafe : Cut
  • RC by MAVLINK : OFF
  • RX batt Sensor : OFF
  • not the Nano RX diversity HW model

TBS micro TX V2 Config :

  • Version : 4.0.8
  • Region : Open
  • Max Power : 100mW
  • Dyn Power : OFF
  • Freq : 868
  • Op Mode : Normal
  • My VTX, Active = OFF

OpenTX version 2.3.10-otx 7ac1ecb6 and 2.3.11-otx tested

diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat 
b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat
index 75a4e16099..47d0f8db11 100644
--- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat
+++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat
@@ -142,7 +142,7 @@ define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"

# setup for OSD
define OSD_ENABLED 1
-define OSD_PARAM_ENABLED 0
+define OSD_PARAM_ENABLED 1
 define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin

@@ -157,6 +157,13 @@ define HAL_BATTMON_FUEL_ENABLE 0
define HAL_PARACHUTE_ENABLED 0
define HAL_SPRAYER_ENABLED 0

+define HAL_CRSF_ENABLED 1
+define HAL_MSP_ENABLED 1
+define HAL_CRSF_TELEM_ENABLED 1
+define HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED 1
+   
 # save FLASH, but leave above when flash issue is fixed
define HAL_MINIMIZE_FEATURES 1

The pr/crsf_telem_passthrough version is compiled successfully, but the lua settings need to be added after the above modification to work. Now the yappu script and crossfire script work perfectly, thank you Alex

oh I see, you mean

+define HAL_CRSF_TELEM_ENABLED 1
+define HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED 1

ok, great!

Sorry for my english~~~ :stuck_out_tongue_closed_eyes:

Hi Alex,

This piece of may introduice a cyclic behaviour, with a 5 sec period :

void AP_CRSF_Telem::adjust_packet_weight(bool queue_empty)
{
uint32_t now_ms = AP_HAL::millis();
setup_custom_telemetry();

/*
 whenever we detect a pending request we configure the scheduler
 to allow faster parameters processing.
 We start a "fast parameter window" that we close after 5sec
*/
bool expired = (now_ms - _custom_telem.params_mode_start_ms) > 5000;
if (!_custom_telem.params_mode_active && _pending_request.frame_type > 0) {
    // fast window start
    _custom_telem.params_mode_start_ms = now_ms;
    _custom_telem.params_mode_active = true;
    enter_scheduler_params_mode();
} else if (expired && _custom_telem.params_mode_active) {
    // fast window stop
    _custom_telem.params_mode_active = false;
    exit_scheduler_params_mode();
}

}
enter_scheduler_params_mode generate a 8Hz on ATTITUDE MSG,
and exit_scheduler_params_mode generate a 1 Hz on ATTITUDE MSG => That is axactly the refresh rate a can measure in OpenTx : Model -> Telemetry page (roll/pitxh/yaw).

My hypothesis is that params_mode_active _custom_telem.params_mode_active is going up, down, up…
What could cause the param request not to be receive ? Who is sending this param request, opentx ? yaapu script ?

could be, that is triggered by receiving a param request from one of the devices on the CRSF bus, like when the crossfire lua script is requesting params, do oyu have any other device running or the TBS Agent X requesting params?

do a quick edit and check yourself by adding some gcs debug

void AP_CRSF_Telem::enter_scheduler_params_mode()
{
    gcs().send_text(MAV_SEVERITY_DEBUG,"CRSF: enter_scheduler_params_mode()");
    set_scheduler_entry(HEARTBEAT, 50, 100);            // heartbeat        10Hz
    set_scheduler_entry(ATTITUDE, 50, 120);             // Attitude and compass 8Hz
    set_scheduler_entry(BATTERY, 1300, 500);            // battery           2Hz
    set_scheduler_entry(GPS, 550, 280);                 // GPS               3Hz
    set_scheduler_entry(FLIGHT_MODE, 550, 500);         // flight mode       2Hz

    disable_scheduler_entry(PASSTHROUGH);
    disable_scheduler_entry(STATUS_TEXT);
}

void AP_CRSF_Telem::exit_scheduler_params_mode()
{
    gcs().send_text(MAV_SEVERITY_DEBUG,"CRSF: exit_scheduler_params_mode()");
    // setup the crossfire scheduler for custom telemetry
    set_scheduler_entry(BATTERY, 1000, 1000);       // 1Hz
    set_scheduler_entry(ATTITUDE, 1000, 1000);      // 1Hz
    set_scheduler_entry(FLIGHT_MODE, 1200, 2000);   // 0.5Hz
    set_scheduler_entry(HEARTBEAT, 2000, 5000);     // 0.2Hz

    enable_scheduler_entry(PASSTHROUGH);
    enable_scheduler_entry(STATUS_TEXT);

    update_custom_telemetry_rates(_telem_rf_mode);
}

…even though if that was the case, having a device continously requesting parameters, you would not have a cyclyc 5 on/5 off but rather a 5 on/5 on/5 on/5 on because hysteresis is only there between on-off transition and not between off-on which is immediate

No Agent, No VTX on the CRSF bus, just MAtek H743-Wing FC + TBS Nano RX.

goodness, just found this thread, and judging the length I already know I’m in over my head. I was trying to enable CRSF with a Kakute F7 V1.5 (non-aio) which has 1Mb flash and I can’t even get RC coms (ignoring telemetry for now). Now I see that CRSF support is not fully sorted out. I was hoping for TBS range + Arducopter + telemetry. I wish I could help with the development but I lack the ability. But if another test case is useful, I’ll volunteer.

I’m seeing here that the 1Mb flash is most likely my first problem? To start with, it sounds like I will need to learn how to compile my own firmware version, and also learn how to remove certain features before compiling so that it will fit on my kakute. That alone is daunting enough to make me want to run SBUS and sacrifice the telemetry. Here’s one question that I’m confused about: are CSRF and Mavlink separate protocols? If so, can I use SBUS for the RCin and then configure the nano to spit out Mavlink telemetry on a separate pin to a separate FC UART?

Hi, it’s working quite well for tens of users actually, tested and used in conjunction with DJI for long range video+RC+telemetry

1 Like

on 1Mb flash? I thought I saw earlier that a reduced compile yet CSRF included was necessary. I just dumped the latest 4.1.0-dev (26a3a02c) on there. Do you think I have misdiagnosed my problem?

I did rebuild the arduplane FW with your patch. the new debug line appear in log appear every 5 sec aprox…

As i was planning to a backup link for MAVLINK, my XF WIFI on the Micro TX V2 has always been connected to my AP as wifi client…
I have juste clicked on" Forget Wifi" in the CRSF LUA Script → XF Wifi, and the issue has disappear !

So the issue seems to be linked with the TBS Wifi Agent running… which is doing param request every 10 sec…

haha…great news! if the agent has a distinctive string we might be able to ignore it’s requests… need to think about it, really glad you figured it out! Good problem solving

Only possible with you help ! Thanks you so much

I will try to do a patch proposal for filtering WIFI agent request…

If you pull in this change as well you should be ok:

try this, as @andyp1per suggested it includes the patch to make it fit on the KakuteF7

https://drive.google.com/file/d/1UYKLAj9Gd-UXrq4RHQUe3v6KWkQgLePl/view?usp=sharing