mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduPlane: Add conversion from ArduPlane geofence param to AC_Fence param
This commit is contained in:
parent
6f7ba3b037
commit
c316711351
@ -1331,6 +1331,13 @@ const AP_Param::ConversionInfo conversion_table[] = {
|
||||
{ Parameters::k_param_arming, 3, AP_PARAM_INT8, "ARMING_RUDDER" },
|
||||
{ Parameters::k_param_compass_enabled_deprecated, 0, AP_PARAM_INT8, "COMPASS_ENABLE" },
|
||||
{ Parameters::k_param_arming, 128, AP_PARAM_INT16, "ARMING_CHECK" },
|
||||
|
||||
{ Parameters::k_param_fence_minalt, 0, AP_PARAM_INT16, "FENCE_ALT_MIN"},
|
||||
{ Parameters::k_param_fence_maxalt, 0, AP_PARAM_INT16, "FENCE_ALT_MAX"},
|
||||
{ Parameters::k_param_fence_retalt, 0, AP_PARAM_INT16, "FENCE_RET_ALT"},
|
||||
{ Parameters::k_param_fence_action, 0, AP_PARAM_INT8, "FENCE_ACTION"},
|
||||
{ Parameters::k_param_fence_autoenable, 0, AP_PARAM_INT8, "FENCE_AUTOENABLE"},
|
||||
{ Parameters::k_param_fence_ret_rally, 0, AP_PARAM_INT8, "FENCE_RET_RALLY"},
|
||||
};
|
||||
|
||||
void Plane::load_parameters(void)
|
||||
|
@ -193,7 +193,7 @@ private:
|
||||
AP_Float _margin; // distance in meters that autopilot's should maintain from the fence to avoid a breach
|
||||
AP_Int8 _total; // number of polygon points saved in eeprom
|
||||
AP_Int8 _ret_rally; // return to fence return point or rally point/home
|
||||
AP_Float _ret_altitude; // return to this altitude
|
||||
AP_Int16 _ret_altitude; // return to this altitude
|
||||
|
||||
// backup fences
|
||||
float _alt_max_backup; // backup altitude upper limit in meters used to refire the breach if the vehicle continues to move further away
|
||||
|
Loading…
Reference in New Issue
Block a user