mirror of
https://github.com/ArduPilot/ardupilot.git
synced 2026-02-06 00:30:56 +08:00
ArduSub: fix bug in Sub master
This commit is contained in:
committed by
Willian Galvani
parent
7eac443150
commit
39426ed27a
@@ -29,7 +29,7 @@ void ModeManual::run()
|
||||
sub.motors.set_roll(channel_roll->norm_input());
|
||||
sub.motors.set_pitch(channel_pitch->norm_input());
|
||||
sub.motors.set_yaw(channel_yaw->norm_input() * g.acro_yaw_p / ACRO_YAW_P);
|
||||
sub.motors.set_throttle(channel_throttle->norm_input());
|
||||
sub.motors.set_throttle((channel_throttle->norm_input() + 1.0f) / 2.0f);
|
||||
sub.motors.set_forward(channel_forward->norm_input());
|
||||
sub.motors.set_lateral(channel_lateral->norm_input());
|
||||
}
|
||||
|
||||
@@ -60,7 +60,7 @@ void ModeStabilize::run()
|
||||
}
|
||||
|
||||
// output pilot's throttle
|
||||
attitude_control->set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt);
|
||||
attitude_control->set_throttle_out((channel_throttle->norm_input() + 1.0f) / 2.0f, false, g.throttle_filt);
|
||||
|
||||
//control_in is range -1000-1000
|
||||
//radio_in is raw pwm value
|
||||
|
||||
Reference in New Issue
Block a user