Browse Source

Copter: remove unused TB_RATIO parameter

master
Randy Mackay 12 years ago
parent
commit
33d1129904
  1. 4
      ArduCopter/ArduCopter.pde
  2. 2
      ArduCopter/Parameters.pde
  3. 1
      ArduCopter/defines.h
  4. 7
      libraries/AP_Motors/AP_Motors_Class.cpp
  5. 8
      libraries/AP_Motors/AP_Motors_Class.h

4
ArduCopter/ArduCopter.pde

@ -2066,10 +2066,6 @@ static void tuning(){ @@ -2066,10 +2066,6 @@ static void tuning(){
g.pid_throttle.kD(tuning_value);
break;
case CH6_TOP_BOTTOM_RATIO:
motors.top_bottom_ratio = tuning_value;
break;
case CH6_RELAY:
if (g.rc_6.control_in > 525) relay.on();
if (g.rc_6.control_in < 475) relay.off();

2
ArduCopter/Parameters.pde

@ -380,7 +380,7 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -380,7 +380,7 @@ const AP_Param::Info var_info[] PROGMEM = {
// @DisplayName: Channel 6 Tuning
// @Description: Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
// @User: Standard
// @Values: 0:CH6_NONE,1:CH6_STABILIZE_KP,2:CH6_STABILIZE_KI,3:CH6_YAW_KP,4:CH6_RATE_KP,5:CH6_RATE_KI,6:CH6_YAW_RATE_KP,7:CH6_THROTTLE_KP,8:CH6_TOP_BOTTOM_RATIO,9:CH6_RELAY,10:CH6_WP_SPEED,12:CH6_LOITER_KP,13:CH6_HELI_EXTERNAL_GYRO,14:CH6_THR_HOLD_KP,17:CH6_OPTFLOW_KP,18:CH6_OPTFLOW_KI,19:CH6_OPTFLOW_KD,21:CH6_RATE_KD,22:CH6_LOITER_RATE_KP,23:CH6_LOITER_RATE_KD,24:CH6_YAW_KI,25:CH6_ACRO_KP,26:CH6_YAW_RATE_KD,27:CH6_LOITER_KI,28:CH6_LOITER_RATE_KI,29:CH6_STABILIZE_KD,30:CH6_AHRS_YAW_KP,31:CH6_AHRS_KP,32:CH6_INAV_TC,33:CH6_THROTTLE_KI,34:CH6_THR_ACCEL_KP,35:CH6_THR_ACCEL_KI,36:CH6_THR_ACCEL_KD,38:CH6_DECLINATION,39:CH6_CIRCLE_RATE
// @Values: 0:CH6_NONE,1:CH6_STABILIZE_KP,2:CH6_STABILIZE_KI,3:CH6_YAW_KP,4:CH6_RATE_KP,5:CH6_RATE_KI,6:CH6_YAW_RATE_KP,7:CH6_THROTTLE_KP,9:CH6_RELAY,10:CH6_WP_SPEED,12:CH6_LOITER_KP,13:CH6_HELI_EXTERNAL_GYRO,14:CH6_THR_HOLD_KP,17:CH6_OPTFLOW_KP,18:CH6_OPTFLOW_KI,19:CH6_OPTFLOW_KD,21:CH6_RATE_KD,22:CH6_LOITER_RATE_KP,23:CH6_LOITER_RATE_KD,24:CH6_YAW_KI,25:CH6_ACRO_KP,26:CH6_YAW_RATE_KD,27:CH6_LOITER_KI,28:CH6_LOITER_RATE_KI,29:CH6_STABILIZE_KD,30:CH6_AHRS_YAW_KP,31:CH6_AHRS_KP,32:CH6_INAV_TC,33:CH6_THROTTLE_KI,34:CH6_THR_ACCEL_KP,35:CH6_THR_ACCEL_KI,36:CH6_THR_ACCEL_KD,38:CH6_DECLINATION,39:CH6_CIRCLE_RATE
GSCALAR(radio_tuning, "TUNE", 0),
// @Param: TUNE_LOW

1
ArduCopter/defines.h

@ -156,7 +156,6 @@ @@ -156,7 +156,6 @@
#define CH6_THR_ACCEL_KP 34 // accel based throttle controller's P term
#define CH6_THR_ACCEL_KI 35 // accel based throttle controller's I term
#define CH6_THR_ACCEL_KD 36 // accel based throttle controller's D term
#define CH6_TOP_BOTTOM_RATIO 8 // upper/lower motor ratio (not used)
#define CH6_RELAY 9 // switch relay on if ch6 high, off if low
#define CH6_WP_SPEED 10 // maximum speed to next way point (0 to 10m/s)
#define CH6_LOITER_KP 12 // loiter distance controller's P term (position error to speed)

7
libraries/AP_Motors/AP_Motors_Class.cpp

@ -14,10 +14,7 @@ extern const AP_HAL::HAL& hal; @@ -14,10 +14,7 @@ extern const AP_HAL::HAL& hal;
// parameters for the motor class
const AP_Param::GroupInfo AP_Motors::var_info[] PROGMEM = {
// @Param: TB_RATIO
// @DisplayName: Top Bottom Ratio
// @Description: Not Used. Will control the speed of the top motors vs bottom motors on frames such as the Octo-Quad and Y6
AP_GROUPINFO("TB_RATIO", 0, AP_Motors, top_bottom_ratio, AP_MOTORS_TOP_BOTTOM_RATIO), // not used
// 0 was used by TB_RATIO
// @Param: TCRV_ENABLE
// @DisplayName: Thrust Curve Enable
@ -56,8 +53,6 @@ AP_Motors::AP_Motors( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_ @@ -56,8 +53,6 @@ AP_Motors::AP_Motors( RC_Channel* rc_roll, RC_Channel* rc_pitch, RC_Channel* rc_
AP_Param::setup_object_defaults(this, var_info);
top_bottom_ratio = AP_MOTORS_TOP_BOTTOM_RATIO;
// initialise motor map
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
set_motor_to_channel_map(APM1_MOTOR_TO_CHANNEL_MAP);

8
libraries/AP_Motors/AP_Motors_Class.h

@ -38,10 +38,7 @@ @@ -38,10 +38,7 @@
#define AP_MOTORS_H_FRAME 3 // same as X frame but motors spin in opposite direction
// motor update rate
#define AP_MOTORS_SPEED_DEFAULT 490
// top-bottom ratio (for Y6)
#define AP_MOTORS_TOP_BOTTOM_RATIO 1.0
#define AP_MOTORS_SPEED_DEFAULT 490 // default output rate to the motors
#define THROTTLE_CURVE_ENABLED 1 // throttle curve disabled by default
#define THROTTLE_CURVE_MID_THRUST 52 // throttle which produces 1/2 the maximum thrust. expressed as a percentage of the full throttle range (i.e 0 ~ 100)
@ -142,9 +139,6 @@ public: @@ -142,9 +139,6 @@ public:
// final output values sent to the motors. public (for now) so that they can be access for logging
int16_t motor_out[AP_MOTORS_MAX_NUM_MOTORS];
// power ratio of upper vs lower motors (only used by y6 and octa quad copters)
AP_Float top_bottom_ratio;
// var_info for holding Parameter information
static const struct AP_Param::GroupInfo var_info[];

Loading…
Cancel
Save