APM:Copter
mode_althold.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 
4 /*
5  * Init and run calls for althold, flight mode
6  */
7 
8 // althold_init - initialise althold controller
9 bool Copter::ModeAltHold::init(bool ignore_checks)
10 {
11  // initialise position and desired velocity
12  if (!pos_control->is_active_z()) {
15  }
16 
17  return true;
18 }
19 
20 // althold_run - runs the althold controller
21 // should be called at 100hz or more
23 {
24  AltHoldModeState althold_state;
25  float takeoff_climb_rate = 0.0f;
26 
27  // initialize vertical speeds and acceleration
30 
31  // apply SIMPLE mode transform to pilot inputs
33 
34  // get pilot desired lean angles
35  float target_roll, target_pitch;
36  get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, attitude_control->get_althold_lean_angle_max());
37 
38  // get pilot's desired yaw rate
39  float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
40 
41  // get pilot desired climb rate
42  float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
43  target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), g.pilot_speed_up);
44 
45  // Alt Hold State Machine Determination
46  if (!motors->armed() || !motors->get_interlock()) {
47  althold_state = AltHold_MotorStopped;
48  } else if (takeoff_state.running || takeoff_triggered(target_climb_rate)) {
49  althold_state = AltHold_Takeoff;
50  } else if (!ap.auto_armed || ap.land_complete) {
51  althold_state = AltHold_Landed;
52  } else {
53  althold_state = AltHold_Flying;
54  }
55 
56  // Alt Hold State Machine
57  switch (althold_state) {
58 
60 
61  motors->set_desired_spool_state(AP_Motors::DESIRED_SHUT_DOWN);
62  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
63  attitude_control->reset_rate_controller_I_terms();
64  attitude_control->set_yaw_target_to_current_heading();
65 #if FRAME_CONFIG == HELI_FRAME
66  // force descent rate and call position controller
68  heli_flags.init_targets_on_arming=true;
69 #else
70  pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
71 #endif
73  break;
74 
75  case AltHold_Takeoff:
76 #if FRAME_CONFIG == HELI_FRAME
77  if (heli_flags.init_targets_on_arming) {
78  heli_flags.init_targets_on_arming=false;
79  }
80 #endif
81  // set motors to full range
82  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
83 
84  // initiate take-off
85  if (!takeoff_state.running) {
87  // indicate we are taking off
88  set_land_complete(false);
89  // clear i terms
91  }
92 
93  // get take-off adjusted pilot and takeoff climb rates
94  takeoff_get_climb_rates(target_climb_rate, takeoff_climb_rate);
95 
96  // get avoidance adjusted climb rate
97  target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
98 
99  // call attitude controller
100  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
101 
102  // call position controller
103  pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
104  pos_control->add_takeoff_climb_rate(takeoff_climb_rate, G_Dt);
106  break;
107 
108  case AltHold_Landed:
109  // set motors to spin-when-armed if throttle below deadzone, otherwise full range (but motors will only spin at min throttle)
110  if (target_climb_rate < 0.0f) {
111  motors->set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED);
112  } else {
113  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
114  }
115 
116 #if FRAME_CONFIG == HELI_FRAME
117  if (heli_flags.init_targets_on_arming) {
118  attitude_control->reset_rate_controller_I_terms();
119  attitude_control->set_yaw_target_to_current_heading();
120  if (motors->get_interlock()) {
121  heli_flags.init_targets_on_arming=false;
122  }
123  }
124 #else
125  attitude_control->reset_rate_controller_I_terms();
126  attitude_control->set_yaw_target_to_current_heading();
127 #endif
128  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
129  pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
131  break;
132 
133  case AltHold_Flying:
134  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
135 
136 #if AC_AVOID_ENABLED == ENABLED
137  // apply avoidance
138  copter.avoid.adjust_roll_pitch(target_roll, target_pitch, copter.aparm.angle_max);
139 #endif
140 
141  // call attitude controller
142  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
143 
144  // adjust climb rate using rangefinder
145  if (copter.rangefinder_alt_ok()) {
146  // if rangefinder is ok, use surface tracking
147  target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control->get_alt_target(), G_Dt);
148  }
149 
150  // get avoidance adjusted climb rate
151  target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate);
152 
153  // call position controller
154  pos_control->set_alt_target_from_climb_rate_ff(target_climb_rate, G_Dt, false);
156  break;
157  }
158 }
DESIRED_SPIN_WHEN_ARMED
virtual float get_velocity_z() const=0
float get_alt_target() const
bool takeoff_triggered(float target_climb_rate) const
Definition: mode.cpp:354
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
Definition: mode.cpp:548
void run() override
virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
void takeoff_get_climb_rates(float &pilot_climb_rate, float &takeoff_climb_rate)
Definition: mode.cpp:612
float get_avoidance_adjusted_climbrate(float target_rate)
Definition: mode.cpp:617
void update_z_controller()
uint16_t get_pilot_speed_dn(void)
Definition: mode.cpp:622
void update_simple_mode(void)
Definition: mode.cpp:573
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
float get_pilot_desired_climb_rate(float throttle_control)
Definition: mode.cpp:558
AP_Int16 pilot_speed_up
Definition: Parameters.h:416
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
AP_Int16 pilot_accel_z
Definition: Parameters.h:417
AP_Float pilot_takeoff_alt
Definition: Parameters.h:389
void add_takeoff_climb_rate(float climb_rate_cms, float dt)
bool is_active_z() const
void takeoff_timer_start(float alt_cm)
Definition: mode.cpp:602
int16_t get_control_in() const
AltHoldModeState
Definition: defines.h:235
void relax_alt_hold_controllers(float throttle_setting)
#define f(i)
void set_desired_velocity_z(float vel_z_cms)
AP_Int16 land_speed
Definition: Parameters.h:414
void set_speed_z(float speed_down, float speed_up)
void set_throttle_takeoff(void)
Definition: mode.cpp:597
void set_accel_z(float accel_cmss)
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
Definition: mode.cpp:326
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
takeoff_state_t & takeoff_state
Definition: Copter.h:131
float constrain_float(const float amt, const float low, const float high)
bool init(bool ignore_checks) override
Definition: mode_althold.cpp:9
MOTOR_CLASS *& motors
Definition: Copter.h:124
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float & G_Dt
Definition: Copter.h:129
AP_InertialNav & inertial_nav
Definition: Copter.h:121
RC_Channel *& channel_yaw
Definition: Copter.h:128
Parameters & g
Definition: Copter.h:116
void set_land_complete(bool b)
Definition: mode.cpp:582
RC_Channel *& channel_throttle
Definition: Copter.h:127
void set_alt_target_to_current_alt()