2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2019-02-25 10:32:52 -04:00
|
|
|
#if MODE_BRAKE_ENABLED == ENABLED
|
|
|
|
|
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
|
2019-05-09 23:18:49 -03:00
|
|
|
bool ModeBrake::init(bool ignore_checks)
|
2015-04-22 18:10:10 -03:00
|
|
|
{
|
2021-05-11 01:42:02 -03:00
|
|
|
// initialise pos controller speed and acceleration
|
2021-10-20 05:29:57 -03:00
|
|
|
pos_control->set_max_speed_accel_xy(inertial_nav.get_velocity_neu_cms().length(), BRAKE_MODE_DECEL_RATE);
|
|
|
|
pos_control->set_correction_speed_accel_xy(inertial_nav.get_velocity_neu_cms().length(), BRAKE_MODE_DECEL_RATE);
|
2021-05-11 01:42:02 -03:00
|
|
|
|
|
|
|
// initialise position controller
|
|
|
|
pos_control->init_xy_controller();
|
2015-04-22 18:10:10 -03:00
|
|
|
|
2021-05-19 11:07:38 -03:00
|
|
|
// set vertical speed and acceleration limits
|
2021-05-11 01:42:02 -03:00
|
|
|
pos_control->set_max_speed_accel_z(BRAKE_MODE_SPEED_Z, BRAKE_MODE_SPEED_Z, BRAKE_MODE_DECEL_RATE);
|
2021-07-08 01:17:41 -03:00
|
|
|
pos_control->set_correction_speed_accel_z(BRAKE_MODE_SPEED_Z, BRAKE_MODE_SPEED_Z, BRAKE_MODE_DECEL_RATE);
|
2015-04-22 18:10:10 -03:00
|
|
|
|
2021-05-19 11:07:38 -03:00
|
|
|
// initialise the vertical position controller
|
2019-02-28 20:52:28 -04:00
|
|
|
if (!pos_control->is_active_z()) {
|
2021-05-11 01:42:02 -03:00
|
|
|
pos_control->init_z_controller();
|
2019-02-28 20:52:28 -04:00
|
|
|
}
|
2015-04-22 18:10:10 -03:00
|
|
|
|
2019-02-28 20:52:28 -04:00
|
|
|
_timeout_ms = 0;
|
2016-01-05 02:12:25 -04:00
|
|
|
|
2019-02-28 20:52:28 -04:00
|
|
|
return true;
|
2015-04-22 18:10:10 -03:00
|
|
|
}
|
|
|
|
|
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
|
2019-05-09 23:18:49 -03:00
|
|
|
void ModeBrake::run()
|
2015-04-22 18:10:10 -03:00
|
|
|
{
|
2019-02-28 05:03:23 -04:00
|
|
|
// if not armed set throttle to zero and exit immediately
|
2019-04-08 05:15:57 -03:00
|
|
|
if (is_disarmed_or_landed()) {
|
2020-10-13 20:19:42 -03:00
|
|
|
make_safe_ground_handling();
|
2021-05-11 01:42:02 -03:00
|
|
|
pos_control->relax_z_controller(0.0f);
|
2015-04-22 18:10:10 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2019-02-28 05:03:23 -04:00
|
|
|
// set motors to full range
|
2019-04-09 09:16:58 -03:00
|
|
|
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
|
2019-02-28 05:03:23 -04:00
|
|
|
|
2015-04-22 18:10:10 -03:00
|
|
|
// relax stop target if we might be landed
|
2019-05-09 23:18:49 -03:00
|
|
|
if (copter.ap.land_complete_maybe) {
|
2022-02-01 23:40:27 -04:00
|
|
|
pos_control->soften_for_landing_xy();
|
2015-05-17 02:28:55 -03:00
|
|
|
}
|
|
|
|
|
2019-06-12 03:42:55 -03:00
|
|
|
// use position controller to stop
|
2021-06-21 04:22:48 -03:00
|
|
|
Vector2f vel;
|
|
|
|
Vector2f accel;
|
2021-05-11 01:42:02 -03:00
|
|
|
pos_control->input_vel_accel_xy(vel, accel);
|
2019-06-12 03:42:55 -03:00
|
|
|
pos_control->update_xy_controller();
|
2015-04-22 18:10:10 -03:00
|
|
|
|
|
|
|
// call attitude controller
|
2021-05-11 01:42:02 -03:00
|
|
|
attitude_control->input_thrust_vector_rate_heading(pos_control->get_thrust_vector(), 0.0f);
|
|
|
|
|
2021-08-31 01:17:59 -03:00
|
|
|
pos_control->set_pos_target_z_from_climb_rate_cm(0.0f);
|
2017-01-09 03:31:26 -04:00
|
|
|
pos_control->update_z_controller();
|
2016-01-05 02:12:25 -04:00
|
|
|
|
2023-05-20 20:24:54 -03:00
|
|
|
// MAV_CMD_SOLO_BTN_PAUSE_CLICK (Solo only) is used to set the timeout.
|
2016-03-22 22:00:19 -03:00
|
|
|
if (_timeout_ms != 0 && millis()-_timeout_start >= _timeout_ms) {
|
2019-10-17 00:49:22 -03:00
|
|
|
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
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-05-20 20:24:54 -03:00
|
|
|
/**
|
|
|
|
* Set a timeout for the brake mode
|
|
|
|
*
|
|
|
|
* @param timeout_ms [in] timeout in milliseconds
|
|
|
|
*
|
|
|
|
* @note MAV_CMD_SOLO_BTN_PAUSE_CLICK (Solo only) is used to set the timeout.
|
|
|
|
* If the timeout is reached, the mode will switch to loiter or alt hold depending on the current mode.
|
|
|
|
* If timeout_ms is 0, the timeout is disabled.
|
|
|
|
*
|
|
|
|
*/
|
2019-05-09 23:18:49 -03:00
|
|
|
void 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
|
|
|
}
|
2019-02-25 10:32:52 -04:00
|
|
|
|
|
|
|
#endif
|