AP_Motors: Rename output_yaw to move_yaw in AP_MotorsHeli_Single.

This commit is contained in:
Fredrik Hedberg 2015-08-06 10:25:31 +02:00 committed by Randy Mackay
parent 7ac02922e9
commit 260d018db9
2 changed files with 6 additions and 4 deletions

View File

@ -463,11 +463,11 @@ void AP_MotorsHeli_Single::move_swash(int16_t roll_out, int16_t pitch_out, int16
hal.rcout->write(pgm_read_byte(&_motor_to_channel_map[AP_MOTORS_MOT_3]), _servo_3.radio_out);
// update the yaw rate using the tail rotor/servo
output_yaw(yaw_out + yaw_offset);
move_yaw(yaw_out + yaw_offset);
}
// output_yaw
void AP_MotorsHeli_Single::output_yaw(int16_t yaw_out)
// move_yaw
void AP_MotorsHeli_Single::move_yaw(int16_t yaw_out)
{
_servo_4.servo_out = constrain_int16(yaw_out, -4500, 4500);

View File

@ -129,7 +129,6 @@ protected:
// output - sends commands to the motors
void output_armed_stabilizing();
void output_disarmed();
void output_yaw(int16_t yaw_out);
// reset_servos - free up the swash servos for maximum movement
void reset_servos();
@ -143,6 +142,9 @@ protected:
// heli_move_swash - moves swash plate to attitude of parameters passed in
void move_swash(int16_t roll_out, int16_t pitch_out, int16_t coll_in, int16_t yaw_out);
// move_yaw - moves the yaw servo
void move_yaw(int16_t yaw_out);
// write_aux - outputs pwm onto output aux channel (ch7). servo_out parameter is of the range 0 ~ 1000
void write_aux(int16_t servo_out);