APM:Copter
mode_brake.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * Init and run calls for brake flight mode
5  */
6 
7 // brake_init - initialise brake controller
8 bool Copter::ModeBrake::init(bool ignore_checks)
9 {
10  if (copter.position_ok() || ignore_checks) {
11 
12  // set target to current position
14 
15  // initialize vertical speed and acceleration
18 
19  // initialise position and desired velocity
20  if (!pos_control->is_active_z()) {
23  }
24 
25  _timeout_ms = 0;
26 
27  return true;
28  }else{
29  return false;
30  }
31 }
32 
33 // brake_run - runs the brake controller
34 // should be called at 100hz or more
36 {
37  // if not auto armed set throttle to zero and exit immediately
38  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
42  return;
43  }
44 
45  // relax stop target if we might be landed
46  if (ap.land_complete_maybe) {
48  }
49 
50  // if landed immediately disarm
51  if (ap.land_complete) {
52  copter.init_disarm_motors();
53  }
54 
55  // set motors to full range
56  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
57 
58  // run brake controller
60 
61  // call attitude controller
62  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), 0.0f);
63 
64  // body-frame rate controller is run directly from 100hz loop
65 
66  // update altitude target and call position controller
69 
70  if (_timeout_ms != 0 && millis()-_timeout_start >= _timeout_ms) {
71  if (!copter.set_mode(LOITER, MODE_REASON_BRAKE_TIMEOUT)) {
73  }
74  }
75 }
76 
77 void Copter::ModeBrake::timeout_to_loiter_ms(uint32_t timeout_ms)
78 {
80  _timeout_ms = timeout_ms;
81 }
uint32_t _timeout_start
Definition: Copter.h:571
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
virtual float get_velocity_z() const=0
uint32_t _timeout_ms
Definition: Copter.h:572
int32_t get_pitch() const
void update_z_controller()
void timeout_to_loiter_ms(uint32_t timeout_ms)
Definition: mode_brake.cpp:77
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
int32_t get_roll() const
void soften_for_landing()
void init_brake_target(float accel_cmss)
bool is_active_z() const
void relax_alt_hold_controllers(float throttle_setting)
#define f(i)
void run() override
Definition: mode_brake.cpp:35
void set_desired_velocity_z(float vel_z_cms)
void set_speed_z(float speed_down, float speed_up)
uint32_t millis()
AC_WPNav *& wp_nav
Definition: Copter.h:118
#define BRAKE_MODE_SPEED_Z
Definition: config.h:558
#define BRAKE_MODE_DECEL_RATE
Definition: config.h:561
void set_accel_z(float accel_cmss)
Definition: defines.h:97
DESIRED_THROTTLE_UNLIMITED
virtual void set_alt_target_from_climb_rate_ff(float climb_rate_cms, float dt, bool force_descend)
AC_PosControl *& pos_control
Definition: Copter.h:120
MOTOR_CLASS *& motors
Definition: Copter.h:124
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float & G_Dt
Definition: Copter.h:129
void update_brake(float ekfGndSpdLimit, float ekfNavVelGainScaler)
float & ekfNavVelGainScaler
Definition: Copter.h:137
AP_InertialNav & inertial_nav
Definition: Copter.h:121
bool init(bool ignore_checks) override
Definition: mode_brake.cpp:8
float & ekfGndSpdLimit
Definition: Copter.h:134
AC_Loiter *& loiter_nav
Definition: Copter.h:119
void set_alt_target_to_current_alt()