This commit is contained in:
Amilcar Lucas 2012-06-21 00:21:55 +02:00
commit 9c7fdd742c
4 changed files with 9 additions and 9 deletions

View File

@ -1642,7 +1642,7 @@ void update_throttle_mode(void)
throttle_avg = g.throttle_cruise; throttle_avg = g.throttle_cruise;
} }
// calc average throttle // calc average throttle
if ((g.rc_3.control_in > MINIMUM_THROTTLE) && abs(climb_rate) < 60){ if ((g.rc_3.control_in > g.throttle_min) && abs(climb_rate) < 60){
throttle_avg = throttle_avg * .98 + (float)g.rc_3.control_in * .02; throttle_avg = throttle_avg * .98 + (float)g.rc_3.control_in * .02;
g.throttle_cruise = throttle_avg; g.throttle_cruise = throttle_avg;
} }
@ -2054,9 +2054,9 @@ static void update_altitude_est()
static void static void
adjust_altitude() adjust_altitude()
{ {
if(g.rc_3.control_in <= (MINIMUM_THROTTLE + THROTTLE_ADJUST)){ if(g.rc_3.control_in <= (g.throttle_min + THROTTLE_ADJUST)){
// we remove 0 to 100 PWM from hover // we remove 0 to 100 PWM from hover
manual_boost = (g.rc_3.control_in - MINIMUM_THROTTLE) - THROTTLE_ADJUST; manual_boost = (g.rc_3.control_in - g.throttle_min) - THROTTLE_ADJUST;
manual_boost = max(-THROTTLE_ADJUST, manual_boost); manual_boost = max(-THROTTLE_ADJUST, manual_boost);
}else if (g.rc_3.control_in >= (MAXIMUM_THROTTLE - THROTTLE_ADJUST)){ }else if (g.rc_3.control_in >= (MAXIMUM_THROTTLE - THROTTLE_ADJUST)){

View File

@ -350,8 +350,8 @@ public:
crosstrack_gain (CROSSTRACK_GAIN), crosstrack_gain (CROSSTRACK_GAIN),
auto_land_timeout (AUTO_LAND_TIME * 1000), auto_land_timeout (AUTO_LAND_TIME * 1000),
throttle_min (0), throttle_min (MINIMUM_THROTTLE),
throttle_max (1000), throttle_max (MAXIMUM_THROTTLE),
throttle_fs_enabled (THROTTLE_FAILSAFE), throttle_fs_enabled (THROTTLE_FAILSAFE),
throttle_fs_action (THROTTLE_FAILSAFE_ACTION), throttle_fs_action (THROTTLE_FAILSAFE_ACTION),
throttle_fs_value (THROTTLE_FS_VALUE), throttle_fs_value (THROTTLE_FS_VALUE),

View File

@ -26,7 +26,7 @@ static void init_rc_in()
// we do not want to limit the movment of the heli's swash plate // we do not want to limit the movment of the heli's swash plate
g.rc_3.set_range(0, 1000); g.rc_3.set_range(0, 1000);
#else #else
g.rc_3.set_range(MINIMUM_THROTTLE, MAXIMUM_THROTTLE); g.rc_3.set_range(g.throttle_min, g.throttle_max);
#endif #endif
g.rc_4.set_angle(4500); g.rc_4.set_angle(4500);
@ -54,8 +54,8 @@ static void init_rc_out()
#endif #endif
motors.set_frame_orientation(g.frame_orientation); motors.set_frame_orientation(g.frame_orientation);
motors.Init(); // motor initialisation motors.Init(); // motor initialisation
motors.set_min_throttle(MINIMUM_THROTTLE); motors.set_min_throttle(g.throttle_min);
motors.set_max_throttle(MAXIMUM_THROTTLE); motors.set_max_throttle(g.throttle_max);
// this is the camera pitch5 and roll6 // this is the camera pitch5 and roll6
APM_RC.OutputCh(CH_CAM_PITCH, 1500); APM_RC.OutputCh(CH_CAM_PITCH, 1500);

View File

@ -189,7 +189,7 @@ static int8_t
{ {
print_hit_enter(); print_hit_enter();
delay(1000); delay(1000);
int16_t temp = MINIMUM_THROTTLE; int16_t temp = g.throttle_min;
while(1){ while(1){
delay(20); delay(20);