mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Update forward and strafe rc channels in the control mode files.
This commit is contained in:
parent
c2d37ffd6e
commit
2f3aff7499
@ -47,6 +47,11 @@ void Copter::acro_run()
|
||||
|
||||
// output pilot's throttle without angle boost
|
||||
attitude_control.set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
|
||||
|
||||
//control_in is range 0-1000
|
||||
//radio_in is raw pwm value
|
||||
motors.set_forward(channel_forward->radio_in);
|
||||
motors.set_strafe(channel_strafe->radio_in);
|
||||
}
|
||||
|
||||
|
||||
|
@ -158,4 +158,9 @@ void Copter::althold_run()
|
||||
pos_control.update_z_controller();
|
||||
break;
|
||||
}
|
||||
|
||||
//control_in is range 0-1000
|
||||
//radio_in is raw pwm value
|
||||
motors.set_forward(channel_forward->radio_in);
|
||||
motors.set_strafe(channel_strafe->radio_in);
|
||||
}
|
||||
|
@ -57,4 +57,9 @@ void Copter::stabilize_run()
|
||||
|
||||
// output pilot's throttle
|
||||
attitude_control.set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt);
|
||||
|
||||
//control_in is range 0-1000
|
||||
//radio_in is raw pwm value
|
||||
motors.set_forward(channel_forward->radio_in);
|
||||
motors.set_strafe(channel_strafe->radio_in);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user