ardupilot/ArduCopter/mode_brake.cpp

97 lines
2.9 KiB
C++
Raw Normal View History

#include "Copter.h"
#if MODE_BRAKE_ENABLED == ENABLED
/*
* Init and run calls for brake flight mode
*/
2015-05-17 00:22:20 -03:00
// brake_init - initialise brake controller
bool ModeBrake::init(bool ignore_checks)
{
// set target to current position
2019-06-12 03:42:55 -03:00
init_target();
// initialize vertical speed and acceleration
pos_control->set_max_speed_z(BRAKE_MODE_SPEED_Z, BRAKE_MODE_SPEED_Z);
pos_control->set_max_accel_z(BRAKE_MODE_DECEL_RATE);
// initialise position and desired velocity
if (!pos_control->is_active_z()) {
pos_control->set_alt_target_to_current_alt();
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
}
_timeout_ms = 0;
2016-01-05 02:12:25 -04:00
return true;
}
2015-05-17 00:22:20 -03:00
// brake_run - runs the brake controller
// should be called at 100hz or more
void ModeBrake::run()
{
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if (is_disarmed_or_landed()) {
make_safe_spool_down();
2019-06-12 03:42:55 -03:00
init_target();
return;
}
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
// relax stop target if we might be landed
if (copter.ap.land_complete_maybe) {
loiter_nav->soften_for_landing();
2015-05-17 02:28:55 -03:00
}
2019-06-12 03:42:55 -03:00
// use position controller to stop
pos_control->set_desired_velocity_xy(0.0f, 0.0f);
pos_control->update_xy_controller();
// call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), 0.0f);
// update altitude target and call position controller
// protects heli's from inflight motor interlock disable
if (motors->get_desired_spool_state() == AP_Motors::DesiredSpoolState::GROUND_IDLE && !copter.ap.land_complete) {
pos_control->set_alt_target_from_climb_rate(-abs(g.land_speed), G_Dt, false);
} else {
pos_control->set_alt_target_from_climb_rate_ff(0.0f, G_Dt, false);
}
pos_control->update_z_controller();
2016-01-05 02:12:25 -04:00
if (_timeout_ms != 0 && millis()-_timeout_start >= _timeout_ms) {
if (!copter.set_mode(Mode::Number::LOITER, ModeReason::BRAKE_TIMEOUT)) {
copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::BRAKE_TIMEOUT);
2016-01-05 02:12:25 -04:00
}
}
}
void ModeBrake::timeout_to_loiter_ms(uint32_t timeout_ms)
2016-01-05 02:12:25 -04:00
{
_timeout_start = millis();
_timeout_ms = timeout_ms;
}
2019-06-12 03:42:55 -03:00
void ModeBrake::init_target()
{
// initialise position controller
pos_control->set_desired_velocity_xy(0.0f,0.0f);
pos_control->set_desired_accel_xy(0.0f,0.0f);
pos_control->init_xy_controller();
// initialise pos controller speed and acceleration
pos_control->set_max_speed_xy(inertial_nav.get_velocity().length());
pos_control->set_max_accel_xy(BRAKE_MODE_DECEL_RATE);
pos_control->calc_leash_length_xy();
// set target position
Vector3f stopping_point;
pos_control->get_stopping_point_xy(stopping_point);
pos_control->set_xy_target(stopping_point.x, stopping_point.y);
}
#endif