APM:Copter
mode_circle.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if MODE_CIRCLE_ENABLED == ENABLED
4 
5 /*
6  * Init and run calls for circle flight mode
7  */
8 
9 // circle_init - initialise circle controller flight mode
10 bool Copter::ModeCircle::init(bool ignore_checks)
11 {
12  if (copter.position_ok() || ignore_checks) {
13  pilot_yaw_override = false;
14 
15  // initialize speeds and accelerations
20 
21  // initialise circle controller including setting the circle center based on vehicle speed
22  copter.circle_nav->init();
23 
24  return true;
25  }else{
26  return false;
27  }
28 }
29 
30 // circle_run - runs the circle flight mode
31 // should be called at 100hz or more
33 {
34  float target_yaw_rate = 0;
35  float target_climb_rate = 0;
36 
37  // initialize speeds and accelerations
42 
43  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
44  if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
45  // To-Do: add some initialisation of position controllers
48  return;
49  }
50 
51  // process pilot inputs
52  if (!copter.failsafe.radio) {
53  // get pilot's desired yaw rate
55  if (!is_zero(target_yaw_rate)) {
56  pilot_yaw_override = true;
57  }
58 
59  // get pilot desired climb rate
61 
62  // check for pilot requested take-off
63  if (ap.land_complete && target_climb_rate > 0) {
64  // indicate we are taking off
65  set_land_complete(false);
66  // clear i term when we're taking off
68  }
69  }
70 
71  // set motors to full range
72  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
73 
74  // run circle controller
75  copter.circle_nav->update();
76 
77  // call attitude controller
78  if (pilot_yaw_override) {
79  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(copter.circle_nav->get_roll(),
80  copter.circle_nav->get_pitch(),
81  target_yaw_rate);
82  }else{
83  attitude_control->input_euler_angle_roll_pitch_yaw(copter.circle_nav->get_roll(),
84  copter.circle_nav->get_pitch(),
85  copter.circle_nav->get_yaw(), true);
86  }
87 
88  // adjust climb rate using rangefinder
89  if (copter.rangefinder_alt_ok()) {
90  // if rangefinder is ok, use surface tracking
91  target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control->get_alt_target(), G_Dt);
92  }
93  // update altitude target and call position controller
94  pos_control->set_alt_target_from_climb_rate(target_climb_rate, G_Dt, false);
96 }
97 
99 {
100  return copter.circle_nav->get_distance_to_target();
101 }
102 
104 {
105  return copter.circle_nav->get_bearing_to_target();
106 }
107 
108 #endif
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
float get_alt_target() const
bool pilot_yaw_override
Definition: Copter.h:602
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt)
Definition: mode.cpp:548
bool init(bool ignore_checks) override
Definition: mode_circle.cpp:10
virtual void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend)
void update_z_controller()
uint16_t get_pilot_speed_dn(void)
Definition: mode.cpp:622
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
float get_pilot_desired_climb_rate(float throttle_control)
Definition: mode.cpp:558
uint32_t wp_distance() const override
Definition: mode_circle.cpp:98
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
float get_speed_xy() const
int16_t get_control_in() const
bool is_zero(const T fVal1)
void set_speed_z(float speed_down, float speed_up)
AC_WPNav *& wp_nav
Definition: Copter.h:118
void set_throttle_takeoff(void)
Definition: mode.cpp:597
void set_accel_z(float accel_cmss)
DESIRED_THROTTLE_UNLIMITED
AC_PosControl *& pos_control
Definition: Copter.h:120
float get_wp_acceleration() const
void run() override
Definition: mode_circle.cpp:32
MOTOR_CLASS *& motors
Definition: Copter.h:124
void set_accel_xy(float accel_cmss)
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float & G_Dt
Definition: Copter.h:129
RC_Channel *& channel_yaw
Definition: Copter.h:128
int32_t wp_bearing() const override
void set_speed_xy(float speed_cms)
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()