[[searchwing-px4-analyse]]

This is an old revision of the document!


Analysis of the PX4-Firmware

The most relevant parts for making an adaptation with the goal of integrating an altered landing approach into the PX4-Firmware seem to be the navigator and the position-controller. To enable an easy exchange about the findings source code analysis should be based on the version 1.8.0 of the PX4 firmware (PX4FW-1.8.0).

An analysis of the navigator can be found here (in german).

An analysis of the position controller can be found here

Follow-me mode and offboard mode are not supported for fixedwing in the current PX4 firmware according to the documentation.

The navigator controls the attitude of the plane by publishing a position setpoint triplet (ORB position_setpoint_triplet) . Through this mechanism the position controller further down the pipeline receives its input. The triplet contains the previous, the current and the next waypoint.

The autonomous flight mode of the fixedwing position controller only considers a maximum of two waypoints at a time. Those are the previous and current waypoint of the position setpoint triplet (ORB position_setpoint_triplet).

A position setpoint for fixedwing describes the location of a waypoint, the type of waypoint, loiter radius and loiter direction (clockwise or counter-clockwise). Furthermore a non binding cruising speed and cruising throttle can be contained. Takeoff waypoints can contain a minimum pitch angle. Not all information is used for all waypoint types.

The fixedwing position controller supports the following types:

uint8 SETPOINT_TYPE_POSITION=0	# position setpoint
uint8 SETPOINT_TYPE_LOITER=2	# loiter setpoint
uint8 SETPOINT_TYPE_TAKEOFF=3	# takeoff setpoint
uint8 SETPOINT_TYPE_LAND=4	# land setpoint, altitude must be ignored, descend until landing
uint8 SETPOINT_TYPE_IDLE=5	# do nothing, switch off motors or keep at idle speed (MC)

The mavlink command MAV_CMD_DO_REPOSITION is hardcoded to command a loiter type setpoint with the commanded coordinates in the navigator. The current global position is used as a previous waypoint. However, the previous waypoint is ignored for loiter type setpoints in the calculation of the fixedwing position controller. MAV_CMD_DO_REPOSITION is the way QGroundControl uses to implement a goto command for the PX4.

The position controller influences the behavior of the navigator through the values of fixedwing position control status (ORB fw_pos_ctrl_status) which are passed up the pipeline.

To determine if a navigation waypoint is reached the acceptance radius stored in the mission item is overruled by the turn distance of the fixedwing position control status if it is larger and up to date. The parameter for the Acceptance Radius (NAV_ACC_RAD) is not used in fixed wing.
The turn distance in the fixedwing position control status is taken out of the l1_control_library which uses a value of 4.77 * groundspeed (e.g. 95.4 m for 20 m/s) with the default parameter set. Therefore a waypoint can be declared reached in a distance much larger than the distance configured in either the waypoint itself or the parameter (NAV_ACC_RAD).

The mission state machine of the navigator continuously checks if the current mission item is reached and advances automatically to the next mission items once the current waypoint is considered reached. It copies the current position setpoint to become the previous position setpoint. The next position item after the currently reached point becomes the new current position setpoint and the next position item after that becomes the next position setpoint.

In case actual position waypoints are used (and not loiter waypoints) the position controller will use the logic documented in “A New Nonlinear Guidance Logic for Trajectory Tracking” (S. Park, J. Deyst, and J. P. How, Aug 2004). The L1 distance defined in the default parameter only allows an offset correction of about 70% within a 100 meter distance for a ground speed of 20 m/s.

The PX4 firmware only supports one mission at a time. If the mission needs to be updated a full clear is required. Afterwards the mission needs to be uploaded using multiple mavlink messages and roundtrip times (see Mission Protocol). The behavior of the PX4 controlled plane during this phase still needs to be examined.

  • How to command flying to a moving location?
  • What happens during upload of missions?
  • Is an increased responsiveness of L1 position control during approach required?
  • A predicted route of the ship could be used to generate a trajectory that passes though all points the landing spot could be located at. This seems possible as no sudden deviation of the predicted route is to be expected for a ship.
  • searchwing-px4-analyse.1540762398.txt.gz
  • Last modified: 2018/10/28 22:33
  • by natwati