lida2003
(Daniel Li)
May 28, 2023, 7:19am
1
Hi guys,
My VTX is Not working on arduPilot, so any ideas? Or any configurations I have to check?
I’m using H743 flying Copter 4.3.6 with PandaRC VT5804M L1 (Buzzer/Mic/IRC Protocol) 5.8G
I follow the guide Video Transmitter Support — Copter documentation , and set my configurations below:
SERIAL4_PROTOCOL 44 //IRC Tramp
SERIAL4_OPTION 4 //HalfDuplex
VTX_ENABLE 1
VTX_BAND = 4 //R
VTX_CHANNEL = 7 //8
VTX_FREQ = 0 //default, no idea, it’s readonly
VTX_POWER = 600
VTX_MAX_POWER = 800 //default
VTX_OPTIONS =8 //default
Note: Hardware connection should be fine, since bf 4.4.1/4.3.1 works fine with VTX.
Running script C:\Users\Administrator\AppData\Local.mavproxy\mavinit.scr
→ set moddebug 2
→ module load help
online system 1
Mode STABILIZE
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
fence present
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
AP: ArduCopter V4.3.6 (0c5e999c)
AP: ChibiOS: 66e5de0d
AP: H743_BMI270x2_v23 00290029 30315119 39373436
AP: RCOut: DS600:1-4 PWM:5-8
AP: Frame: QUAD/X
TRAMP: send command ‘r’: 0
Flight battery 100 percent
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
AP: PreArm: Throttle below failsafe
AP: PreArm: Compass not calibrated
TRAMP: send command ‘r’: 0
TRAMP: send command ‘r’: 0
I’m NOT sure if it’s related with hardware configurations: (I have checked NODMA or get rid of “NODMA”, all is not going to work.)
lida2003
(Daniel Li)
May 28, 2023, 10:36pm
2
I found a couple of links talking about this. I’m NOT sure about what’s happening in my fc.
Hello all,
I had Matek H743-wing v3 controller running Plane v4.3.1 and I was trying to activate and setup VTX control using IRCTramp. It didn’t work.
Then I found this page , it looks like TRAMP is not supported in default firmware for Matek H743, why?
So I made custom build for H743 with TRAMP included which is a latest 4.4beta. Is it a stable version? How can I run v4.3.1 custom build?
Unfortunately, even with v4.4 the VTX control doesn’t work
I have configured all parameters l…
[ArduPilotPlanePorter]
I’ve just released plane 4.3.1 stable. This is a minor release with a few important fixes:
fixed build with gcc 11.3
fixed random number generator in lua core
scale VTOL angle P with airspeed in quadplane back-transition
added support for implementing AUX functions in lua scripts
fixed BMI085 accel scaling
fixed KSXT NMEA parsing affecting position resolution
fixed race condition in TECS control leading to ‘nod’ in forward transition
allow for expansion of notch filter…
opened 06:15PM - 03 Apr 22 UTC
closed 08:23AM - 13 Jul 22 UTC
## Feature request
**Is your feature request related to a problem? Please des… cribe.**
Not really. I want the VTX to run in Pit mode until I arm. When I am on the bench, the VTX gets really hot.
**Describe the solution you'd like**
Just like Smart Audio, I would like Ardupilot to support the IRC Tramp protocol to control VTX parameters like frequency and power level. An option to keep the VTX in pit mode until we arm.
I see more VTXes coming to support IRC tramp compared to Smart Audio.
Currently, betaflight and Inav support it. Being an Ardupilot pilot, I would like to have these features in my FPV drones having IRC Tramp VTX.
**Describe alternatives you've considered**
NA
**Platform**
[x] All
[ ] AntennaTracker
[ ] Copter
[ ] Plane
[ ] Rover
[ ] Submarine
**Additional context**
PR of IRC Tramp in betaflight: https://github.com/betaflight/betaflight/pull/2106
ArduPilot:master
← andyp1per:pr-tramp
opened 04:46PM - 18 Jun 22 UTC
Implement support for the IRC tramp protocol to allow control of VTX pitmode, po… wer and frequency.
This completes our support for VTX control as we already support SmartAudio and CRSF
https://github.com/ArduPilot/ardupilot/issues/20438
lida2003
(Daniel Li)
May 29, 2023, 1:29am
3
Add debug prints, and log(with/without VTX powered on) shows there is an issue.
tramp.log (6.3 KB)
TRAMP: send command ‘r’: 0
TRAMP: packet not complete 15/‘16’
TRAMP: packet complete 16/‘16’
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
TRAMP: state 0 receive_pos 1 char 0
// returns completed response code or 0
char AP_Tramp::receive_response()
{
if (port == nullptr) {
return 0;
}
// wait for complete packet
const uint16_t bytesNeeded = TRAMP_BUF_SIZE - receive_pos;
if (port->available() < bytesNeeded) {
debug("packet not complete %u/'%u'", unsigned(port->available()), unsigned(bytesNeeded));
return 0;
}
debug("packet complete %u/'%u'", unsigned(port->available()), unsigned(bytesNeeded));
// sanity check
if (bytesNeeded == 0) {
debug("packet sanity %u", unsigned(port->available()));
reset_receiver();
return 0;
}
for (uint16_t i = 0; i < bytesNeeded; i++) {
const int16_t b = port->read();
if (b < 0) {
debug("data sanity fail");
// uart claimed bytes available, but there were none
return 0;
}
const uint8_t c = uint8_t(b);
response_buffer[receive_pos++] = c;
debug("state %u receive_pos %u char %u", unsigned(receive_state), unsigned(receive_pos), unsigned(c));
switch (receive_state) {
case ReceiveState::S_WAIT_LEN: {
if (c == 0x0F) {
// Found header byte, advance to wait for code
receive_state = ReceiveState::S_WAIT_CODE;
} else {
// Unexpected header, reset state machine
reset_receiver();
}
break;
}
case ReceiveState::S_WAIT_CODE: {
if (c == 'r' || c == 'v' || c == 's') {
// Code is for response is one we're interested in, advance to data
receive_state = ReceiveState::S_DATA;
} else {
// Unexpected code, reset state machine
reset_receiver();
}
break;
}
case ReceiveState::S_DATA: {
if (receive_pos == TRAMP_BUF_SIZE) {
// Buffer is full, calculate checksum
const uint8_t cksum = checksum(response_buffer);
// Reset state machine ready for next response
reset_receiver();
if ((response_buffer[TRAMP_BUF_SIZE-2] == cksum) && (response_buffer[TRAMP_BUF_SIZE-1] == 0)) {
// Checksum is correct, process response
const char r = handle_response();
// Check response valid else keep on reading
if (r != 0) {
return r;
}
}
}
break;
}
default:
// Invalid state, reset state machine
reset_receiver();
break;
}
}
return 0;
}
Can you post your parameter file?
lida2003
(Daniel Li)
May 29, 2023, 9:48am
5
Sure. This is my params. The port is SERIAL3 for VTX.
I have a good news, which is to say it’s definitely hardware configuration issue. I’m still checking the difference, which setting makes this wrong.
h7dual.param (19.9 KB)
andyp1per
(Andyp1per)
May 29, 2023, 11:12am
6
Looking at the code we are not automatically setting half-duplex, so you do need to set this in your config
lida2003
(Daniel Li)
May 29, 2023, 12:27pm
7
@andyp1per Thanks for help. Now I got rootcause. Manufacture use one pinio as DC2DC 9V output switch, which I don’t know. Now turn on the swith 9V DC powered VTX, and then it works.
lida2003
(Daniel Li)
May 29, 2023, 9:08pm
8
Wel, in my case,l it seems that IRC Tramp can get something from serial, which might suggest root cause. So is there any way to tell these different cases?
FC VTX port initilization error, which might be serial port open failed // might be hardware configuration issue, contact manufacture.
No data coming back from VTX port // connection or port configuration issue
Feedback corrupted from VTX port // connection/configuration issue or VTX is NOT powered on.
Based on these cases [open failed]/[no data feedback]/[corrupted data feedback], is it possible to make a checklist for user to check?
alccrl
(Alfredo)
July 25, 2023, 8:14am
9
Hi.
On speedybeef4v3 I am going to test it (Ruibet vtx).
I enabled AP_TRAMP (define) in hwdef and I got a built bin file that seems to stay into 1 mbyte flash size (hex is 2.7 mbyte like stock firmware).
Have You idea if enabling tramp on 1 mbyte fc would cause troubles ?
I had a look at the code and tramp is enabled only for 2 mbyte boards.
Side effect of this question:
Is there a way to control by gui local on pc compilation options ?
The custom online build service does not show all available options.
Example:
I needed mav link on uart1 because my usb fc connector is broken, so I had to compile on my pc after canceling in hwdef default conf for uart1 for vtx. I moved vtx to uart3. Online build service does not propose hwdef default param modifications (I did not find a way).
Thanks in advance for help.
Alfredo
andyp1per
(Andyp1per)
July 25, 2023, 10:32am
10
Tramp is fine for 1Mb boards if you build it in. I wish I had made it the default
alccrl
(Alfredo)
July 25, 2023, 8:37pm
11
I tested Tramp on UART3, using same options (44/halfduplex) but
it does not work…nothing happens, power and channels are always the same (set by switch pushbutton on vtx).
Ruibet vtx goes up to 1.6 watt, so max should be 1600, not 1000.
Anyway it does work partiallly also on Inav 6.1.1, with power level 3 and 4, other levels do not work.
I wonder if serial speeds matters, it is 38400 by default on ardupilot uart3 speedybeef4v3…
Anybody knows ? …
Alfredo
andyp1per
(Andyp1per)
July 25, 2023, 9:29pm
12
Baud is set correctly automatically, what you configure is irrelevant.
lida2003
(Daniel Li)
July 30, 2023, 2:40am
13
@alccrl In order to configure analog VTX power level, there is quite a lot of works, please consult following links:
a) Document: Video Transmitter Support — Copter documentation
b) PowerLevel issue(Which might happen, then just change vtx power tables, please): Why analog VTX doesn't support 600mW power level? - #9 by lida2003
alccrl
(Alfredo)
July 30, 2023, 2:25pm
14
Thanks for the links.
I had a look.
I agree with @andyp1per that many VTX have no clear specification or good sw/hw implementation.
I made another trial with my RuiBet VTX and I noticed that sometime it shows a power change.
It seems that at least at poweron (with unlocked bit set in options) power level 800 is set.
Documentation of RuiBet declares pit mode available, but I played with pushbutton and what I got is one red flash, that is minimum power (five flashes is maximum). Not clear what exactly pit mode means for RuiBet, so far …
I am new to arducopter and today I got my first stable flight, after changing a few tuning parameters, found along arducopter discussions (yesterday my quad was vibrating after takeoff …, likely because PIDs were not suitable for a 5 inch quad), but I keep VTX power manually selected, Ruibet gets hot quite soon after poweron …
PS: at my first flight copter it overturned (motor order was not correct it was inav ordered) .
Alfredo