Open nilay994 opened 3 years ago
I have tried to answer some of your questions below, but I am not sure how helpful it is. Just ask for clarification if anything is unclear.
msp_override
you need #define USE_RX_MSP_OVERRIDE
as in https://github.com/betaflight/betaflight/blob/master/src/main/target/common_pre.h#L401 this is defined by default for FCs with enough flash. Other than I did not change any build settings, but some changes in the Betaflight cli is required. I think I have mentioned them in the github issue you linked.serial_rx_update_rate
so that may improve performance.I do not think this is possible with unmodified Betaflight, but it should be possible to patch betaflight into sending IMU data with MSP continuously. I don't think it will break anything? Note that we did not use IMU data and the telemetry we requested was low-freq and mostly for debugging-purposes. Your solution with using mavlink (on a seperate UART channel?) may be a better idea.
I am absolutely no Betaflight guru so I cannot really help you with failsafe settings. However it should not be a too big of a problem, in the Betaflight configurator you will find a tab with failsafe settings where you can tell the drone to disarm when entering failsafe. When using set msp_override_channels 15
the companion computer will only be able to override rpyt and has no control over arming. This means that you can always disarm while in offboard mode. While we were testing we found it quite simple to take over control by simply switching from offboard to stabilized mode.
I would recommend simply hooking the drone up to the configurator and trying to send various commands through MSP and radio and check that everything seems to work as expected and when it does you can try some flying.
@birktj , thank you so much, I will report metrics / results back here. All of your answers are helpful to us at the moment :) Thank you for your elaborate and quick revert.
Apologies for the delay, I was doing this in my free time. Hope you weren't waiting on our reply. What we've found until now:
seems like on inav, when the companion computer stops sending control commands, there is some sort of timeout facilitating an automatic switch to manual rc mode. That feature seems to be absent on betaflight and the motors spin constantly according to the last updated command sent by the companion pc (pilot should always be ready to override in case of any segfault on companion pc end).
this is our diff that gets the MSP companion pc feature work for us: No src changes required to the betaflight firmware. But the latest devel build (maybe nightly). Apart from that firmware, just this diff:
# diff
batch start
board_name KAKUTEF7
feature -RX_SERIAL feature -OSD feature RX_MSP
serial 0 1 115200 57600 0 115200
map TAER1234
aux 0 0 0 1700 2100 0 0 aux 1 1 0 900 2100 0 0 aux 2 27 2 1700 2100 0 0 aux 3 26 0 900 2100 0 0 aux 4 50 1 1700 2100 0 0
rxfail 0 s 1500 rxfail 1 s 1500 rxfail 2 s 1500 rxfail 3 s 875 rxfail 6 h
set acc_calibration = -68,-92,-53,1 set mag_hardware = NONE set msp_override_channels_mask = 31 set blackbox_sample_rate = 1/1 set blackbox_mode = ALWAYS set motor_pwm_protocol = DSHOT300 set serial_update_rate_hz = 2000 set small_angle = 180 set debug_mode = RC_INTERPOLATION
profile 0
rateprofile 1
batch end
3. I used your msp ros example on the companion pc for a very rudimentary test:
https://github.com/AscendNTNU/msp_flightcontroller_interface
I ran it on a default linux kernel without any real time patch:
`Linux xps15 5.4.0-56-generic #62-Ubuntu SMP Mon Nov 23 19:20:19 UTC 2020 x86_64 x86_64 x86_64 GNU/Linux`
4. these were the results obtained from the betaflight blackbox logged on the sdcard:
![image](https://user-images.githubusercontent.com/22093651/101648826-82afb700-3a3a-11eb-9479-5bee4c7f5306.png)
row 1, col1 = timestamp of each sample logged
row 1, col2 = Delta t between each sample logged
row2, col1 = Checking how consistent the control commands are when MSP commands are sent via UART at 50Hz (jitter and latency)
row2, col2 = mean of the confidence interval of logger (1/Delta_t) equal 8000Hz which is the default logging frequency..
Most of these plots might not be useful since they just say apples = apples. It was just something that bothered me, so I ran the test.
## setup of expt:
![image](https://user-images.githubusercontent.com/22093651/101648859-8ba08880-3a3a-11eb-8861-88b8e4373ee3.png)
Thank you for your code and contribution in this area of MSP! Given the dearth of documentation resources, I can imagine that contributing to this part wouldn't have been easy.
1
We've been building an autonomous drone and were in search of a flight-computer firmware that could listen to:
so to be able to send rate commands to the flight-computer from a companion computer but still override in case there is lets say a segfault on the companion computer. In other words, takeover (or even disarm) when the uart commands do something stupid.
So far, I've been able to run your solution successfully which sends MSP commands to betaflight from a UART port of an nvidia board. I could also see the change in RC commands on the configurator. The github discussion that you contributed to also mentioned that the state machine switches to failsafe - which was a critical feature. However, does it
Question:
I guess inav requires a flag while compiling. Also, here it is recommended to increase the
serial_rx_update_rate
to 2000 Hz. Do you change any settings while building the firmware to be able to fly with MSP?Do you have any observations / metrics on consistency of these MSP commands sent over UART? On a 50Hz update rate, could there be times that the flight-computer takes twice as much as time to update the rate commands because the uart buffers were not in sync?
2
Addition to receiving these commands, there was also a requirement of sending out high frequency IMU based telemetry from the flight-computer. After some effort I could get some nice 50 Hz mavlink telemetry from the UART ports of the flight computer. (timestamped at the receiving end i.e. pc)
Question: Can MSP be a one direction protocol, in which there is no request supposed to be made for receiving telemetry? In other words, can a TX pin of a flight-computer just keep giving telemetry information without the PC-side requesting for it? I read that this is not possible.
3
While having the above rx-tx features, we were aiming for minimal alteration of the betaflight / inav firmware. Thanks to your contribution, this does look possible! For now, I'm trying to understand more about
failsafe
,msp_override
andmsp_override_channels_mask
before putting any props on!Thank you for reading the long message, please don't feel obliged to revert back in case you are busy!! :smile: