Skip to content

[REPORT]Multi-Threaded Race Condition bug found in src/modules/navigator/navigator_main.cpp which cause drone can not PAUSE

High
bkueng published GHSA-x57h-c282-63hg Jan 25, 2024

Package

PX4-Autopilot (Pixhawk )

Affected versions

1.14.0

Patched versions

None

Description

Summary

Due to the lack of synchronization mechanism for vehicle_status variable,we identified a Race Condition vulnerability in the navigator_main.cpp and commander.cpp.This will result in the drone not being able to PAUSE when it executes a mission.

Details

When the drone is executing a mission and the user clicks PAUSE, the ground control station will send command::VEHICLE_CMD_DO_REPOSITION to the drone.

  1. In commander.cpp, the drone state is modified to NAVIGATION_STATE_AUTO_LOITER based on the received commands and the state is published.
    As stated in the code comment, it is designed not to require the navigator and command to receive/process data at the exact same time.

    case vehicle_command_s::VEHICLE_CMD_DO_REPOSITION: {
    // Just switch the flight mode here, the navigator takes care of
    // doing something sensible with the coordinates. Its designed
    // to not require navigator and command to receive / process
    // the data at the exact same time.

  2. In navigator_main.cpp, it will subscribe to the drone status and execute status->run()

    _navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]);

  3. Some of the parameters needed in status->run() are also calculated in navigator_main.cpp, but the conditions that trigger the execution of these calculated functions are not based on the drone status but on the received commander.Here calculate the break point to pause the mission.

    // All three set to NaN - pause vehicle
    rep->current.alt = get_global_position()->alt;
    if (_vstatus.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING
    && (get_position_setpoint_triplet()->current.type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF)) {
    calculate_breaking_stop(rep->current.lat, rep->current.lon, rep->current.yaw);

    Multi-Threaded Race Condition occurs here.When navigator_main.cpp receives the command from the GCS and calculates the braking point, commander.cpp hasn't yet modified the UAV's status according to the received command, so status->run(),doesn't publish the braking point as expected

    By the time commander.cpp finishes modifying the drone's status, navigator_main.cpp has executed to the next round and overwritten the brake point it just calculated, causing status->run() (status==loiter) to PUBLISH the wrong data

  4. Here overwrite the brake point.Because the Pause command is a compound command.
    Pause command==reposition to break point+change altitude
    I analyzed the QGC code, and when the user presses the PAUSE button, QGC sends twice the REPOSITION CMD to the drone.The second REPOSITION CMD triggers here and cause overwrite.

    } else if (PX4_ISFINITE(cmd.param7) || PX4_ISFINITE(cmd.param4)) {
    // Position is not changing, thus we keep the setpoint
    rep->current.lat = PX4_ISFINITE(curr->current.lat) ? curr->current.lat : get_global_position()->lat;
    rep->current.lon = PX4_ISFINITE(curr->current.lon) ? curr->current.lon : get_global_position()->lon;

Verification

I added some debug output to watch the drone's state change.

// Navigator.cpp

WHILE true DO
    IF vehicle_command_s EQUALS VEHICLE_CMD_DO_reposition THEN
        PX4_INFO("VEHICLE_CMD_DO_REPOSITION")
        IF user_intent EQUALS pause THEN
            PX4_INFO("calculate_breaking_stop point")
            calculate_breaking_stop(rep.current.lat, rep.current.lon, rep.current.yaw)
        END IF
    END IF

    PX4_INFO("Now vehicle_status=missison/loiter") //output drone status
    vehicle_status_s.Run() // If status EQUALS loiter, publish the break point
END WHILE


When the drone is executing a mission and the user clicks PAUSE,the console will output the following content:

...
INFO  [navigator] Now  vehicle_status=missison    //The drone is on a mission.
INFO  [navigator] Now  vehicle_status=missison
INFO  [navigator] Now  vehicle_status=missison
INFO  [navigator] VEHICLE_CMD_DO_REPOSITION     //Navigator_main.cpp accept CMD from GCS
INFO  [navigator] calculate_breaking_stop point             
INFO  [navigator] Now  vehicle_status=missison   //!!!!!!Beacuse of Race Condition,Drone is still in the previous status
INFO  [navigator] VEHICLE_CMD_DO_REPOSITION   //Pause command==reposition to break point+change altitude,so here's the VEHICLE_CMD_DO_REPOSITION twice
INFO  [navigator] Now vehicle_status=loiter  //Commander.cpp has modified status according to CMD
INFO  [navigator] Now vehicle_status=loiter
INFO  [navigator] Now vehicle_status=loiter
...

Temporary Patch

vehicle_command_s cmd{};
_vehicle_command_sub.copy(&cmd);
if(cmd.command == vehicle_command_s::VEHICLE_CMD_DO_REPOSITION){
_navigation_mode=&_loiter;
}

Add code before this line,assure the status is consistent with CMD before executing status->run()

_navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]);

Impact

  • Due to multiple threads accessing the 'vehicle_status' variable, one thread may experience simultaneous modifications by another thread, leading to a data race bug.
  • Drones are unable to PAUSE during missions, which can lead to collision crashes in the event of a hazardous encounter or incorrect mission settings.#22492
can.t.pause.mp4
  • After pause,the drone still keep move, but also in hold mode.So the user can not manually enter the hold to stop the aircraft, user need to switch to other modes then manually hold.
  • An attacker could use the vulnerability to keep the drone from executing certain commands.

Severity

High
8.2
/ 10

CVSS base metrics

Attack vector
Network
Attack complexity
Low
Privileges required
None
User interaction
Required
Scope
Changed
Confidentiality
None
Integrity
Low
Availability
High
CVSS:3.1/AV:N/AC:L/PR:N/UI:R/S:C/C:N/I:L/A:H

CVE ID

No known CVE

Weaknesses

Credits