Compass: always default devid to zero

This commit is contained in:
Randy Mackay 2014-09-23 20:35:18 +09:00
parent d4cfb432ca
commit c2c5807ec7
2 changed files with 3 additions and 22 deletions

View File

@ -120,13 +120,13 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
// @DisplayName: Compass device id
// @Description: Compass device id. Automatically detected, do not set manually
// @User: Advanced
AP_GROUPINFO("DEV_ID", 15, Compass, _dev_id[0], COMPASS_EXPECTED_DEV_ID),
AP_GROUPINFO("DEV_ID", 15, Compass, _dev_id[0], 0),
// @Param: DEV_ID2
// @DisplayName: Compass2 device id
// @Description: Second compass's device id. Automatically detected, do not set manually
// @User: Advanced
AP_GROUPINFO("DEV_ID2", 16, Compass, _dev_id[1], COMPASS_EXPECTED_DEV_ID2),
AP_GROUPINFO("DEV_ID2", 16, Compass, _dev_id[1], 0),
#endif
#if COMPASS_MAX_INSTANCES > 2
@ -134,7 +134,7 @@ const AP_Param::GroupInfo Compass::var_info[] PROGMEM = {
// @DisplayName: Compass3 device id
// @Description: Third compass's device id. Automatically detected, do not set manually
// @User: Advanced
AP_GROUPINFO("DEV_ID3", 17, Compass, _dev_id[2], COMPASS_EXPECTED_DEV_ID3),
AP_GROUPINFO("DEV_ID3", 17, Compass, _dev_id[2], 0),
#endif
AP_GROUPEND

View File

@ -52,25 +52,6 @@
#define COMPASS_MAX_INSTANCES 1
#endif
// default compass device ids for each board type to most common set-up to reduce eeprom usage
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
# define COMPASS_EXPECTED_DEV_ID 73225 // external hmc5883
# define COMPASS_EXPECTED_DEV_ID2 -1 // internal ldm303d
# define COMPASS_EXPECTED_DEV_ID3 0
#elif CONFIG_HAL_BOARD == HAL_BOARD_LINUX
# define COMPASS_EXPECTED_DEV_ID 0
# define COMPASS_EXPECTED_DEV_ID2 0
# define COMPASS_EXPECTED_DEV_ID3 0
#elif CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
# define COMPASS_EXPECTED_DEV_ID 0
# define COMPASS_EXPECTED_DEV_ID2 0
# define COMPASS_EXPECTED_DEV_ID3 0
#else
# define COMPASS_EXPECTED_DEV_ID 0
# define COMPASS_EXPECTED_DEV_ID2 0
# define COMPASS_EXPECTED_DEV_ID3 0
#endif
class Compass
{
public: