Copter: auto uses AP_Motors set_desired_spool_state

This commit is contained in:
Randy Mackay 2016-02-02 21:17:04 +09:00
parent a927db3e6a
commit 4f192d0bc7
1 changed files with 10 additions and 10 deletions

View File

@ -120,7 +120,7 @@ void Copter::auto_takeoff_run()
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
attitude_control.set_throttle_out(0,false,g.throttle_filt); attitude_control.set_throttle_out(0,false,g.throttle_filt);
#else // multicopters do not stabilize roll/pitch/yaw when disarmed #else // multicopters do not stabilize roll/pitch/yaw when disarmed
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// reset attitude control targets // reset attitude control targets
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif #endif
@ -137,7 +137,7 @@ void Copter::auto_takeoff_run()
} }
// set motors to full range // set motors to full range
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// run waypoint controller // run waypoint controller
wp_nav.update_wpnav(); wp_nav.update_wpnav();
@ -177,7 +177,7 @@ void Copter::auto_wp_run()
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
attitude_control.set_throttle_out(0,false,g.throttle_filt); attitude_control.set_throttle_out(0,false,g.throttle_filt);
#else // multicopters do not stabilize roll/pitch/yaw when disarmed #else // multicopters do not stabilize roll/pitch/yaw when disarmed
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif #endif
// clear i term when we're taking off // clear i term when we're taking off
@ -196,7 +196,7 @@ void Copter::auto_wp_run()
} }
// set motors to full range // set motors to full range
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// run waypoint controller // run waypoint controller
wp_nav.update_wpnav(); wp_nav.update_wpnav();
@ -246,7 +246,7 @@ void Copter::auto_spline_run()
attitude_control.set_throttle_out(0,false,g.throttle_filt); attitude_control.set_throttle_out(0,false,g.throttle_filt);
#else // multicopters do not stabilize roll/pitch/yaw when disarmed #else // multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
#endif #endif
// clear i term when we're taking off // clear i term when we're taking off
set_throttle_takeoff(); set_throttle_takeoff();
@ -264,7 +264,7 @@ void Copter::auto_spline_run()
} }
// set motors to full range // set motors to full range
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// run waypoint controller // run waypoint controller
wp_nav.update_spline(); wp_nav.update_spline();
@ -322,7 +322,7 @@ void Copter::auto_land_run()
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
attitude_control.set_throttle_out(0,false,g.throttle_filt); attitude_control.set_throttle_out(0,false,g.throttle_filt);
#else #else
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// multicopters do not stabilize roll/pitch/yaw when disarmed // multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif #endif
@ -360,7 +360,7 @@ void Copter::auto_land_run()
} }
// set motors to full range // set motors to full range
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// process roll, pitch inputs // process roll, pitch inputs
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control); wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
@ -507,7 +507,7 @@ void Copter::auto_loiter_run()
attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain()); attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw_smooth(0, 0, 0, get_smoothing_gain());
attitude_control.set_throttle_out(0,false,g.throttle_filt); attitude_control.set_throttle_out(0,false,g.throttle_filt);
#else #else
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_SPIN_WHEN_ARMED); motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
// multicopters do not stabilize roll/pitch/yaw when disarmed // multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif #endif
@ -521,7 +521,7 @@ void Copter::auto_loiter_run()
} }
// set motors to full range // set motors to full range
motors.set_desired_spool_state(AP_MotorsMulticopter::DESIRED_THROTTLE_UNLIMITED); motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
// run waypoint and z-axis postion controller // run waypoint and z-axis postion controller
wp_nav.update_wpnav(); wp_nav.update_wpnav();