Sub: Repair motor outputs for ROVs for +/-1.0 range

This commit is contained in:
Rustom Jehangir 2016-04-11 17:09:01 -07:00 committed by Andrew Tridgell
parent 837f429bf0
commit cc00feac29
3 changed files with 7 additions and 7 deletions

View File

@ -49,8 +49,8 @@ void Sub::acro_run()
//control_in is range 0-1000
//radio_in is raw pwm value
motors.set_forward(channel_forward->radio_in);
motors.set_lateral(channel_lateral->radio_in);
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
}

View File

@ -155,6 +155,6 @@ void Sub::althold_run()
//control_in is range 0-1000
//radio_in is raw pwm value
motors.set_forward(channel_forward->radio_in);
motors.set_lateral(channel_lateral->radio_in);
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
}

View File

@ -28,7 +28,7 @@ void Sub::stabilize_run()
float pilot_throttle_scaled;
// if not armed set throttle to zero and exit immediately
if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) {
if (!motors.armed() || !motors.get_interlock()) {
motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
return;
@ -59,6 +59,6 @@ void Sub::stabilize_run()
//control_in is range -1000-1000
//radio_in is raw pwm value
motors.set_forward(channel_forward->radio_in);
motors.set_lateral(channel_lateral->radio_in);
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
}