MOTORS Mixer: temp removal of Yaw Contrib code

This commit is contained in:
Jason Short 2012-08-09 16:57:51 -07:00
parent ab60681376
commit d37ca9343b
1 changed files with 7 additions and 7 deletions

View File

@ -125,7 +125,7 @@ void AP_MotorsMatrix::output_armed()
int8_t i;
int16_t out_min = _rc_throttle->radio_min;
int16_t out_max = _rc_throttle->radio_max;
int16_t yaw_contribution = 0;
//int16_t yaw_contribution = 0;
// Throttle is 0 to 1000 only
_rc_throttle->servo_out = constrain(_rc_throttle->servo_out, 0, _max_throttle);
@ -142,16 +142,16 @@ void AP_MotorsMatrix::output_armed()
// mix roll, pitch, yaw, throttle into output for each motor
for( i=0; i<AP_MOTORS_MAX_NUM_MOTORS; i++ ) {
if( motor_enabled[i] ) {
yaw_contribution = _rc_yaw->pwm_out*_yaw_factor[i];
/*yaw_contribution = _rc_yaw->pwm_out*_yaw_factor[i];
if (yaw_contribution > 0 ){
yaw_contribution *= 0.7;
}else{
yaw_contribution *= 1.42;
}
}*/
motor_out[i] = _rc_throttle->radio_out +
_rc_roll->pwm_out * _roll_factor[i] +
_rc_pitch->pwm_out * _pitch_factor[i] +
yaw_contribution;
_rc_yaw->pwm_out*_yaw_factor[i];
}
}