From 929e933b692c25d71cf9e2f252073721109355e8 Mon Sep 17 00:00:00 2001
From: rmackay9 <rmackay9@yahoo.com>
Date: Wed, 4 Apr 2012 22:55:07 +0900
Subject: [PATCH] ArduCopter - increased firmware version to 118.  Removed
 nearly all heli parameters as these are all created by the AP_MotorHeli class
 now. Note: we cannot move the heli_servos to the AP_MotorHeli class yet
 because of a small issue in the parameters class.

---
 ArduCopter/Parameters.h   | 57 ++++++---------------------------------
 ArduCopter/Parameters.pde | 22 +++++----------
 2 files changed, 14 insertions(+), 65 deletions(-)

diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h
index beb92f70b..c26ca271e 100644
--- a/ArduCopter/Parameters.h
+++ b/ArduCopter/Parameters.h
@@ -17,7 +17,7 @@ public:
 	// The increment will prevent old parameters from being used incorrectly
 	// by newer code.
 	//
-	static const uint16_t k_format_version = 117;
+	static const uint16_t k_format_version = 118;
 
 	// The parameter software_type is set up solely for ground station use
 	// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
@@ -65,23 +65,13 @@ public:
 	k_param_heli_servo_2,
 	k_param_heli_servo_3,
 	k_param_heli_servo_4,
-	k_param_heli_servo1_pos ,
-	k_param_heli_servo2_pos,
-	k_param_heli_servo3_pos,
-	k_param_heli_roll_max,
-	k_param_heli_pitch_max,
-	k_param_heli_collective_min,
-	k_param_heli_collective_max,
-	k_param_heli_collective_mid,
-	k_param_heli_ext_gyro_enabled,
-	k_param_heli_ext_gyro_gain,
-	k_param_heli_servo_averaging,
-	k_param_heli_servo_manual,
-	k_param_heli_phase_angle,
-	k_param_heli_collective_yaw_effect,
-	k_param_heli_h1_swash_enabled, //98
 	#endif
 
+	//
+	// 90: Motors
+	//
+	k_param_motors = 90,
+
 	// 110: Telemetry control
 	//
 	k_param_gcs0 = 110,
@@ -103,15 +93,14 @@ public:
 	k_param_compass,
 	k_param_sonar_enabled,
 	k_param_frame_orientation,
-	k_param_top_bottom_ratio,
 	k_param_optflow_enabled,
 	k_param_low_voltage,
 	k_param_ch7_option,
 	k_param_auto_slew_rate,
 	k_param_sonar_type,
-	k_param_super_simple, //155
+	k_param_super_simple,
 	k_param_rtl_land_enabled,
-	k_param_axis_enabled,
+	k_param_axis_enabled, //157
 
 	//
 	// 160: Navigation parameters
@@ -266,23 +255,12 @@ public:
 	AP_Int16	radio_tuning_high;
 	AP_Int16	radio_tuning_low;
 	AP_Int8		frame_orientation;
-	AP_Float	top_bottom_ratio;
 	AP_Int8		ch7_option;
 	AP_Int16	auto_slew_rate;
 
 	#if FRAME_CONFIG ==	HELI_FRAME
 	// Heli
 	RC_Channel	heli_servo_1, heli_servo_2, heli_servo_3, heli_servo_4;	// servos for swash plate and tail
-	AP_Int16	heli_servo1_pos, heli_servo2_pos, heli_servo3_pos;		// servo positions (3 because we don't need pos for tail servo)
-	AP_Int16	heli_roll_max, heli_pitch_max;	// maximum allowed roll and pitch of swashplate
-	AP_Int16	heli_collective_min, heli_collective_max, heli_collective_mid;		// min and max collective.	mid = main blades at zero pitch
-	AP_Int8		heli_ext_gyro_enabled;	// 0 = no external tail gyro, 1 = external tail gyro
-	AP_Int16	heli_ext_gyro_gain;		// radio output 1000~2000 (value output on CH_7)
-	AP_Int8		heli_servo_averaging;	// 0 or 1 = no averaging (250hz) for **digital servos**, 2=average of two samples (125hz), 3=three samples (83.3hz) **analog servos**, 4=four samples (62.5hz), 5=5 samples(50hz)
-	AP_Int8		heli_servo_manual;	    // 0 = normal mode, 1 = radio inputs directly control swash.  required for swash set-up
-	AP_Int16	heli_phase_angle;		// 0 to 360 degrees.  specifies mixing between roll and pitch for helis
-	AP_Float	heli_collective_yaw_effect;	// -5.0 ~ 5.0.  Feed forward control from collective to yaw.  1.0 = move rudder right 1% for every 1% of collective above the mid point
-	AP_Int8		heli_h1_swash_enabled; 	// 0 = CCPM swashplate, 1 = H1 swashplate (no servo mixing)
 	#endif
 
 	// RC channels
