Files
ardupilot/ArduCopter/mode_brake.cpp
2025-12-17 08:03:10 +09:00

89 lines
2.7 KiB
C++

#include "Copter.h"
#if MODE_BRAKE_ENABLED
/*
* Init and run calls for brake flight mode
*/
// brake_init - initialise brake controller
bool ModeBrake::init(bool ignore_checks)
{
// initialise pos controller speed and acceleration
pos_control->NE_set_max_speed_accel_m(pos_control->get_vel_estimate_NED_ms().xy().length(), BRAKE_MODE_DECEL_RATE_MSS);
pos_control->NE_set_correction_speed_accel_m(pos_control->get_vel_estimate_NED_ms().xy().length(), BRAKE_MODE_DECEL_RATE_MSS);
// initialise position controller
pos_control->NE_init_controller();
// set vertical speed and acceleration limits
pos_control->D_set_max_speed_accel_m(BRAKE_MODE_SPEED_Z_MS, BRAKE_MODE_SPEED_Z_MS, BRAKE_MODE_DECEL_RATE_MSS);
pos_control->D_set_correction_speed_accel_m(BRAKE_MODE_SPEED_Z_MS, BRAKE_MODE_SPEED_Z_MS, BRAKE_MODE_DECEL_RATE_MSS);
// initialise the vertical position controller
if (!pos_control->D_is_active()) {
pos_control->D_init_controller();
}
_timeout_ms = 0;
return true;
}
// 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
if (is_disarmed_or_landed()) {
make_safe_ground_handling();
pos_control->D_relax_controller(0.0f);
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) {
pos_control->NE_soften_for_landing();
}
// use position controller to stop
Vector2f vel;
Vector2f accel;
pos_control->input_vel_accel_NE_m(vel, accel);
pos_control->NE_update_controller();
// call attitude controller
attitude_control->input_thrust_vector_rate_heading_rads(pos_control->get_thrust_vector(), 0.0f);
pos_control->D_set_pos_target_from_climb_rate_ms(0.0f);
pos_control->D_update_controller();
// MAV_CMD_SOLO_BTN_PAUSE_CLICK (Solo only) is used to set the timeout.
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);
}
}
}
/**
* 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.
*
*/
void ModeBrake::timeout_to_loiter_ms(uint32_t timeout_ms)
{
_timeout_start = millis();
_timeout_ms = timeout_ms;
}
#endif