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.
This commit is contained in:
Mathieu OTHACEHE 2017-01-18 17:04:30 +01:00 committed by Francisco Ferreira
parent fdb2a9c99b
commit bad1c879d9
1 changed files with 2 additions and 2 deletions

View File

@ -68,7 +68,7 @@
#define HAL_FLOW_PX4_MAX_FLOW_PIXEL 4 #define HAL_FLOW_PX4_MAX_FLOW_PIXEL 4
#define HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD 30 #define HAL_FLOW_PX4_BOTTOM_FLOW_FEATURE_THRESHOLD 30
#define HAL_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD 5000 #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_BUS 1
#define HAL_RCOUT_BEBOP_BLDC_I2C_ADDR 0x08 #define HAL_RCOUT_BEBOP_BLDC_I2C_ADDR 0x08
/* focal length 3.6 um, 2x binning in each direction /* 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_FLOW_PX4_BOTTOM_FLOW_VALUE_THRESHOLD 5000
#define HAL_RCOUT_DISCO_BLDC_I2C_BUS 1 #define HAL_RCOUT_DISCO_BLDC_I2C_BUS 1
#define HAL_RCOUT_DISCO_BLDC_I2C_ADDR 0x08 #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 /* focal length 3.6 um, 2x binning in each direction
* 240x240 crop rescaled to 64x64 */ * 240x240 crop rescaled to 64x64 */
#define HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX (2.5 / (3.6 * 2.0 * 240 / 64)) #define HAL_FLOW_PX4_FOCAL_LENGTH_MILLIPX (2.5 / (3.6 * 2.0 * 240 / 64))