Expose SYSTEMID mode for Plane [Experimental PR branch]

I am attempting to test the system identification mode for Plane from @bnsgeyer 's PR request. My issue has been exposing the SYSTEMID flight mode in SITL (The sysID- specific parameters I can access and change).

I have so far attempted to enable the AP_PLANE_SYSTEMID_ENABLED flag defined in ./Tools/scripts/build_options.py via the waf feature –enable flag:

./waf configure --board sitl --enable-PLANE_SYSTEMID

This compiles but does not show SYSTEMID in the available modes in MAVProxy, so I am most likely writing the feature-enable argument wrong/ using the incorrect parameter name.

Any advice will be greatly appreciated!

Juan,
Thanks for volunteering to test this feature. This is very different from how system ID is implemented in copter. In plane and quadplane, system ID is no longer a mode, but a feature that you use a Aux switch to enable in certain flight modes.

In SITL, you should just be able to compile my PR branch and run the plane SITL. once you have the simulator running, you’ll need to use one of the RC channels to set the aux switch function. I’ve been using the RC channel 6 and I’ve set the RC6_options to 184. Next, you’ll have to set up the SID_AXIS parameter in order to reveal the rest of the parameters for the system ID feature. Here are the Sid axis value definitions for plane.

20 - Input Roll
21 - Input Pitch
22 - input Yaw
23 - Mixer Roll
24 - Mixer Pitch
25 - Mixer Yaw
26 - Mixer Thrust

Try setting 20 initially and then reload the parameters. Remaining parameters for the system ID feature should now be visible. You could use the default or set the parameters to your liking.

Here is how you would use it in flight. Takeoff and get the aircraft to a safe altitude. I would suggest using either FBWA or loiter flight modes. In the simulator, the long system ID chirps will not be so much of an issue with the aircraft going too far away from the takeoff point. However, in real life, you won’t want the aircraft to get too far from you while it’s conducting the system ID chirp and you don’t want to make control inputs as it’s conducting the chirp to keep it close to you because that will affect the quality of the data. So I would recommend either using the FBWA flight mode and keeping a slight roll angle so it makes a large circle or using loiter mode. For the loiter flight mode, I would suggest setting a 100 to 150 m radius so as to keep the roll attitude below 15°. This will minimize the effect of a non zero roll attitude system identification. You will initiate the system ID chirp using the switch with the system ID aux function. After initiating the chirp, wait the time you set for the chirp length and then switch the feature off with the aux switch. During the system ID chirps you will want to keep airspeed and altitude constant or for pitch sweeps where altitude and airspeed are affected by the chirp, just be sure the altitude or airspeed average remains constant while it varies due to the sweep. I would keep the throttle stationary and just adjust the pitch attitude if necessary to maintain the average values.

Hope this helps

I will try to get a 4.6 version of this in a branch so you can build the firmware for your board and test in real life.

2 Likes

Thanks very much @bnsgeyer,

I have tested FW_MIX_ROLL and FW_MIX_PITCH in SITL for plane-elevon in loiter mode with success. Below are the extracted SISO time-domain pairs of interest. I have observed the following things:

  1. The chirp record length is (SID_T_REC / SITL speedup), which I am unsure if that is the expected behaviour
  2. The SID_MAGNITUDE parameter is described to be [0, 1] for the mixer input axes, however, this results in very small output responses. Using dimensional values (as the default value) for the chirp magnitude gives expected output response magnitudes
  3. Can you confirm the log output in SIDD for Gx,Gy,Gz,Ax,Ay,Az are in degrees? As you can see from the normal load factor (-Az / gravity) and pitch rate (Gy) time responses, the magnitudes are very large. For the roll rate (Gx), however, the response magnitude appears correct.

Juan



2 Likes

Juan, it is great to see that you got it working in SITL.

Gx, Gy, and Gz are given in deg/s. Ax,Ay, and Az are given in m/s/s.

I will check into this. I may have applied a conversion improperly.

Thanks. I will fix this. I find it odd that the fixed wing rate controller output is so different than vtol

I will make the updates and let you know.

Hi Bill,

I have re-run FW_MIX_PITCH sweeps for the generic plane and plane-elevon models again SITL (see below). I am no longer seeing the very large magnitudes in Gy/ Az, so not sure why that occurred the first time around.

I am curious about the amplified response around 10 seconds followed by large attenuation for higher frequencies. Would that be to do with the controller closed-loop response? Although I was under the impression that using the mixer inputs would be as close to ‘bare-airframe’ dynamics as you could get. Please correct me if I’m mistaken in my thinking.

Thanks,

Juan


Plane:

Plane-elevon:

Hi Juan, I had looked at my results as well and didn’t see anything out of the ordinary.

Yes, I believe you are correct. it is due to the controller responding to the artificial inputs being made at the mixer and sees them as disturbances. You can use this frequency sweep for determining bare airframe dynamics but you can also use the frequency sweep of the pilot input. You would just determine the frequency response of the aircraft response to the mixer input.

1 Like