Firmware
Functions
precland_params.c File Reference

Parameters for precision landing. More...

Functions

 PARAM_DEFINE_FLOAT (PLD_BTOUT, 5.0f)
 Landing Target Timeout. More...
 
 PARAM_DEFINE_FLOAT (PLD_HACC_RAD, 0.2f)
 Horizontal acceptance radius. More...
 
 PARAM_DEFINE_FLOAT (PLD_FAPPR_ALT, 0.1f)
 Final approach altitude. More...
 
 PARAM_DEFINE_FLOAT (PLD_SRCH_ALT, 10.0f)
 Search altitude. More...
 
 PARAM_DEFINE_FLOAT (PLD_SRCH_TOUT, 10.0f)
 Search timeout. More...
 
 PARAM_DEFINE_INT32 (PLD_MAX_SRCH, 3)
 Maximum number of search attempts. More...
 

Detailed Description

Parameters for precision landing.

Author
Nicolas de Palezieux (Sunflower Labs) ndepa.nosp@m.l@gm.nosp@m.ail.c.nosp@m.om

Function Documentation

§ PARAM_DEFINE_FLOAT() [1/5]

PARAM_DEFINE_FLOAT ( PLD_BTOUT  ,
5.  0f 
)

Landing Target Timeout.

Time after which the landing target is considered lost without any new measurements.

s 0.0 50 1 0.5 Precision Land

§ PARAM_DEFINE_FLOAT() [2/5]

PARAM_DEFINE_FLOAT ( PLD_HACC_RAD  ,
0.  2f 
)

Horizontal acceptance radius.

Start descending if closer above landing target than this.

m 0.0 10 2 0.1 Precision Land

§ PARAM_DEFINE_FLOAT() [3/5]

PARAM_DEFINE_FLOAT ( PLD_FAPPR_ALT  ,
0.  1f 
)

Final approach altitude.

Allow final approach (without horizontal positioning) if losing landing target closer than this to the ground.

m 0.0 10 2 0.1 Precision Land

§ PARAM_DEFINE_FLOAT() [4/5]

PARAM_DEFINE_FLOAT ( PLD_SRCH_ALT  ,
10.  0f 
)

Search altitude.

Altitude above home to which to climb when searching for the landing target.

m 0.0 100 1 0.1 Precision Land

§ PARAM_DEFINE_FLOAT() [5/5]

PARAM_DEFINE_FLOAT ( PLD_SRCH_TOUT  ,
10.  0f 
)

Search timeout.

Time allowed to search for the landing target before falling back to normal landing.

s 0.0 100 1 0.1 Precision Land

§ PARAM_DEFINE_INT32()

PARAM_DEFINE_INT32 ( PLD_MAX_SRCH  ,
 
)

Maximum number of search attempts.

Maximum number of times to seach for the landing target if it is lost during the precision landing.

0 100 Precision Land