@@ -384,28 +362,9 @@ public:
 	radio_tuning_high 		(1000),
 	radio_tuning_low 		(0),
 	frame_orientation 		(FRAME_ORIENTATION),
-	top_bottom_ratio 		(TOP_BOTTOM_RATIO),
 	ch7_option 				(CH7_OPTION),
 	auto_slew_rate			(AUTO_SLEW_RATE),
 
-	#if FRAME_CONFIG ==	HELI_FRAME
-	heli_servo1_pos				(-60),
-	heli_servo2_pos				(60),
-	heli_servo3_pos				(180),
-	heli_roll_max				(4500),
-	heli_pitch_max				(4500),
-	heli_collective_min			(1250),
-	heli_collective_max			(1750),
-	heli_collective_mid			(1500),
-	heli_ext_gyro_enabled		(0),
-	heli_ext_gyro_gain			(1350),
-	heli_servo_averaging		(0),
-	heli_servo_manual			(0),
-	heli_phase_angle			(0),
-	heli_collective_yaw_effect	(0),
-	heli_h1_swash_enabled		(0),
-	#endif
-
     rc_speed(RC_FAST_SPEED),
 
 	camera_pitch_gain 		(CAM_PITCH_GAIN),
diff --git a/ArduCopter/Parameters.pde b/ArduCopter/Parameters.pde
index 4855031e4..8a84e81ac 100644
--- a/ArduCopter/Parameters.pde
+++ b/ArduCopter/Parameters.pde
@@ -67,7 +67,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GSCALAR(radio_tuning_low, "TUNE_LOW"),
 	GSCALAR(radio_tuning_high, "TUNE_HIGH"),
 	GSCALAR(frame_orientation, "FRAME"),
-	GSCALAR(top_bottom_ratio, "TB_RATIO"),
 	GSCALAR(ch7_option, "CH7_OPT"),
 	GSCALAR(auto_slew_rate, "AUTO_SLEW"),
 
@@ -76,21 +75,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GGROUP(heli_servo_2,	"HS2_", RC_Channel),
 	GGROUP(heli_servo_3,	"HS3_", RC_Channel),
 	GGROUP(heli_servo_4,	"HS4_", RC_Channel),
-	GSCALAR(heli_servo1_pos,	"SV1_POS"),
-	GSCALAR(heli_servo2_pos,	"SV2_POS"),
-	GSCALAR(heli_servo3_pos,	"SV3_POS"),
-	GSCALAR(heli_roll_max,	"ROL_MAX"),
-	GSCALAR(heli_pitch_max,	"PIT_MAX"),
-	GSCALAR(heli_collective_min,	"COL_MIN"),
-	GSCALAR(heli_collective_max,	"COL_MAX"),
-	GSCALAR(heli_collective_mid,	"COL_MID"),
-	GSCALAR(heli_ext_gyro_enabled,	"GYR_ENABLE"),
-	GSCALAR(heli_h1_swash_enabled,	"H1_ENABLE"),
-	GSCALAR(heli_ext_gyro_gain,	"GYR_GAIN"),
-	GSCALAR(heli_servo_averaging,	"SV_AVG"),
-	GSCALAR(heli_servo_manual,	"HSV_MAN"),
-	GSCALAR(heli_phase_angle,	"H_PHANG"),
-	GSCALAR(heli_collective_yaw_effect,	"H_COLYAW"),
 	#endif
 
 	// RC channel
@@ -151,6 +135,12 @@ static const AP_Param::Info var_info[] PROGMEM = {
 	GOBJECT(gcs0,			"SR0_",     GCS_MAVLINK),
 	GOBJECT(gcs3,			"SR3_",     GCS_MAVLINK),
 	GOBJECT(imu,			"IMU_",     IMU)
+
+	#if FRAME_CONFIG ==	HELI_FRAME
+	,GOBJECT(motors,	"H_",		AP_MotorsHeli)
+	#else
+	,GOBJECT(motors,	"MOT_",		AP_Motors)
+	#endif
 };
 
 
-- 
GitLab