APM:Copter
mode_stabilize.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * Init and run calls for stabilize flight mode
5  */
6 
7 // stabilize_init - initialise stabilize controller
8 bool Copter::ModeStabilize::init(bool ignore_checks)
9 {
10  // if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
11  if (motors->armed() && ap.land_complete && !copter.flightmode->has_manual_throttle() &&
13  return false;
14  }
15  // set target altitude to zero for reporting
17 
18  return true;
19 }
20 
21 // stabilize_run - runs the main stabilize controller
22 // should be called at 100hz or more
24 {
25  float target_roll, target_pitch;
26  float target_yaw_rate;
27  float pilot_throttle_scaled;
28 
29  // if not armed set throttle to zero and exit immediately
30  if (!motors->armed() || ap.throttle_zero || !motors->get_interlock()) {
32  return;
33  }
34 
35  // clear landing flag
36  set_land_complete(false);
37 
38  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
39 
40  // apply SIMPLE mode transform to pilot inputs
42 
44 
45  // convert pilot input to lean angles
46  get_pilot_desired_lean_angles(target_roll, target_pitch, aparm.angle_max, aparm.angle_max);
47 
48  // get pilot's desired yaw rate
50 
51  // get pilot's desired throttle
53 
54  // call attitude controller
55  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
56 
57  // body-frame rate controller is run directly from 100hz loop
58 
59  // output pilot's throttle
60  attitude_control->set_throttle_out(pilot_throttle_scaled, true, g.throttle_filt);
61 }
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
virtual void run() override
AP_Float throttle_filt
Definition: Parameters.h:386
void update_simple_mode(void)
Definition: mode.cpp:573
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
float get_non_takeoff_throttle(void)
Definition: mode.cpp:568
int16_t get_control_in() const
virtual bool init(bool ignore_checks) override
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
Definition: mode.cpp:326
float get_pilot_desired_throttle(int16_t throttle_control, float thr_mid=0.0f)
Definition: mode.cpp:563
DESIRED_THROTTLE_UNLIMITED
AC_PosControl *& pos_control
Definition: Copter.h:120
void set_alt_target(float alt_cm)
MOTOR_CLASS *& motors
Definition: Copter.h:124
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
RC_Channel *& channel_yaw
Definition: Copter.h:128
Parameters & g
Definition: Copter.h:116
void set_land_complete(bool b)
Definition: mode.cpp:582
AP_Vehicle::MultiCopter aparm
Definition: Copter.h:205
RC_Channel *& channel_throttle
Definition: Copter.h:127