From 0ffba07ec8b7bab8df4f61435540ed4491c672a9 Mon Sep 17 00:00:00 2001 From: Julien BERAUD Date: Tue, 22 Dec 2015 17:06:39 +0100 Subject: [PATCH] AP_HAL: Set default params for Bebop --- libraries/AP_HAL/AP_HAL_Boards.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index d24ebb8847..aba46ca6f7 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -229,6 +229,7 @@ #define HAL_FLOW_PX4_MAX_FLOW_PIXEL 4 #define HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD 30 #define HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD 5000 +#define HAL_PARAM_DEFAULTS_PATH "/etc/arducopter/bebop.parm" /* focal length 3.6 um, 2x binning in each direction * 240x240 crop rescaled to 64x64 */ #define HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX (2.5 / (3.6 * 2.0 * 240 / 64))