diff --git a/APMrover2/APMrover2.pde b/APMrover2/APMrover2.pde
index f091215690c663e55e878676e803dcfb9bb61264..62364fcd2d14c86e4c7feac2752cbc99c1bf7d95 100644
--- a/APMrover2/APMrover2.pde
+++ b/APMrover2/APMrover2.pde
@@ -92,6 +92,7 @@
 #include <AP_Navigation.h>
 #include <APM_Control.h>
 #include <AP_L1_Control.h>
+#include <AP_BoardConfig.h>
 
 #include <AP_HAL_AVR.h>
 #include <AP_HAL_AVR_SITL.h>
@@ -143,6 +144,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_steer;
 static RC_Channel *channel_throttle;
diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h
index e8f4fad4cd835d0b61edf3fc823d2936381a97f4..f88a0aa256384bbed91b1c3c84c6265462d37e95 100644
--- a/APMrover2/Parameters.h
+++ b/APMrover2/Parameters.h
@@ -34,6 +34,7 @@ public:
         k_param_initial_mode,
         k_param_scheduler,
         k_param_relay,
+        k_param_BoardConfig,
 
         // IO pins
         k_param_rssi_pin = 20,
diff --git a/APMrover2/Parameters.pde b/APMrover2/Parameters.pde
index 0b14af889a71f39337b8d6985db264dd1a76e17b..988cf6cd0580a1304655c177bc0a0167c0a8ed26 100644
--- a/APMrover2/Parameters.pde
+++ b/APMrover2/Parameters.pde
@@ -482,6 +482,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),
+
 	AP_VAREND
 };
 
diff --git a/APMrover2/system.pde b/APMrover2/system.pde
index 93ad2a0f12cc999f0e8c34baefd3589769fe7225..d1710a33676f68f0bf39a6ea1ddc67ef92f1be3b 100644
--- a/APMrover2/system.pde
+++ b/APMrover2/system.pde
@@ -104,6 +104,8 @@ static void init_ardupilot()
 	
     load_parameters();
 
+    BoardConfig.init();
+
     set_control_channels();
 
     // after parameter load setup correct baud rate on uartA