From bad1c879d9a71f0fca6b1deed8dd64da1707e94d Mon Sep 17 00:00:00 2001 From: Mathieu OTHACEHE Date: Wed, 18 Jan 2017 17:04:30 +0100 Subject: [PATCH] AP_HAL: Bebop & Disco: move default param file path In future Bebop & Disco releases, no ardupilot binary nor default param file will be provided. So move HAL_PARAM_DEFAULTS_PATH to ardupilot folder in RW memory. --- libraries/AP_HAL/board/linux.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/board/linux.h b/libraries/AP_HAL/board/linux.h index bd2845fb40..0932ce2db3 100644 --- a/libraries/AP_HAL/board/linux.h +++ b/libraries/AP_HAL/board/linux.h @@ -68,7 +68,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" +#define HAL_PARAM_DEFAULTS_PATH "/data/ftp/internal_000/ardupilot/bebop.parm" #define HAL_RCOUT_BEBOP_BLDC_I2C_BUS 1 #define HAL_RCOUT_BEBOP_BLDC_I2C_ADDR 0x08 /* focal length 3.6 um, 2x binning in each direction @@ -111,7 +111,7 @@ #define HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD 5000 #define HAL_RCOUT_DISCO_BLDC_I2C_BUS 1 #define HAL_RCOUT_DISCO_BLDC_I2C_ADDR 0x08 -#define HAL_PARAM_DEFAULTS_PATH "/etc/arduplane/disco.parm" +#define HAL_PARAM_DEFAULTS_PATH "/data/ftp/internal_000/ardupilot/disco.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))