mirror of https://github.com/ArduPilot/ardupilot
90 lines
3.2 KiB
C++
90 lines
3.2 KiB
C++
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
#include "Copter.h"
|
|
|
|
/*
|
|
* control_circle.pde - init and run calls for circle flight mode
|
|
*/
|
|
|
|
// circle_init - initialise circle controller flight mode
|
|
bool Copter::circle_init(bool ignore_checks)
|
|
{
|
|
if (position_ok() || ignore_checks) {
|
|
circle_pilot_yaw_override = false;
|
|
|
|
// initialize speeds and accelerations
|
|
pos_control.set_speed_xy(wp_nav.get_speed_xy());
|
|
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
|
|
pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max);
|
|
pos_control.set_accel_z(g.pilot_accel_z);
|
|
|
|
// initialise circle controller including setting the circle center based on vehicle speed
|
|
circle_nav.init();
|
|
|
|
return true;
|
|
}else{
|
|
return false;
|
|
}
|
|
}
|
|
|
|
// circle_run - runs the circle flight mode
|
|
// should be called at 100hz or more
|
|
void Copter::circle_run()
|
|
{
|
|
float target_yaw_rate = 0;
|
|
float target_climb_rate = 0;
|
|
|
|
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
|
|
if(!ap.auto_armed || ap.land_complete || !motors.get_interlock()) {
|
|
// To-Do: add some initialisation of position controllers
|
|
#if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
|
|
// call attitude controller
|
|
attitude_control.angle_ef_roll_pitch_rate_ef_yaw_smooth(0, 0, 0, get_smoothing_gain());
|
|
attitude_control.set_throttle_out(0,false,g.throttle_filt);
|
|
#else // multicopters do not stabilize roll/pitch/yaw when disarmed
|
|
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
|
#endif
|
|
pos_control.set_alt_target_to_current_alt();
|
|
return;
|
|
}
|
|
|
|
// process pilot inputs
|
|
if (!failsafe.radio) {
|
|
// get pilot's desired yaw rate
|
|
target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->control_in);
|
|
if (!is_zero(target_yaw_rate)) {
|
|
circle_pilot_yaw_override = true;
|
|
}
|
|
|
|
// get pilot desired climb rate
|
|
target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->control_in);
|
|
|
|
// check for pilot requested take-off
|
|
if (ap.land_complete && target_climb_rate > 0) {
|
|
// indicate we are taking off
|
|
set_land_complete(false);
|
|
// clear i term when we're taking off
|
|
set_throttle_takeoff();
|
|
}
|
|
}
|
|
|
|
// run circle controller
|
|
circle_nav.update();
|
|
|
|
// call attitude controller
|
|
if (circle_pilot_yaw_override) {
|
|
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), target_yaw_rate);
|
|
}else{
|
|
attitude_control.angle_ef_roll_pitch_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), circle_nav.get_yaw(),true);
|
|
}
|
|
|
|
// run altitude controller
|
|
if (sonar_enabled && (sonar_alt_health >= SONAR_ALT_HEALTH_MAX)) {
|
|
// if sonar is ok, use surface tracking
|
|
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
|
}
|
|
// update altitude target and call position controller
|
|
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt, false);
|
|
pos_control.update_z_controller();
|
|
}
|