MSP protocol support

Hi Serge, from the wiki

  1. If OF.flowX is larger or smaller than OF.bodyX , then it can be adjusted by changing the FLOW_FXSCALER parameter
  2. IF OF.bodyX is uncorrelated or opposite sign to IMU.GyrX , the FLOW_ORIENT_YAW parameter is probably set incorrectly or you do not have the flow sensor pointing downwards

OF.bodyX is correlated and not opposite sign to IMU.GyrX`, the problem with OF.flowX, and changes parameters FLOW_ORINET_YAW and FLOW_FXSCALER , don’t change graph for OF.flowX, only OF.bodyX. As a result, when you turn on loiter, the copter sharply flies away

Alex, I add some changes in code (file AP_OpticalFlow_MSP.cpp)
// copy flow rates to state structure
state.flowRate = { ((float)flow_sum.x / count) * flow_scale_factor_x * dt,
((float)flow_sum.y / count) * flow_scale_factor_y * dt };
///////////////////////////////////////my string //////////////////////////////////////////////
state.flowRate *= -1;

The graphs have become synchronous, and the copter perfectly holds its position in Loiter mode. Perhaps this is somehow related to the mutual location of gyro and OF sensor. But the configuration parameters failed to achieve the result. Only by changing the sign in the program code

Thanks Serge, et me check the originale code for another way to achieve the same (if possible)

I checked the code

    // copy flow rates to state structure
    state.flowRate = { ((float)flow_sum.x / count) * flow_scale_factor_x * dt,
                       ((float)flow_sum.y / count) * flow_scale_factor_y * dt };

state.flowRate is 2D vector, by doing flowRate *= -1 you invert BOTH x and y components
just like the sensor was YAW rotated by 180 degrees, did you try setting FLOW_ORIENT_YAW to +/-18000, the library then applies the compensation with the line

    _applyYaw(state.flowRate);

which would invert the vector provided you did set 180 deg yaw rotation.

OR simply rotate it physically by 180 deg

Yes, I try FLOW_ORIENT_YAW, to +/-18000 but it only affected on parameter OF.body. Why so, I don’t understand yet.
I really have gyro turned 180 (GY-91 module), I will try to turn OF it is not soldered on the Board

1 Like

I may have missed it earlier in the thread. If I want to compile for a 1mb board, what settings should I disable and where do I do that? I need to modify the hardware .dat for the kakute mini which I’ve done before, but I haven’t ever changed compilation options, just compiled with modified .dats.

Also, does this allow changing of PID values through the goggles or not?

Thanks!

Hello Alex, can i request a build for Hoylbro Kakute F4 v2 flight controller ? Thanks

to compile your own version you need to checkout the release tag msp_v0.7, and change the ardupilot/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat files by adding as last line define
HAL_MSP_ENABLED 1

# reduce max size of embedded params for apj_tool.py
define AP_PARAM_MAX_EMBEDDED_PARAM 1024

# we are low on flash on this board
define HAL_MINIMIZE_FEATURES 1
define HAL_WITH_DSP 1
# enable MSP support
define HAL_MSP_ENABLED 1

No it does not, Betaflight PIDS are normalized 8bits values 0-255 whereas Ardupilot PIDS are floats

Hi, I added the build for the KakuteF4 target

Awesome. Thanks for the info, and for writing the library!

Hi Alex,

is there a possibility to switch to the statistic screen of ArduPilot? (consumption, flight distance etc.)

Hi Reinhard,
no, unfortunately we have no control on which osd items the DJI goggles render and ATM they do not support MSP stats display.
The way msp OSD works is like minim-osd, we do not have direct access to the screen and we cannot “draw” on it but rather we provide raw MSP telemetry to the OSD engine which renders it autonomously (i.e. we send a 200° for home direction and the OSD renders it as a rotating arrow)

Hi Alex,

couldn’t you use the MSP_OSD_MSG text area for this? After a disarm or via a switch, display the statistics data in a rolling manner? What do you think?

ahn ok, yes it could work, hardest part is switching context in a smart way

This could go through the normal screen switch. Screen 1 = normal OSD, Screen 2 = rolling statistics data.

This would then work the same way as with the analog OSD.

you mean inherit the context switch of the built in OSD?

Yes, like the integrated OSD.

…we could actually switch all supported widgets in a “stats” mode and display min or max values when the stats screen is selected, mhmm, bad idea it’s a lot of coding :slight_smile:

It doesn’t have to be… :smile: But it would be nice if you could display the statistics at the end of the flight as usual. I just don’t have this information to optimize the equipment or to set personal records :wink:.