Merged Jacob's changes but removed deleted submodules from commit.

This commit is contained in:
Rustom Jehangir 2016-01-08 20:33:21 -08:00
commit aad6fcbbf8
4 changed files with 19 additions and 2 deletions

View File

@ -261,8 +261,10 @@ void Copter::fast_loop()
// run low level rate controllers that only require IMU data
attitude_control.rate_controller_run();
motors.set_forward(channel_forward->control_in);
motors.set_strafe(channel_strafe->control_in);
// moved this to update in control_acro.cpp, control_stabilize.cpp ...
// motors.set_forward(channel_forward->control_in);
// motors.set_strafe(channel_strafe->control_in);
#if FRAME_CONFIG == HELI_FRAME
update_heli_control_dynamics();

View File

@ -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);
}

View File

@ -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);
}

View File

@ -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);
}