5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-13 20:28:37 -04:00

Aeducopter.pde: Toy mode updates

This commit is contained in:
Jason Short 2012-06-26 21:57:53 -07:00
parent d399143498
commit c830ab6ded

View File

@ -1493,7 +1493,6 @@ void update_yaw_mode(void)
void update_roll_pitch_mode(void)
{
int control_roll, control_pitch;
int yaw_rate;
// hack to do auto_flip - need to remove, no one is using.
@ -1570,9 +1569,9 @@ void update_roll_pitch_mode(void)
break;
case ROLL_PITCH_TOY:
yaw_rate = g.rc_1.control_in / toy_yaw_rate;
{
int yaw_rate = g.rc_1.control_in / toy_yaw_rate;
int roll_rate;
//yaw_rate = constrain(yaw_rate, -4500, 4500);
if (g.rc_7.radio_in > 1800){
@ -1584,11 +1583,12 @@ void update_roll_pitch_mode(void)
}
// yaw_rate = roll angle
yaw_rate = (g_gps->ground_speed / 1200) * yaw_rate;
yaw_rate = min(yaw_rate, (4500 / toy_yaw_rate)); // 1(fast), 2, 3(slow)
roll_rate = (g_gps->ground_speed / 1200) * yaw_rate;
roll_rate = min(roll_rate, (4500 / toy_yaw_rate)); // 1(fast), 2, 3(slow)
g.rc_1.servo_out = get_stabilize_roll(yaw_rate);// our roll defined by speed and yaw rate
g.rc_1.servo_out = get_stabilize_roll(roll_rate);// our roll defined by speed and yaw rate
g.rc_2.servo_out = get_stabilize_pitch(g.rc_2.control_in);
}
break;
}