2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2015-04-22 18:10:10 -03:00
|
|
|
/*
|
2016-07-25 15:45:29 -03:00
|
|
|
* Init and run calls for brake flight mode
|
2015-04-22 18:10:10 -03:00
|
|
|
*/
|
|
|
|
|
2015-05-17 00:22:20 -03:00
|
|
|
// brake_init - initialise brake controller
|
2017-12-10 23:51:13 -04:00
|
|
|
bool Copter::ModeBrake::init(bool ignore_checks)
|
2015-04-22 18:10:10 -03:00
|
|
|
{
|
2018-02-07 22:21:09 -04:00
|
|
|
if (copter.position_ok() || ignore_checks) {
|
2015-04-22 18:10:10 -03:00
|
|
|
|
|
|
|
// set target to current position
|
2017-01-09 03:31:26 -04:00
|
|
|
wp_nav->init_brake_target(BRAKE_MODE_DECEL_RATE);
|
2015-04-22 18:10:10 -03:00
|
|
|
|
|
|
|
// initialize vertical speed and acceleration
|
2018-09-20 02:45:02 -03:00
|
|
|
pos_control->set_max_speed_z(BRAKE_MODE_SPEED_Z, BRAKE_MODE_SPEED_Z);
|
|
|
|
pos_control->set_max_accel_z(BRAKE_MODE_DECEL_RATE);
|
2015-04-22 18:10:10 -03:00
|
|
|
|
2015-10-27 10:06:50 -03:00
|
|
|
// initialise position and desired velocity
|
2017-01-09 03:31:26 -04:00
|
|
|
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());
|
2016-10-14 09:28:32 -03:00
|
|
|
}
|
2015-04-22 18:10:10 -03:00
|
|
|
|
2016-03-22 22:00:19 -03:00
|
|
|
_timeout_ms = 0;
|
2016-01-05 02:12:25 -04:00
|
|
|
|
2015-04-22 18:10:10 -03:00
|
|
|
return true;
|
|
|
|
}else{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-05-17 00:22:20 -03:00
|
|
|
// brake_run - runs the brake controller
|
2015-04-22 18:10:10 -03:00
|
|
|
// should be called at 100hz or more
|
2017-12-10 23:51:13 -04:00
|
|
|
void Copter::ModeBrake::run()
|
2015-04-22 18:10:10 -03:00
|
|
|
{
|
|
|
|
// if not auto armed set throttle to zero and exit immediately
|
2017-01-09 03:31:26 -04:00
|
|
|
if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
|
|
|
|
wp_nav->init_brake_target(BRAKE_MODE_DECEL_RATE);
|
2016-11-17 01:47:41 -04:00
|
|
|
zero_throttle_and_relax_ac();
|
2017-01-09 03:31:26 -04:00
|
|
|
pos_control->relax_alt_hold_controllers(0.0f);
|
2015-04-22 18:10:10 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// relax stop target if we might be landed
|
2015-05-06 01:38:38 -03:00
|
|
|
if (ap.land_complete_maybe) {
|
2018-03-27 23:13:37 -03:00
|
|
|
loiter_nav->soften_for_landing();
|
2015-05-17 02:28:55 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// if landed immediately disarm
|
|
|
|
if (ap.land_complete) {
|
2018-02-07 22:21:09 -04:00
|
|
|
copter.init_disarm_motors();
|
2015-04-22 18:10:10 -03:00
|
|
|
}
|
|
|
|
|
2016-01-13 03:09:42 -04:00
|
|
|
// set motors to full range
|
2017-01-09 03:31:26 -04:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
|
2016-01-13 03:09:42 -04:00
|
|
|
|
2015-05-17 00:22:20 -03:00
|
|
|
// run brake controller
|
2018-09-05 03:47:50 -03:00
|
|
|
wp_nav->update_brake();
|
2015-04-22 18:10:10 -03:00
|
|
|
|
|
|
|
// call attitude controller
|
2017-06-26 05:48:04 -03:00
|
|
|
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), 0.0f);
|
2015-04-22 18:10:10 -03:00
|
|
|
|
|
|
|
// body-frame rate controller is run directly from 100hz loop
|
|
|
|
|
|
|
|
// update altitude target and call position controller
|
2017-01-09 03:31:26 -04:00
|
|
|
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
|
|
|
|
2016-03-22 22:00:19 -03:00
|
|
|
if (_timeout_ms != 0 && millis()-_timeout_start >= _timeout_ms) {
|
2018-02-07 22:21:09 -04:00
|
|
|
if (!copter.set_mode(LOITER, MODE_REASON_BRAKE_TIMEOUT)) {
|
|
|
|
copter.set_mode(ALT_HOLD, MODE_REASON_BRAKE_TIMEOUT);
|
2016-01-05 02:12:25 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-12-10 23:51:13 -04:00
|
|
|
void Copter::ModeBrake::timeout_to_loiter_ms(uint32_t timeout_ms)
|
2016-01-05 02:12:25 -04:00
|
|
|
{
|
2016-03-22 22:00:19 -03:00
|
|
|
_timeout_start = millis();
|
|
|
|
_timeout_ms = timeout_ms;
|
2015-04-22 18:10:10 -03:00
|
|
|
}
|