APM:Copter
autoyaw.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
4 
5 // roi_yaw - returns heading towards location held in roi
7 {
9  if (roi_yaw_counter >= 4) {
10  roi_yaw_counter = 0;
11  _roi_yaw = get_bearing_cd(copter.inertial_nav.get_position(), roi);
12  }
13 
14  return _roi_yaw;
15 }
16 
18 {
19  const Vector3f& vel = copter.inertial_nav.get_velocity();
20  float speed = norm(vel.x,vel.y);
21  // Commanded Yaw to automatically look ahead.
22  if (copter.position_ok() && (speed > YAW_LOOK_AHEAD_MIN_SPEED)) {
23  _look_ahead_yaw = degrees(atan2f(vel.y,vel.x))*100.0f;
24  }
25  return _look_ahead_yaw;
26 }
27 
29 {
30  set_mode(default_mode(rtl));
31 }
32 
33 // default_mode - returns auto_yaw.mode() based on WP_YAW_BEHAVIOR parameter
34 // set rtl parameter to true if this is during an RTL
36 {
37  switch (copter.g.wp_yaw_behavior) {
38 
40  return AUTO_YAW_HOLD;
41 
43  if (rtl) {
44  return AUTO_YAW_HOLD;
45  } else {
47  }
48 
50  return AUTO_YAW_LOOK_AHEAD;
51 
53  default:
55  }
56 }
57 
58 // set_mode - sets the yaw mode for auto
60 {
61  // return immediately if no change
62  if (_mode == yaw_mode) {
63  return;
64  }
65  _mode = yaw_mode;
66 
67  // perform initialisation
68  switch (_mode) {
69 
71  // wpnav will initialise heading when wpnav's set_destination method is called
72  break;
73 
74  case AUTO_YAW_ROI:
75  // look ahead until we know otherwise
76  _roi_yaw = copter.ahrs.yaw_sensor;
77  break;
78 
79  case AUTO_YAW_FIXED:
80  // keep heading pointing in the direction held in fixed_yaw
81  // caller should set the fixed_yaw
82  break;
83 
85  // Commanded Yaw to automatically look ahead.
86  _look_ahead_yaw = copter.ahrs.yaw_sensor;
87  break;
88 
90  // initial_armed_bearing will be set during arming so no init required
91  break;
92 
93  case AUTO_YAW_RATE:
94  // initialise target yaw rate to zero
95  _rate_cds = 0.0f;
96  break;
97  }
98 }
99 
100 // set_fixed_yaw - sets the yaw look at heading for auto mode
101 void Copter::Mode::AutoYaw::set_fixed_yaw(float angle_deg, float turn_rate_dps, int8_t direction, bool relative_angle)
102 {
103  const int32_t curr_yaw_target = copter.attitude_control->get_att_target_euler_cd().z;
104 
105  // calculate final angle as relative to vehicle heading or absolute
106  if (!relative_angle) {
107  // absolute angle
108  _fixed_yaw = wrap_360_cd(angle_deg * 100);
109  } else {
110  // relative angle
111  if (direction < 0) {
112  angle_deg = -angle_deg;
113  }
114  _fixed_yaw = wrap_360_cd((angle_deg * 100) + curr_yaw_target);
115  }
116 
117  // get turn speed
118  if (is_zero(turn_rate_dps)) {
119  // default to regular auto slew rate
121  } else {
122  const int32_t turn_rate = (wrap_180_cd(_fixed_yaw - curr_yaw_target) / 100) / turn_rate_dps;
123  _fixed_yaw_slewrate = constrain_int32(turn_rate, 1, 360); // deg / sec
124  }
125 
126  // set yaw mode
128 
129  // TO-DO: restore support for clockwise and counter clockwise rotation held in cmd.content.yaw.direction. 1 = clockwise, -1 = counterclockwise
130 }
131 
132 // set_roi - sets the yaw to look at roi for auto mode
133 void Copter::Mode::AutoYaw::set_roi(const Location &roi_location)
134 {
135  // if location is zero lat, lon and altitude turn off ROI
136  if (roi_location.alt == 0 && roi_location.lat == 0 && roi_location.lng == 0) {
137  // set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
139 #if MOUNT == ENABLED
140  // switch off the camera tracking if enabled
141  if (copter.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
142  copter.camera_mount.set_mode_to_default();
143  }
144 #endif // MOUNT == ENABLED
145  } else {
146 #if MOUNT == ENABLED
147  // check if mount type requires us to rotate the quad
148  if (!copter.camera_mount.has_pan_control()) {
149  roi = copter.pv_location_to_vector(roi_location);
151  }
152  // send the command to the camera mount
153  copter.camera_mount.set_roi_target(roi_location);
154 
155  // TO-DO: expand handling of the do_nav_roi to support all modes of the MAVLink. Currently we only handle mode 4 (see below)
156  // 0: do nothing
157  // 1: point at next waypoint
158  // 2: point at a waypoint taken from WP# parameter (2nd parameter?)
159  // 3: point at a location given by alt, lon, lat parameters
160  // 4: point at a target given a target id (can't be implemented)
161 #else
162  // if we have no camera mount aim the quad at the location
163  roi = copter.pv_location_to_vector(roi_location);
165 #endif // MOUNT == ENABLED
166  }
167 }
168 
169 // set auto yaw rate in centi-degrees per second
170 void Copter::Mode::AutoYaw::set_rate(float turn_rate_cds)
171 {
173  _rate_cds = turn_rate_cds;
174 }
175 
176 // yaw - returns target heading depending upon auto_yaw.mode()
178 {
179  switch (_mode) {
180 
181  case AUTO_YAW_ROI:
182  // point towards a location held in roi
183  return roi_yaw();
184 
185  case AUTO_YAW_FIXED:
186  // keep heading pointing in the direction held in fixed_yaw
187  // with no pilot input allowed
188  return _fixed_yaw;
189 
190  case AUTO_YAW_LOOK_AHEAD:
191  // Commanded Yaw to automatically look ahead.
192  return look_ahead_yaw();
193 
195  // changes yaw to be same as when quad was armed
196  return copter.initial_armed_bearing;
197 
199  default:
200  // point towards next waypoint.
201  // we don't use wp_bearing because we don't want the copter to turn too much during flight
202  return copter.wp_nav->get_yaw();
203  }
204 }
205 
206 // returns yaw rate normally set by SET_POSITION_TARGET mavlink
207 // messages (positive is clockwise, negative is counter clockwise)
209 {
210  if (_mode == AUTO_YAW_RATE) {
211  return _rate_cds;
212  }
213 
214  // return zero turn rate (this should never happen)
215  return 0.0f;
216 }
float norm(const T first, const U second, const Params... parameters)
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP
Definition: defines.h:189
void set_mode_to_default(bool rtl)
Definition: autoyaw.cpp:28
#define WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL
Definition: defines.h:190
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
float look_ahead_yaw()
Definition: autoyaw.cpp:17
int32_t _fixed_yaw
Definition: Copter.h:58
void set_fixed_yaw(float angle_deg, float turn_rate_dps, int8_t direction, bool relative_angle)
Definition: autoyaw.cpp:101
#define AUTO_YAW_SLEW_RATE
Definition: config.h:529
autopilot_yaw_mode default_mode(bool rtl) const
Definition: autoyaw.cpp:35
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
int32_t lat
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
uint8_t roi_yaw_counter
Definition: Copter.h:70
#define WP_YAW_BEHAVIOR_LOOK_AHEAD
Definition: defines.h:191
void set_mode(autopilot_yaw_mode new_mode)
Definition: autoyaw.cpp:59
int32_t alt
bool is_zero(const T fVal1)
#define YAW_LOOK_AHEAD_MIN_SPEED
Definition: config.h:533
int32_t constrain_int32(const int32_t amt, const int32_t low, const int32_t high)
float rate_cds() const
Definition: autoyaw.cpp:208
void set_rate(float new_rate_cds)
Definition: autoyaw.cpp:170
float _look_ahead_yaw
Definition: Copter.h:64
int32_t lng
void set_roi(const Location &roi_location)
Definition: autoyaw.cpp:133
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
int16_t _fixed_yaw_slewrate
Definition: Copter.h:61
autopilot_yaw_mode
Definition: defines.h:14
#define degrees(x)
static AutoYaw auto_yaw
Definition: Copter.h:73
#define WP_YAW_BEHAVIOR_NONE
Definition: defines.h:188