diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h
index 40e653835de5e5b8421ec3d478d0ec76ece2f21d..47f82568cbe344e62a63b034cbbfee9fa18445fb 100644
--- a/ArduCopter/Parameters.h
+++ b/ArduCopter/Parameters.h
@@ -102,6 +102,7 @@ public:
 	k_param_rtl_land_enabled,
 	k_param_axis_enabled,
 	k_param_copter_leds_mode, //158
+    k_param_ahrs,  // AHRS group
 
 	//
 	// 160: Navigation parameters
diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde
index ba9e31207c59a9c9408ae9a7edbce64821a72602..aba0a9be34d1b3c3639e634f3ea8aa2c5c131eb8 100644
--- a/ArduCopter/Parameters.pde
+++ b/ArduCopter/Parameters.pde
@@ -135,12 +135,13 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GOBJECT(compass,        "COMPASS_", Compass),
 	GOBJECT(gcs0,			"SR0_",     GCS_MAVLINK),
 	GOBJECT(gcs3,			"SR3_",     GCS_MAVLINK),
-	GOBJECT(imu,			"IMU_",     IMU)
+	GOBJECT(imu,			"IMU_",     IMU),
+	GOBJECT(ahrs,			"AHRS_",    AP_AHRS),
 
 	#if FRAME_CONFIG ==	HELI_FRAME
-	,GOBJECT(motors,	"H_",		AP_MotorsHeli)
+	GOBJECT(motors,	"H_",		AP_MotorsHeli),
 	#else
-	,GOBJECT(motors,	"MOT_",		AP_Motors)
+	GOBJECT(motors,	"MOT_",		AP_Motors),
 	#endif
 };