diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index 44a47a80b3f003d9f108b25175d4c4873a40fe0e..cc621efbc9d41964f63d42c34a38894e352588fb 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -74,6 +74,7 @@
 #include <AP_BattMonitor.h> // Battery monitor library
 
 #include <AP_Arming.h>
+#include <AP_BoardConfig.h>
 
 // Pre-AP_HAL compatibility
 #include "compat.h"
@@ -127,6 +128,9 @@ static AP_Scheduler scheduler;
 // mapping between input channels
 static RCMapper rcmap;
 
+// board specific config
+static AP_BoardConfig BoardConfig;
+
 // primary control channels
 static RC_Channel *channel_roll;
 static RC_Channel *channel_pitch;
diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h
index 02be6531ce5d09f8e5f3b1f9e3078a1927e2f019..ca6fc18eefe46795da704b6d0101f6b4efa78cdf 100644
--- a/ArduPlane/Parameters.h
+++ b/ArduPlane/Parameters.h
@@ -100,6 +100,7 @@ public:
         k_param_hil_err_limit,
         k_param_sonar,
         k_param_log_bitmask,
+        k_param_BoardConfig,
 
         // 100: Arming parameters
         k_param_arming = 100,
diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde
index b3cd55019469fc69d72332b7575bfe51218a1cf7..bec1692287b8c010e5f9680b30763d21e6022d1b 100644
--- a/ArduPlane/Parameters.pde
+++ b/ArduPlane/Parameters.pde
@@ -938,6 +938,10 @@ const AP_Param::Info var_info[] PROGMEM = {
     // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
     GOBJECT(battery,                "BATT_",       AP_BattMonitor),
 
+    // @Group: BRD_
+    // @Path: ../libraries/AP_BoardConfig/AP_BoardConfig.cpp
+    GOBJECT(BoardConfig,            "BRD_",       AP_BoardConfig),
+
 #if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
     // @Group: SIM_
     // @Path: ../libraries/SITL/SITL.cpp
diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde
index 669ceade5d7664a36e844179f0805be62aee86bf..92b44f3f8a067904a482d4dfb2d1895dbf1a8b7d 100644
--- a/ArduPlane/system.pde
+++ b/ArduPlane/system.pde
@@ -92,6 +92,8 @@ static void init_ardupilot()
     //
     load_parameters();
 
+    BoardConfig.init();
+
     set_control_channels();
 
     // reset the uartA baud rate after parameter load