ardupilot/ArduCopter/control_brake.cpp

67 lines
2.0 KiB
C++
Raw Normal View History

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Copter.h"
/*
2015-05-17 00:22:20 -03:00
* control_brake.pde - init and run calls for brake flight mode
*/
2015-05-17 00:22:20 -03:00
// brake_init - initialise brake controller
bool Copter::brake_init(bool ignore_checks)
{
if (position_ok() || optflow_position_ok() || ignore_checks) {
// set desired acceleration to zero
wp_nav.clear_pilot_desired_acceleration();
// set target to current position
2015-05-17 00:22:20 -03:00
wp_nav.init_brake_target(BRAKE_MODE_DECEL_RATE);
// initialize vertical speed and acceleration
2015-06-05 03:29:00 -03:00
pos_control.set_speed_z(BRAKE_MODE_SPEED_Z, BRAKE_MODE_SPEED_Z);
2015-05-17 00:22:20 -03:00
pos_control.set_accel_z(BRAKE_MODE_DECEL_RATE);
// initialise altitude target to stopping point
pos_control.set_target_to_stopping_point_z();
return true;
}else{
return false;
}
}
2015-05-17 00:22:20 -03:00
// brake_run - runs the brake controller
// should be called at 100hz or more
void Copter::brake_run()
{
// if not auto armed set throttle to zero and exit immediately
if(!ap.auto_armed) {
2015-05-17 00:22:20 -03:00
wp_nav.init_brake_target(BRAKE_MODE_DECEL_RATE);
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(0)-throttle_average);
return;
}
// relax stop target if we might be landed
2015-05-06 01:38:38 -03:00
if (ap.land_complete_maybe) {
2015-05-17 02:28:55 -03:00
wp_nav.loiter_soften_for_landing();
}
// if landed immediately disarm
if (ap.land_complete) {
init_disarm_motors();
}
2015-05-17 00:22:20 -03:00
// run brake controller
wp_nav.update_brake(ekfGndSpdLimit, ekfNavVelGainScaler);
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_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
pos_control.set_alt_target_from_climb_rate(0.0f, G_Dt, false);
pos_control.update_z_controller();
}