Copter: formatting fixes
This commit is contained in:
parent
6e76dff930
commit
593925567b
@ -999,11 +999,11 @@ void Copter::ModeAuto::payload_place_run()
|
||||
|
||||
bool Copter::ModeAuto::payload_place_run_should_run()
|
||||
{
|
||||
// muts be armed
|
||||
// must be armed
|
||||
if (!motors->armed()) {
|
||||
return false;
|
||||
}
|
||||
// muts be auto-armed
|
||||
// must be auto-armed
|
||||
if (!ap.auto_armed) {
|
||||
return false;
|
||||
}
|
||||
|
@ -52,8 +52,6 @@ void Copter::ModeBrake::run()
|
||||
// call attitude controller
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), 0.0f);
|
||||
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// update altitude target and call position controller
|
||||
// protects heli's from inflight motor interlock disable
|
||||
if (motors->get_desired_spool_state() == AP_Motors::DESIRED_GROUND_IDLE && !ap.land_complete) {
|
||||
|
@ -52,7 +52,7 @@ void Copter::ModeDrift::run()
|
||||
float roll_vel = vel.y * ahrs.cos_yaw() - vel.x * ahrs.sin_yaw(); // body roll vel
|
||||
float pitch_vel = vel.y * ahrs.sin_yaw() + vel.x * ahrs.cos_yaw(); // body pitch vel
|
||||
|
||||
// gain sceduling for Yaw
|
||||
// gain scheduling for yaw
|
||||
float pitch_vel2 = MIN(fabsf(pitch_vel), 2000);
|
||||
float target_yaw_rate = ((float)target_roll/1.0f) * (1.0f - (pitch_vel2 / 5000.0f)) * g.acro_yaw_p;
|
||||
|
||||
@ -64,7 +64,7 @@ void Copter::ModeDrift::run()
|
||||
// convert user input into desired roll velocity
|
||||
float roll_vel_error = roll_vel - (roll_input / DRIFT_SPEEDGAIN);
|
||||
|
||||
// Roll velocity is feed into roll acceleration to minimize slip
|
||||
// roll velocity is feed into roll acceleration to minimize slip
|
||||
target_roll = roll_vel_error * -DRIFT_SPEEDGAIN;
|
||||
target_roll = constrain_float(target_roll, -4500.0f, 4500.0f);
|
||||
|
||||
|
@ -226,7 +226,7 @@ void Copter::ModeFlowHold::run()
|
||||
copter.pos_control->set_max_accel_z(copter.g.pilot_accel_z);
|
||||
|
||||
// apply SIMPLE mode transform to pilot inputs
|
||||
copter.update_simple_mode();
|
||||
update_simple_mode();
|
||||
|
||||
// check for filter change
|
||||
if (!is_equal(flow_filter.get_cutoff_freq(), flow_filter_hz.get())) {
|
||||
|
@ -46,8 +46,6 @@ void Copter::ModeStabilize::run()
|
||||
// call attitude controller
|
||||
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
|
||||
|
||||
// body-frame rate controller is run directly from 100hz loop
|
||||
|
||||
// output pilot's throttle
|
||||
attitude_control->set_throttle_out(get_pilot_desired_throttle(),
|
||||
true,
|
||||
|
Loading…
Reference in New Issue
Block a user