You can not select more than 25 topics
Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.
182 lines
5.4 KiB
182 lines
5.4 KiB
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- |
|
|
|
/* |
|
* control_auto.pde - init and run calls for auto and guided flight modes |
|
*/ |
|
|
|
// auto_init - initialise auto controller |
|
static bool auto_init(bool ignore_checks) |
|
{ |
|
if ((GPS_ok() && g.command_total > 1) || ignore_checks) { |
|
// set target to current position |
|
wp_nav.init_loiter_target(); |
|
// initialise auto_yaw_mode |
|
set_auto_yaw_mode(get_default_auto_yaw_mode(false)); |
|
// clear the command queues. will be reloaded when "run_autopilot" calls "update_commands" function |
|
init_commands(); |
|
return true; |
|
}else{ |
|
return false; |
|
} |
|
} |
|
|
|
// auto_run - runs the auto controller |
|
// should be called at 100hz or more |
|
// relies on run_autopilot being called at 10hz which handles decision making and non-navigation related commands |
|
static void auto_run() |
|
{ |
|
float target_yaw_rate = 0; |
|
|
|
// if not auto armed set throttle to zero and exit immediately |
|
if(!ap.auto_armed || !inertial_nav.position_ok()) { |
|
wp_nav.init_loiter_target(); |
|
attitude_control.init_targets(); |
|
attitude_control.set_throttle_out(0, false); |
|
return; |
|
} |
|
|
|
// process pilot's yaw input |
|
if (!failsafe.radio) { |
|
// get pilot's desired yaw rate |
|
target_yaw_rate = get_pilot_desired_yaw_rate(g.rc_4.control_in); |
|
if (target_yaw_rate != 0) { |
|
set_auto_yaw_mode(AUTO_YAW_HOLD); |
|
} |
|
} |
|
|
|
// run waypoint controller |
|
wp_nav.update_wpnav(); |
|
|
|
// call z-axis position controller (wpnav should have already updated it's alt target) |
|
pos_control.update_z_controller(); |
|
|
|
// call attitude controller |
|
if (auto_yaw_mode == AUTO_YAW_HOLD) { |
|
// roll & pitch from waypoint controller, yaw rate from pilot |
|
attitude_control.angleef_rp_rateef_y(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate); |
|
}else{ |
|
// roll, pitch from waypoint controller, yaw heading from auto_heading() |
|
attitude_control.angleef_rpy(wp_nav.get_roll(), wp_nav.get_pitch(), get_auto_heading()); |
|
} |
|
|
|
// body-frame rate controller is run directly from 100hz loop |
|
|
|
// refetch angle targets for reporting |
|
const Vector3f angle_target = attitude_control.angle_ef_targets(); |
|
control_roll = angle_target.x; |
|
control_pitch = angle_target.y; |
|
control_yaw = angle_target.z; |
|
} |
|
|
|
// get_default_auto_yaw_mode - returns auto_yaw_mode based on WP_YAW_BEHAVIOR parameter |
|
// set rtl parameter to true if this is during an RTL |
|
uint8_t get_default_auto_yaw_mode(bool rtl) |
|
{ |
|
switch (g.wp_yaw_behavior) { |
|
|
|
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL: |
|
if (rtl) { |
|
return AUTO_YAW_HOLD; |
|
}else{ |
|
return AUTO_YAW_LOOK_AT_NEXT_WP; |
|
} |
|
break; |
|
|
|
case WP_YAW_BEHAVIOR_LOOK_AHEAD: |
|
return AUTO_YAW_LOOK_AHEAD; |
|
break; |
|
|
|
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP: |
|
default: |
|
return AUTO_YAW_LOOK_AT_NEXT_WP; |
|
break; |
|
} |
|
} |
|
|
|
// set_auto_yaw_mode - sets the yaw mode for auto |
|
void set_auto_yaw_mode(uint8_t yaw_mode) |
|
{ |
|
// return immediately if no change |
|
if (auto_yaw_mode == yaw_mode) { |
|
return; |
|
} |
|
auto_yaw_mode = yaw_mode; |
|
|
|
// perform initialisation |
|
switch (auto_yaw_mode) { |
|
|
|
case AUTO_YAW_LOOK_AT_NEXT_WP: |
|
// original_wp_bearing will be set by do_nav_wp or other nav command initialisatoin functions so no init required |
|
break; |
|
|
|
case AUTO_YAW_LOOK_AT_LOCATION: |
|
// point towards a location held in yaw_look_at_WP |
|
yaw_look_at_WP_bearing = ahrs.yaw_sensor; |
|
break; |
|
|
|
case AUTO_YAW_LOOK_AT_HEADING: |
|
// keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed |
|
yaw_look_at_heading = ahrs.yaw_sensor; |
|
break; |
|
|
|
case AUTO_YAW_LOOK_AHEAD: |
|
// Commanded Yaw to automatically look ahead. |
|
yaw_look_ahead_bearing = ahrs.yaw_sensor; |
|
break; |
|
|
|
case AUTO_YAW_RESETTOARMEDYAW: |
|
// initial_armed_bearing will be set during arming so no init required |
|
break; |
|
} |
|
} |
|
|
|
// get_auto_heading - returns target heading depending upon auto_yaw_mode |
|
// 100hz update rate |
|
float get_auto_heading(void) |
|
{ |
|
switch(auto_yaw_mode) { |
|
|
|
case AUTO_YAW_LOOK_AT_LOCATION: |
|
// point towards a location held in yaw_look_at_WP |
|
return get_look_at_yaw(); |
|
break; |
|
|
|
case AUTO_YAW_LOOK_AT_HEADING: |
|
// keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed |
|
return yaw_look_at_heading; |
|
break; |
|
|
|
case AUTO_YAW_LOOK_AHEAD: |
|
// Commanded Yaw to automatically look ahead. |
|
return get_look_ahead_yaw(); |
|
break; |
|
|
|
case AUTO_YAW_RESETTOARMEDYAW: |
|
// changes yaw to be same as when quad was armed |
|
return initial_armed_bearing; |
|
break; |
|
|
|
case AUTO_YAW_LOOK_AT_NEXT_WP: |
|
default: |
|
// point towards next waypoint. |
|
// we don't use wp_bearing because we don't want the copter to turn too much during flight |
|
return original_wp_bearing; |
|
break; |
|
} |
|
} |
|
|
|
// guided_init - initialise guided controller |
|
static bool guided_init(bool ignore_checks) |
|
{ |
|
if (GPS_ok() || ignore_checks) { |
|
return true; |
|
}else{ |
|
return false; |
|
} |
|
} |
|
|
|
// guided_run - runs the guided controller |
|
// should be called at 100hz or more |
|
static void guided_run() |
|
{ |
|
}
|
|
|