You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
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.
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.
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.
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
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.
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
...
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.
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.
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.
PX4-Autopilot/src/modules/commander/Commander.cpp
Lines 726 to 731 in 24cee81
In navigator_main.cpp, it will subscribe to the drone status and execute status->run()
PX4-Autopilot/src/modules/navigator/navigator_main.cpp
Line 881 in 24cee81
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.
PX4-Autopilot/src/modules/navigator/navigator_main.cpp
Lines 345 to 351 in 24cee81
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
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.
PX4-Autopilot/src/modules/navigator/navigator_main.cpp
Lines 331 to 334 in f38fe24
Verification
I added some debug output to watch the drone's state change.
When the drone is executing a mission and the user clicks PAUSE,the console will output the following content:
Temporary Patch
Add code before this line,assure the status is consistent with CMD before executing status->run()
PX4-Autopilot/src/modules/navigator/navigator_main.cpp
Line 881 in 24cee81
Impact
can.t.pause.mp4