Pixhawk HIL frame rate problem (among many)

I’ve been using the SITL on Linux for a while, and I wanted to migrate to HIL. There have been lots of issues posted about this, but I think there are some underlying problems that I’ve yet to solve with HIL. I have solved a few that I’ve not seen posted, so I wanted to share those and perhaps someone at the same point as me can help solve the FPS issue.

My issue is that I have managed to get the HIL working, but the framerate is sub-Hertz (i.e. about 1 or two frames during each 3 second reporting interval, or effectively 0 FPS). This makes the simulation not only painful to watch, but the plane will eventually crash as there is such a lag between control and feedback. That I got this far was an exercise in frustration that I hope to save my fellow members from experiencing.

First, there is no separate firmware for HIL, despite a link on the “Install Firmware” tab. If you click on HIL Simulator>Plane, you will get a “URI” error. I recommend that you use AP 3.3.0 as the newer version (esp. 3.5) dont’ seem to work. To enable HIL, connect to the Pixhawk, go to the “Config/Tuning” tab and select the “Full Parameter List”. Search for “HIL” and you will see 12 hits. The most important are the “HIL_MODE” and GPS_TYPE parameters. Enter 1 for HIL_MODE and 7 for the GPS_TYPE (do both for good measure). A reboot is needed after writing parameters for it to take effect (unplug and plug back in).

Okay, now for some code hacking. The mavproxy_HIL.py file has several errors that will prevent the HIL from working. In the function check_sim_in(), the code needs to be modified as such:

[code]def check_sim_in(self):
’’‘check for FDM packets from runsim’’‘
try:
pkt = self.sim_in.recv(188 + 4) # was 178 + 4
except socket.error as e:
if not e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]:
raise
#print(“Socket error in check_sim_in”)
return
if len(pkt) != 188 + 4: # was 178 + 4
# wrong size, discard it
print(“wrong size %u” % len(pkt))
return
(timestamp, latitude, longitude, altitude, heading, v_north, v_east, v_down,
ax, ay, az,
phidot, thetadot, psidot,
roll, pitch, yaw,
vcas, check) = struct.unpack(’<Q17dI’, pkt) # was <17dI, added timestamp output variable Q (not sure if that is what the xtra 8 byes are)
(p, q, r) = self.convert_body_frame(radians(roll), radians(pitch), radians(phidot), radians(thetadot), radians(psidot))

    try:
        self.hil_state_msg = self.master.mav.hil_state_encode(int(time.time()*1e6),
                                                                    radians(roll),
                                                                    radians(pitch),
                                                                    radians(yaw),
                                                                    p,
                                                                    q,
                                                                    r,
                                                                    int(latitude*1.0e7),
                                                                    int(longitude*1.0e7),
                                                                    int(altitude*1.0e3),
                                                                    int(v_north*100),
                                                                    int(v_east*100),
                                                                    0,
                                                                    int(ax*1000/9.81),
                                                                    int(ay*1000/9.81),
                                                                    int(az*1000/9.81))
    except Exception:
        return[/code]

The major error is that the sim is returning 8 more bytes that the code expects, resulting in a buffer overflow error. Additionally, you have to assign that extra 8 bytes; I don’t know what the value is, but I’m guessing it is a timestamp (see runsim.py in Tools/autotest folder). Note that you have to change the struct unpack to also account for it (adding ‘Q’ for long long unsigned int).

At this point, you should be able to run sim_vehicle.sh with the -H option to get the HIL module to load in mavproxy and see your Pixhawk. Look for output like this in the mavproxy windows:

Auto-detected serial ports are: COM6 : PX4 FMU (COM6) : USB VID:PID=26AC:0011 SNR=0 Connecting to COM6 : PX4 FMU (COM6) : USB VID:PID=26AC:0011 SNR=0 Connect COM6 source_system=255 SRTMDownloader - server= firmware.diydrones.com, directory=/SRTM/. SRTMDownloader - server= firmware.diydrones.com, directory=/SRTM/. Loaded module console Loaded module HIL Loaded module graph module console already loaded Loaded module help Log Directory: Telemetry log: mav.tlog Waiting for heartbeat from COM6MAV> AUTO> Received 543 parameters Saved 543 parameters to mav.parm

