microsoft / AirSim

Open source simulator for autonomous vehicles built on Unreal Engine / Unity, from Microsoft AI & Research
https://microsoft.github.io/AirSim/
Other
16.39k stars 4.57k forks source link

HITL with last versions of the PX4 #705

Closed avklab closed 4 years ago

avklab commented 6 years ago

It may be useful information for community. The last versions of the PX4 firmware (1.7) wok correctly in HITL mode with simulators which don't send the ground truth MAVLink messages (mavlink_msg_hil_state_quaternion). Receiving hil_state_quaternion from AirSim makes the autopilot malfunctioning. In addition in my environment by some reason the AirSim sends incorrect accelerometer data in the mavlink_msg_hil_sensor. No gravity component in zacc when on the ground (see the screenshot from QGroundControl), so permanent 'Freefall/Landing detected' messages go from the controller. But HITL works fine in X-Plane (with my PX4 MAVLink plugin) through MavLinkTest and in jMAVSim. mavlinkimu

sytelus commented 6 years ago

AirSim doesn't use HIL_STATE_QUATERNION at all, it uses HIL_SENSOR message.

AirSim uses jMavSim as official simulator implementation to test PX4 and so it uses same messages that jMavSim uses: (1) to send sensor state, use HIL_SENSOR (2) to get actuator controls use either HIL_ACTUATOR_CONTROLS or HIL_CONTROLS.

You are correct about z acceleration where we subtract g from ground truth acceleration. This is again same as how jMavSim has been doing and how sensor drivers behave.

I'm not sure if something has changed from PX4 side but may be they didn't updated jMavSim? Or may be you are seeing something else? Please let us know if you find any other information that conflicts with above... It might be great to look in to plugin's code if its open source to see what PX4 really expects.

This might interest @lovettchris as well who is our PX4 expert in the house.

avklab commented 6 years ago

O.K. with hil quaternion. So probably the only problem is incorrect accelerometer data. The physical accelerometer can not distinguish gravity and kinematic acceleration, they must be combined by the simulator. The jMavSim does this in SimpleSensors.java, line 48, so the zacc is approximately -9.8 on the ground (kinematic acceleration is zero, gravity is normal). I see that AirSim tries to do the same in ImuSimple.hpp line 54 but without correct result (zacc is zero, i.e. weightlessness/free fall).

The last PX4 has corrected the bug in commander module which prevented arming in HITL mode. It also enables to switch any airframe into HITL mode by setting the SYS_HITL parameter in the QGroundControl.

I use the following code to send data from X-Plane to PX4 (the acceleration data gback, gright and gup from the X-Plane already include the gravity):

    /* Sensors */
    rotatemag(0.17f, 0, 0.49f, &xmag, &ymag, &zmag);
    xacc = -XPLMGetDataf(ggback)*ONE_G;
    yacc = XPLMGetDataf(ggright)*ONE_G;
    zacc = -XPLMGetDataf(ggup)*ONE_G;
    Ppx = XPLMGetDataf(gP);
    Qpx = XPLMGetDataf(gQ);
    Rpx = XPLMGetDataf(gR);
    baraltpx = XPLMGetDataf(gbaralt)*0.3048f;
    presspx = XPLMGetDataf(gpressure)*33.8639f;
    timeus = getTime_us();
    memset(buf, 0, BUFFER_LENGTH);
    mavlink_msg_hil_sensor_pack(1, 200, &msg, timeus, xacc + dist(eng)*1e-4, yacc + dist(eng)*1e-4, zacc + dist(eng)*1e-4,
        Ppx + dist(eng)*1e-5, Qpx + dist(eng)*1e-5, Rpx + dist(eng)*1e-5, xmag + dist(eng)*1e-4, ymag + dist(eng)*1e-4,
        zmag + dist(eng)*1e-4, presspx, 0, baraltpx + dist(eng)*1e-2, 20, 1 << 31);
    len = mavlink_msg_to_send_buffer(buf, &msg);
    link->send((char *)buf, len);
    /* GPS */
    latitudepx = XPLMGetDataf(glatitude)*1e7f;
    longitudepx = XPLMGetDataf(glongitude)*1e7f;
    altitudepx = XPLMGetDataf(galtitude) * 1000;
    groundsppx = XPLMGetDataf(ggroundspeed) * 100;
    vn = -XPLMGetDataf(gvz) * 100;
    ve = XPLMGetDataf(gvx) * 100;
    vd = -XPLMGetDataf(gVertV) * 100;
    if (timeus >= nextgps) {
        nextgps = timeus + 100000;
        memset(buf, 0, BUFFER_LENGTH);
        mavlink_msg_hil_gps_pack(1, 200, &msg, timeus, 3, latitudepx, longitudepx,
            altitudepx, 100, 100, groundsppx, vn, ve, vd, XPLMGetDataf(gcog) * 100, 10);
        len = mavlink_msg_to_send_buffer(buf, &msg);
        link->send((char *)buf, len);
    }
sytelus commented 6 years ago

Thanks for more details. I'm planning to wrap up current work and look in to this around couple of weeks. Meanwhile if you want to dig in the code, you are welcome!

sytelus commented 6 years ago

Looks like I won't be able to get to PX4 related issues for a while. If you can, please submit the pull request for any changes you have so far.

lovettchris commented 5 years ago

I found a problem with PX4 1.8.2, they removed a module that is needed for HITL mode to work, namely, "pwm_sim_out" and so I built a new version of the v1.8.2 with this module included and takeoff and normally flying works again. See OneDrive download.