The console should show all “green” (see image).

Now, I modified the runsim.py file to print out the frames processed between reports. Initially it is 15 FPS, but quickly goes to 0 ( or two frames per 3 second reporting period). I have tried to eliminate sections of the main_loop() function, but so far no luck.

I’m hoping someone has hit this before, or will get to this point and can help me figure this out. Thanks in advance for your help.

hi Todd,
The biggest core problem with HIL is the sensor lag. The EKF that ArduPilot uses is built assuming very low sensor lag, and the state estimation error you get with the size of lag you get with HIL makes the state estimation go way off. We do have some code in place that tries to cope with this by detecting differences in the attitude estimate between the HIL state and the AHRS state and resetting the AHRS state, but it isn’t enough.
To continue with HIL we’d need to implement AHRS_EKF_TYPE=10 in HIL mode. That is currently only available in SITL. That special “EKF” type bypasses the state estimation and instead uses the simulator state directly.
You may find you have a bit more luck by disabling the EKF completely, at least for fixed wing, by setting AHRS_EKF_TYPE=0. It still won’t be great though.
What is your use case for HIL btw? SITL is a much better simulation environment for most development tasks.
Cheers, Tridge

Hi Tridge,

Thanks for posting your reply. I didn’t find the AHRS_EKF_TYPE parameter in the version I was using (3.3.0), but I see it is in 3.5.0. Not to burden you with another issue, but I and another post recently have noticed that version 3.4 and higher seems to get stuck at the barometer initialization and a section that runs barometer.get_last_update() in system.cpp and displays “Waiting for first HIL_STATE message” over and over. In 3.3.0, I see a message “APM: barometer calibration complete” on the console:

[code]-> module load help
APM: Initialising APM…
APM: Waiting for first HIL_STATE message
online system 1
Mode INITIALISING
APM: ArduPlane V3.3.0 (6be0932d)
APM: PX4: d2c86797 NuttX: 1e53bc3d
APM: PX4v2 00240026 33345113 32353634
APM: Waiting for first HIL_STATE message
APM: Beginning INS calibration; do not move plane
Init Gyro**

APM: Calibrating barometer
APM: barometer calibration complete
APM: Initialising APM…
APM: Demo Servos!
APM: Demo Servos!
APM:

Ready to FLY.
Mode MANUAL
APM: init home
APM: gps alt: 58438
height -580
height 0
GPS lock at 584 meters
APM: ArduPlane V3.3.0 (6be0932d)
APM: PX4: d2c86797 NuttX: 1e53bc3d
APM: PX4v2 00240026 33345113 32353634[/code]

3.4.0 and higher never makes it past the “APM: Waiting for first HIL_STATE message”

1 Like

@brickster86 Did you figure this out at all? I’m trying to use HIL as well.
@tridge for what its worth, where I am I wanted to use HIL for practising flying manually under different conditions (I realize I could probably do this in stil and with other software) and verifying hardware components are all working well together as well making sure my companion computer was doing everything it needed to (I think for most people it’s a peace of mind thing too). Also we use another autopilot to prove out other algorithms on the companion computer with another autopilot system before flying and it seems much harder, logistically, to get approval for real test flights without proving it in HIL first (yeah I get SIL would probably be fine but it is a higher up decision).
Anyways, on a side note I love the system and use it with my personal plane, the culmination of years of hard work by so many dedicated people really is very apparent in the whole APM eco system.

I didn’t pursue it any further. I have code running on a Jetson that was more important to test and I successfully connected that to the SITL version of the AdruPlane and tested that. Ideally I would have liked to do the full up HIL, but the SITL works well enough that I am confident that the real Pixhawk will not be the issue when I test with the actual platform. I might re-look this after we do some initial testing.